From 4711ca8980eddd33299b6b0cc24650e4481942d0 Mon Sep 17 00:00:00 2001 From: Frank Dellaert Date: Sun, 28 Oct 2018 17:34:41 -0400 Subject: [PATCH 001/869] Added a number of docker images --- docker/ubuntu-gtsam-python-vnc/Dockerfile | 18 ++++ docker/ubuntu-gtsam-python-vnc/bootstrap.sh | 111 ++++++++++++++++++++ docker/ubuntu-gtsam-python-vnc/build.sh | 4 + docker/ubuntu-gtsam-python-vnc/vnc.sh | 5 + docker/ubuntu-gtsam-python/Dockerfile | 29 +++++ docker/ubuntu-gtsam-python/build.sh | 3 + docker/ubuntu-gtsam/Dockerfile | 35 ++++++ docker/ubuntu-gtsam/build.sh | 3 + 8 files changed, 208 insertions(+) create mode 100644 docker/ubuntu-gtsam-python-vnc/Dockerfile create mode 100755 docker/ubuntu-gtsam-python-vnc/bootstrap.sh create mode 100755 docker/ubuntu-gtsam-python-vnc/build.sh create mode 100755 docker/ubuntu-gtsam-python-vnc/vnc.sh create mode 100644 docker/ubuntu-gtsam-python/Dockerfile create mode 100755 docker/ubuntu-gtsam-python/build.sh create mode 100644 docker/ubuntu-gtsam/Dockerfile create mode 100755 docker/ubuntu-gtsam/build.sh diff --git a/docker/ubuntu-gtsam-python-vnc/Dockerfile b/docker/ubuntu-gtsam-python-vnc/Dockerfile new file mode 100644 index 000000000..83222881a --- /dev/null +++ b/docker/ubuntu-gtsam-python-vnc/Dockerfile @@ -0,0 +1,18 @@ +# Get the base Ubuntu/GTSAM image from Docker Hub +FROM dellaert/ubuntu-gtsam-python:bionic + +# Things needed to get a python GUI +ENV DEBIAN_FRONTEND noninteractive +RUN apt-get install -y python-tk +RUN pip install matplotlib + +# Install a VNC X-server, Frame buffer, and windows manager +RUN apt-get install -y x11vnc xvfb fluxbox + +# Finally, install wmctrl needed for bootstrap script +RUN apt-get install -y wmctrl + +# Copy bootstrap script and make sure it runs +COPY bootstrap.sh / + +CMD '/bootstrap.sh' diff --git a/docker/ubuntu-gtsam-python-vnc/bootstrap.sh b/docker/ubuntu-gtsam-python-vnc/bootstrap.sh new file mode 100755 index 000000000..21356138f --- /dev/null +++ b/docker/ubuntu-gtsam-python-vnc/bootstrap.sh @@ -0,0 +1,111 @@ +#!/bin/bash + +# Based on: http://www.richud.com/wiki/Ubuntu_Fluxbox_GUI_with_x11vnc_and_Xvfb + +main() { + log_i "Starting xvfb virtual display..." + launch_xvfb + log_i "Starting window manager..." + launch_window_manager + log_i "Starting VNC server..." + run_vnc_server +} + +launch_xvfb() { + local xvfbLockFilePath="/tmp/.X1-lock" + if [ -f "${xvfbLockFilePath}" ] + then + log_i "Removing xvfb lock file '${xvfbLockFilePath}'..." + if ! rm -v "${xvfbLockFilePath}" + then + log_e "Failed to remove xvfb lock file" + exit 1 + fi + fi + + # Set defaults if the user did not specify envs. + export DISPLAY=${XVFB_DISPLAY:-:1} + local screen=${XVFB_SCREEN:-0} + local resolution=${XVFB_RESOLUTION:-1280x960x24} + local timeout=${XVFB_TIMEOUT:-5} + + # Start and wait for either Xvfb to be fully up or we hit the timeout. + Xvfb ${DISPLAY} -screen ${screen} ${resolution} & + local loopCount=0 + until xdpyinfo -display ${DISPLAY} > /dev/null 2>&1 + do + loopCount=$((loopCount+1)) + sleep 1 + if [ ${loopCount} -gt ${timeout} ] + then + log_e "xvfb failed to start" + exit 1 + fi + done +} + +launch_window_manager() { + local timeout=${XVFB_TIMEOUT:-5} + + # Start and wait for either fluxbox to be fully up or we hit the timeout. + fluxbox & + local loopCount=0 + until wmctrl -m > /dev/null 2>&1 + do + loopCount=$((loopCount+1)) + sleep 1 + if [ ${loopCount} -gt ${timeout} ] + then + log_e "fluxbox failed to start" + exit 1 + fi + done +} + +run_vnc_server() { + local passwordArgument='-nopw' + + if [ -n "${VNC_SERVER_PASSWORD}" ] + then + local passwordFilePath="${HOME}/.x11vnc.pass" + if ! x11vnc -storepasswd "${VNC_SERVER_PASSWORD}" "${passwordFilePath}" + then + log_e "Failed to store x11vnc password" + exit 1 + fi + passwordArgument=-"-rfbauth ${passwordFilePath}" + log_i "The VNC server will ask for a password" + else + log_w "The VNC server will NOT ask for a password" + fi + + x11vnc -ncache 10 -ncache_cr -display ${DISPLAY} -forever ${passwordArgument} & + wait $! +} + +log_i() { + log "[INFO] ${@}" +} + +log_w() { + log "[WARN] ${@}" +} + +log_e() { + log "[ERROR] ${@}" +} + +log() { + echo "[$(date '+%Y-%m-%d %H:%M:%S')] ${@}" +} + +control_c() { + echo "" + exit +} + +trap control_c SIGINT SIGTERM SIGHUP + +main + +exit diff --git a/docker/ubuntu-gtsam-python-vnc/build.sh b/docker/ubuntu-gtsam-python-vnc/build.sh new file mode 100755 index 000000000..8d280252f --- /dev/null +++ b/docker/ubuntu-gtsam-python-vnc/build.sh @@ -0,0 +1,4 @@ +# Build command for Docker image +# TODO(dellaert): use docker compose and/or cmake +# Needs to be run in docker/ubuntu-gtsam-python-vnc directory +docker build -t dellaert/ubuntu-gtsam-python-vnc:bionic . diff --git a/docker/ubuntu-gtsam-python-vnc/vnc.sh b/docker/ubuntu-gtsam-python-vnc/vnc.sh new file mode 100755 index 000000000..c0ab692c6 --- /dev/null +++ b/docker/ubuntu-gtsam-python-vnc/vnc.sh @@ -0,0 +1,5 @@ +# After running this script, connect VNC client to 0.0.0.0:5900 +docker run -it \ + --workdir="/usr/src/gtsam" \ + -p 5900:5900 \ + dellaert/ubuntu-gtsam-python-vnc:bionic \ No newline at end of file diff --git a/docker/ubuntu-gtsam-python/Dockerfile b/docker/ubuntu-gtsam-python/Dockerfile new file mode 100644 index 000000000..0c7d131be --- /dev/null +++ b/docker/ubuntu-gtsam-python/Dockerfile @@ -0,0 +1,29 @@ +# Get the base Ubuntu/GTSAM image from Docker Hub +FROM dellaert/ubuntu-gtsam:bionic + +# Install pip +RUN apt-get install -y python-pip python-dev + +# Install python wrapper requirements +RUN pip install -r /usr/src/gtsam/cython/requirements.txt + +# Run cmake again, now with cython toolbox on +WORKDIR /usr/src/gtsam/build +RUN cmake \ + -DCMAKE_BUILD_TYPE=Release \ + -DGTSAM_USE_SYSTEM_EIGEN=ON \ + -DGTSAM_WITH_EIGEN_MKL=OFF \ + -DGTSAM_BUILD_EXAMPLES_ALWAYS=OFF \ + -DGTSAM_BUILD_TIMING_ALWAYS=OFF \ + -DGTSAM_BUILD_TESTS=OFF \ + -DGTSAM_INSTALL_CYTHON_TOOLBOX=ON \ + .. + +# Build again, as ubuntu-gtsam image cleaned +RUN make -j3 install && make clean + +# Needed to run python wrapper: +RUN echo 'export PYTHONPATH=/usr/local/cython/' >> /root/.bashrc + +# Run bash +CMD ["bash"] diff --git a/docker/ubuntu-gtsam-python/build.sh b/docker/ubuntu-gtsam-python/build.sh new file mode 100755 index 000000000..1696f6c61 --- /dev/null +++ b/docker/ubuntu-gtsam-python/build.sh @@ -0,0 +1,3 @@ +# Build command for Docker image +# TODO(dellaert): use docker compose and/or cmake +docker build --no-cache -t dellaert/ubuntu-gtsam-python:bionic . diff --git a/docker/ubuntu-gtsam/Dockerfile b/docker/ubuntu-gtsam/Dockerfile new file mode 100644 index 000000000..bdfa8d9a5 --- /dev/null +++ b/docker/ubuntu-gtsam/Dockerfile @@ -0,0 +1,35 @@ +# Get the base Ubuntu image from Docker Hub +FROM dellaert/ubuntu-boost-tbb-eigen3:bionic + +# Install git +RUN apt-get update && \ + apt-get install -y git + +# Install compiler +RUN apt-get install -y build-essential + +# Clone GTSAM +WORKDIR /usr/src/ +RUN git clone https://bitbucket.org/gtborg/gtsam.git + +# Run cmake +RUN mkdir /usr/src/gtsam/build +WORKDIR /usr/src/gtsam/build +RUN cmake \ + -DCMAKE_BUILD_TYPE=Release \ + -DGTSAM_USE_SYSTEM_EIGEN=ON \ + -DGTSAM_WITH_EIGEN_MKL=OFF \ + -DGTSAM_BUILD_EXAMPLES_ALWAYS=OFF \ + -DGTSAM_BUILD_TIMING_ALWAYS=OFF \ + -DGTSAM_BUILD_TESTS=OFF \ + -DGTSAM_INSTALL_CYTHON_TOOLBOX=OFF \ + .. + +# Build +RUN make -j3 install && make clean + +# Needed to link with GTSAM +RUN echo 'export LD_LIBRARY_PATH=/usr/local/lib' >> /root/.bashrc + +# Run bash +CMD ["bash"] diff --git a/docker/ubuntu-gtsam/build.sh b/docker/ubuntu-gtsam/build.sh new file mode 100755 index 000000000..bf545e9c2 --- /dev/null +++ b/docker/ubuntu-gtsam/build.sh @@ -0,0 +1,3 @@ +# Build command for Docker image +# TODO(dellaert): use docker compose and/or cmake +docker build --no-cache -t dellaert/ubuntu-gtsam:bionic . From b84c6efe51949cb5c248b4c989a0a0239fe6d535 Mon Sep 17 00:00:00 2001 From: Ellon Paiva Mendes Date: Thu, 3 Oct 2019 13:56:26 +0200 Subject: [PATCH 002/869] Bump version to 4.0.2 --- CMakeLists.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index b0457cb1c..1c9f0639a 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -10,7 +10,7 @@ endif() # Set the version number for the library set (GTSAM_VERSION_MAJOR 4) set (GTSAM_VERSION_MINOR 0) -set (GTSAM_VERSION_PATCH 0) +set (GTSAM_VERSION_PATCH 2) math (EXPR GTSAM_VERSION_NUMERIC "10000 * ${GTSAM_VERSION_MAJOR} + 100 * ${GTSAM_VERSION_MINOR} + ${GTSAM_VERSION_PATCH}") set (GTSAM_VERSION_STRING "${GTSAM_VERSION_MAJOR}.${GTSAM_VERSION_MINOR}.${GTSAM_VERSION_PATCH}") From 0760858aab942c03b438cfbfe89cab326d83cfb4 Mon Sep 17 00:00:00 2001 From: Ellon Paiva Mendes Date: Thu, 3 Oct 2019 17:45:58 +0200 Subject: [PATCH 003/869] Install GTSAMConfigVersion.cmake --- cmake/GtsamMakeConfigFile.cmake | 28 ++++++++++++++++++++++++++-- gtsam_extra.cmake.in | 5 ++--- 2 files changed, 28 insertions(+), 5 deletions(-) diff --git a/cmake/GtsamMakeConfigFile.cmake b/cmake/GtsamMakeConfigFile.cmake index 74081b58a..2fff888ef 100644 --- a/cmake/GtsamMakeConfigFile.cmake +++ b/cmake/GtsamMakeConfigFile.cmake @@ -20,13 +20,37 @@ function(GtsamMakeConfigFile PACKAGE_NAME) set(EXTRA_FILE "_does_not_exist_") endif() + # GTSAM defines its version variable as GTSAM_VERSION_STRING while other + # projects may define it as _VERSION. Since this file is + # installed on the system as part of GTSAMCMakeTools and may be useful in + # external projects, we need to handle both cases of version variable naming + # here. + if(NOT DEFINED ${PACKAGE_NAME}_VERSION AND DEFINED ${PACKAGE_NAME}_VERSION_STRING) + set(${PACKAGE_NAME}_VERSION ${${PACKAGE_NAME}_VERSION_STRING}) + endif() + + # Version file + include(CMakePackageConfigHelpers) + write_basic_package_version_file( + "${PROJECT_BINARY_DIR}/${PACKAGE_NAME}ConfigVersion.cmake" + VERSION ${${PACKAGE_NAME}_VERSION} + COMPATIBILITY SameMajorVersion + ) + + # Config file file(RELATIVE_PATH CONF_REL_INCLUDE_DIR "${CMAKE_INSTALL_PREFIX}/${DEF_INSTALL_CMAKE_DIR}" "${CMAKE_INSTALL_PREFIX}/include") file(RELATIVE_PATH CONF_REL_LIB_DIR "${CMAKE_INSTALL_PREFIX}/${DEF_INSTALL_CMAKE_DIR}" "${CMAKE_INSTALL_PREFIX}/lib") configure_file(${GTSAM_CONFIG_TEMPLATE_PATH}/Config.cmake.in "${PROJECT_BINARY_DIR}/${PACKAGE_NAME}Config.cmake" @ONLY) message(STATUS "Wrote ${PROJECT_BINARY_DIR}/${PACKAGE_NAME}Config.cmake") - # Install config and exports files (for find scripts) - install(FILES "${PROJECT_BINARY_DIR}/${PACKAGE_NAME}Config.cmake" DESTINATION "${CMAKE_INSTALL_PREFIX}/${DEF_INSTALL_CMAKE_DIR}") + # Install config, version and exports files (for find scripts) + install( + FILES + "${PROJECT_BINARY_DIR}/${PACKAGE_NAME}Config.cmake" + "${PROJECT_BINARY_DIR}/${PACKAGE_NAME}ConfigVersion.cmake" + DESTINATION + "${CMAKE_INSTALL_PREFIX}/${DEF_INSTALL_CMAKE_DIR}" + ) install(EXPORT ${PACKAGE_NAME}-exports DESTINATION ${DEF_INSTALL_CMAKE_DIR}) endfunction() diff --git a/gtsam_extra.cmake.in b/gtsam_extra.cmake.in index b7990b3cc..8a9a13648 100644 --- a/gtsam_extra.cmake.in +++ b/gtsam_extra.cmake.in @@ -1,8 +1,7 @@ # Extra CMake definitions for GTSAM -set (GTSAM_VERSION_MAJOR @GTSAM_VERSION_MAJOR@) -set (GTSAM_VERSION_MINOR @GTSAM_VERSION_MINOR@) -set (GTSAM_VERSION_PATCH @GTSAM_VERSION_PATCH@) +# All version variables are handled by GTSAMConfigVersion.cmake, except these +# two below. We continue to set them here in case someone uses them set (GTSAM_VERSION_NUMERIC @GTSAM_VERSION_NUMERIC@) set (GTSAM_VERSION_STRING "@GTSAM_VERSION_STRING@") From 0aaf496b6dae7e7e7785e1886e81b95539855d1e Mon Sep 17 00:00:00 2001 From: Jose Luis Blanco-Claraco Date: Mon, 7 Oct 2019 11:15:31 +0200 Subject: [PATCH 004/869] Remove obsolete cmake FindXX modules. Exported config files are preferred over modules, and easier to maintain. --- cmake/obsolete/FindGTSAM.cmake | 88 ------------------------- cmake/obsolete/FindGTSAM_UNSTABLE.cmake | 88 ------------------------- 2 files changed, 176 deletions(-) delete mode 100644 cmake/obsolete/FindGTSAM.cmake delete mode 100644 cmake/obsolete/FindGTSAM_UNSTABLE.cmake diff --git a/cmake/obsolete/FindGTSAM.cmake b/cmake/obsolete/FindGTSAM.cmake deleted file mode 100644 index 895eb853b..000000000 --- a/cmake/obsolete/FindGTSAM.cmake +++ /dev/null @@ -1,88 +0,0 @@ -# This is FindGTSAM.cmake -# DEPRECIATED: Use config file approach to pull in targets from gtsam -# CMake module to locate the GTSAM package -# -# The following cache variables may be set before calling this script: -# -# GTSAM_DIR (or GTSAM_ROOT): (Optional) The install prefix OR source tree of gtsam (e.g. /usr/local or src/gtsam) -# GTSAM_BUILD_NAME: (Optional) If compiling against a source tree, the name of the build directory -# within it (e.g build-debug). Without this defined, this script tries to -# intelligently find the build directory based on the project's build directory name -# or based on the build type (Debug/Release/etc). -# -# The following variables will be defined: -# -# GTSAM_FOUND : TRUE if the package has been successfully found -# GTSAM_INCLUDE_DIR : paths to GTSAM's INCLUDE directories -# GTSAM_LIBS : paths to GTSAM's libraries -# -# NOTES on compiling against an uninstalled GTSAM build tree: -# - A GTSAM source tree will be automatically searched for in the directory -# 'gtsam' next to your project directory, after searching -# CMAKE_INSTALL_PREFIX and $HOME, but before searching /usr/local and /usr. -# - The build directory will be searched first with the same name as your -# project's build directory, e.g. if you build from 'MyProject/build-optimized', -# 'gtsam/build-optimized' will be searched first. Next, a build directory for -# your project's build type, e.g. if CMAKE_BUILD_TYPE in your project is -# 'Release', then 'gtsam/build-release' will be searched next. Finally, plain -# 'gtsam/build' will be searched. -# - You can control the gtsam build directory name directly by defining the CMake -# cache variable 'GTSAM_BUILD_NAME', then only 'gtsam/${GTSAM_BUILD_NAME} will -# be searched. -# - Use the standard CMAKE_PREFIX_PATH, or GTSAM_DIR, to find a specific gtsam -# directory. - -# Get path suffixes to help look for gtsam -if(GTSAM_BUILD_NAME) - set(gtsam_build_names "${GTSAM_BUILD_NAME}/gtsam") -else() - # lowercase build type - string(TOLOWER "${CMAKE_BUILD_TYPE}" build_type_suffix) - # build suffix of this project - get_filename_component(my_build_name "${CMAKE_BINARY_DIR}" NAME) - - set(gtsam_build_names "${my_build_name}/gtsam" "build-${build_type_suffix}/gtsam" "build/gtsam") -endif() - -# Use GTSAM_ROOT or GTSAM_DIR equivalently -if(GTSAM_ROOT AND NOT GTSAM_DIR) - set(GTSAM_DIR "${GTSAM_ROOT}") -endif() - -if(GTSAM_DIR) - # Find include dirs - find_path(GTSAM_INCLUDE_DIR gtsam/inference/FactorGraph.h - PATHS "${GTSAM_DIR}/include" "${GTSAM_DIR}" NO_DEFAULT_PATH - DOC "GTSAM include directories") - - # Find libraries - find_library(GTSAM_LIBS NAMES gtsam - HINTS "${GTSAM_DIR}/lib" "${GTSAM_DIR}" NO_DEFAULT_PATH - PATH_SUFFIXES ${gtsam_build_names} - DOC "GTSAM libraries") -else() - # Find include dirs - set(extra_include_paths ${CMAKE_INSTALL_PREFIX}/include "$ENV{HOME}/include" "${PROJECT_SOURCE_DIR}/../gtsam" /usr/local/include /usr/include) - find_path(GTSAM_INCLUDE_DIR gtsam/inference/FactorGraph.h - PATHS ${extra_include_paths} - DOC "GTSAM include directories") - if(NOT GTSAM_INCLUDE_DIR) - message(STATUS "Searched for gtsam headers in default paths plus ${extra_include_paths}") - endif() - - # Find libraries - find_library(GTSAM_LIBS NAMES gtsam - HINTS ${CMAKE_INSTALL_PREFIX}/lib "$ENV{HOME}/lib" "${PROJECT_SOURCE_DIR}/../gtsam" /usr/local/lib /usr/lib - PATH_SUFFIXES ${gtsam_build_names} - DOC "GTSAM libraries") -endif() - -# handle the QUIETLY and REQUIRED arguments and set GTSAM_FOUND to TRUE -# if all listed variables are TRUE -include(FindPackageHandleStandardArgs) -find_package_handle_standard_args(GTSAM DEFAULT_MSG - GTSAM_LIBS GTSAM_INCLUDE_DIR) - - - - diff --git a/cmake/obsolete/FindGTSAM_UNSTABLE.cmake b/cmake/obsolete/FindGTSAM_UNSTABLE.cmake deleted file mode 100644 index 42cc9c8b0..000000000 --- a/cmake/obsolete/FindGTSAM_UNSTABLE.cmake +++ /dev/null @@ -1,88 +0,0 @@ -# This is FindGTSAM_UNSTABLE.cmake -# DEPRECIATED: Use config file approach to pull in targets from gtsam -# CMake module to locate the GTSAM_UNSTABLE package -# -# The following cache variables may be set before calling this script: -# -# GTSAM_UNSTABLE_DIR (or GTSAM_UNSTABLE_ROOT): (Optional) The install prefix OR source tree of gtsam_unstable (e.g. /usr/local or src/gtsam_unstable) -# GTSAM_UNSTABLE_BUILD_NAME: (Optional) If compiling against a source tree, the name of the build directory -# within it (e.g build-debug). Without this defined, this script tries to -# intelligently find the build directory based on the project's build directory name -# or based on the build type (Debug/Release/etc). -# -# The following variables will be defined: -# -# GTSAM_UNSTABLE_FOUND : TRUE if the package has been successfully found -# GTSAM_UNSTABLE_INCLUDE_DIR : paths to GTSAM_UNSTABLE's INCLUDE directories -# GTSAM_UNSTABLE_LIBS : paths to GTSAM_UNSTABLE's libraries -# -# NOTES on compiling against an uninstalled GTSAM_UNSTABLE build tree: -# - A GTSAM_UNSTABLE source tree will be automatically searched for in the directory -# 'gtsam_unstable' next to your project directory, after searching -# CMAKE_INSTALL_PREFIX and $HOME, but before searching /usr/local and /usr. -# - The build directory will be searched first with the same name as your -# project's build directory, e.g. if you build from 'MyProject/build-optimized', -# 'gtsam_unstable/build-optimized' will be searched first. Next, a build directory for -# your project's build type, e.g. if CMAKE_BUILD_TYPE in your project is -# 'Release', then 'gtsam_unstable/build-release' will be searched next. Finally, plain -# 'gtsam_unstable/build' will be searched. -# - You can control the gtsam build directory name directly by defining the CMake -# cache variable 'GTSAM_UNSTABLE_BUILD_NAME', then only 'gtsam/${GTSAM_UNSTABLE_BUILD_NAME} will -# be searched. -# - Use the standard CMAKE_PREFIX_PATH, or GTSAM_UNSTABLE_DIR, to find a specific gtsam -# directory. - -# Get path suffixes to help look for gtsam_unstable -if(GTSAM_UNSTABLE_BUILD_NAME) - set(gtsam_unstable_build_names "${GTSAM_UNSTABLE_BUILD_NAME}/gtsam_unstable") -else() - # lowercase build type - string(TOLOWER "${CMAKE_BUILD_TYPE}" build_type_suffix) - # build suffix of this project - get_filename_component(my_build_name "${CMAKE_BINARY_DIR}" NAME) - - set(gtsam_unstable_build_names "${my_build_name}/gtsam_unstable" "build-${build_type_suffix}/gtsam_unstable" "build/gtsam_unstable") -endif() - -# Use GTSAM_UNSTABLE_ROOT or GTSAM_UNSTABLE_DIR equivalently -if(GTSAM_UNSTABLE_ROOT AND NOT GTSAM_UNSTABLE_DIR) - set(GTSAM_UNSTABLE_DIR "${GTSAM_UNSTABLE_ROOT}") -endif() - -if(GTSAM_UNSTABLE_DIR) - # Find include dirs - find_path(GTSAM_UNSTABLE_INCLUDE_DIR gtsam_unstable/base/DSF.h - PATHS "${GTSAM_UNSTABLE_DIR}/include" "${GTSAM_UNSTABLE_DIR}" NO_DEFAULT_PATH - DOC "GTSAM_UNSTABLE include directories") - - # Find libraries - find_library(GTSAM_UNSTABLE_LIBS NAMES gtsam_unstable - HINTS "${GTSAM_UNSTABLE_DIR}/lib" "${GTSAM_UNSTABLE_DIR}" NO_DEFAULT_PATH - PATH_SUFFIXES ${gtsam_unstable_build_names} - DOC "GTSAM_UNSTABLE libraries") -else() - # Find include dirs - set(extra_include_paths ${CMAKE_INSTALL_PREFIX}/include "$ENV{HOME}/include" "${PROJECT_SOURCE_DIR}/../gtsam" /usr/local/include /usr/include) - find_path(GTSAM_UNSTABLE_INCLUDE_DIR gtsam_unstable/base/DSF.h - PATHS ${extra_include_paths} - DOC "GTSAM_UNSTABLE include directories") - if(NOT GTSAM_UNSTABLE_INCLUDE_DIR) - message(STATUS "Searched for gtsam_unstable headers in default paths plus ${extra_include_paths}") - endif() - - # Find libraries - find_library(GTSAM_UNSTABLE_LIBS NAMES gtsam_unstable - HINTS ${CMAKE_INSTALL_PREFIX}/lib "$ENV{HOME}/lib" "${PROJECT_SOURCE_DIR}/../gtsam" /usr/local/lib /usr/lib - PATH_SUFFIXES ${gtsam_unstable_build_names} - DOC "GTSAM_UNSTABLE libraries") -endif() - -# handle the QUIETLY and REQUIRED arguments and set GTSAM_UNSTABLE_FOUND to TRUE -# if all listed variables are TRUE -include(FindPackageHandleStandardArgs) -find_package_handle_standard_args(GTSAM_UNSTABLE DEFAULT_MSG - GTSAM_UNSTABLE_LIBS GTSAM_UNSTABLE_INCLUDE_DIR) - - - - From cf76820cab3f6e0427568cc63ed9059af4563567 Mon Sep 17 00:00:00 2001 From: Fan Jiang Date: Thu, 23 Jan 2020 15:25:12 -0500 Subject: [PATCH 005/869] Add pybind11 --- wrap/python/pybind11/.appveyor.yml | 70 + wrap/python/pybind11/.gitignore | 38 + wrap/python/pybind11/.gitmodules | 3 + wrap/python/pybind11/.readthedocs.yml | 3 + wrap/python/pybind11/.travis.yml | 280 +++ wrap/python/pybind11/CMakeLists.txt | 157 ++ wrap/python/pybind11/CONTRIBUTING.md | 49 + wrap/python/pybind11/ISSUE_TEMPLATE.md | 17 + wrap/python/pybind11/LICENSE | 29 + wrap/python/pybind11/MANIFEST.in | 2 + wrap/python/pybind11/README.md | 129 + wrap/python/pybind11/docs/Doxyfile | 20 + .../pybind11/docs/_static/theme_overrides.css | 11 + .../pybind11/docs/advanced/cast/chrono.rst | 81 + .../pybind11/docs/advanced/cast/custom.rst | 91 + .../pybind11/docs/advanced/cast/eigen.rst | 310 +++ .../docs/advanced/cast/functional.rst | 109 + .../pybind11/docs/advanced/cast/index.rst | 42 + .../pybind11/docs/advanced/cast/overview.rst | 165 ++ .../pybind11/docs/advanced/cast/stl.rst | 240 ++ .../pybind11/docs/advanced/cast/strings.rst | 305 +++ .../python/pybind11/docs/advanced/classes.rst | 1125 +++++++++ .../pybind11/docs/advanced/embedding.rst | 261 ++ .../pybind11/docs/advanced/exceptions.rst | 142 ++ .../pybind11/docs/advanced/functions.rst | 507 ++++ wrap/python/pybind11/docs/advanced/misc.rst | 306 +++ .../pybind11/docs/advanced/pycpp/index.rst | 13 + .../pybind11/docs/advanced/pycpp/numpy.rst | 386 +++ .../pybind11/docs/advanced/pycpp/object.rst | 170 ++ .../docs/advanced/pycpp/utilities.rst | 144 ++ .../pybind11/docs/advanced/smart_ptrs.rst | 173 ++ wrap/python/pybind11/docs/basics.rst | 293 +++ wrap/python/pybind11/docs/benchmark.py | 88 + wrap/python/pybind11/docs/benchmark.rst | 97 + wrap/python/pybind11/docs/changelog.rst | 1158 +++++++++ wrap/python/pybind11/docs/classes.rst | 521 ++++ wrap/python/pybind11/docs/compiling.rst | 289 +++ wrap/python/pybind11/docs/conf.py | 332 +++ wrap/python/pybind11/docs/faq.rst | 297 +++ wrap/python/pybind11/docs/index.rst | 47 + wrap/python/pybind11/docs/intro.rst | 93 + wrap/python/pybind11/docs/limitations.rst | 20 + wrap/python/pybind11/docs/pybind11-logo.png | Bin 0 -> 58510 bytes .../docs/pybind11_vs_boost_python1.png | Bin 0 -> 44653 bytes .../docs/pybind11_vs_boost_python1.svg | 427 ++++ .../docs/pybind11_vs_boost_python2.png | Bin 0 -> 41121 bytes .../docs/pybind11_vs_boost_python2.svg | 427 ++++ wrap/python/pybind11/docs/reference.rst | 117 + wrap/python/pybind11/docs/release.rst | 25 + wrap/python/pybind11/docs/requirements.txt | 1 + wrap/python/pybind11/docs/upgrade.rst | 404 +++ wrap/python/pybind11/include/pybind11/attr.h | 493 ++++ .../pybind11/include/pybind11/buffer_info.h | 108 + wrap/python/pybind11/include/pybind11/cast.h | 2128 ++++++++++++++++ .../python/pybind11/include/pybind11/chrono.h | 162 ++ .../python/pybind11/include/pybind11/common.h | 2 + .../pybind11/include/pybind11/complex.h | 65 + .../pybind11/include/pybind11/detail/class.h | 623 +++++ .../pybind11/include/pybind11/detail/common.h | 807 ++++++ .../pybind11/include/pybind11/detail/descr.h | 100 + .../pybind11/include/pybind11/detail/init.h | 335 +++ .../include/pybind11/detail/internals.h | 291 +++ .../pybind11/include/pybind11/detail/typeid.h | 55 + wrap/python/pybind11/include/pybind11/eigen.h | 607 +++++ wrap/python/pybind11/include/pybind11/embed.h | 200 ++ wrap/python/pybind11/include/pybind11/eval.h | 117 + .../pybind11/include/pybind11/functional.h | 94 + .../pybind11/include/pybind11/iostream.h | 207 ++ wrap/python/pybind11/include/pybind11/numpy.h | 1610 ++++++++++++ .../pybind11/include/pybind11/operators.h | 168 ++ .../pybind11/include/pybind11/options.h | 65 + .../pybind11/include/pybind11/pybind11.h | 2162 +++++++++++++++++ .../pybind11/include/pybind11/pytypes.h | 1471 +++++++++++ wrap/python/pybind11/include/pybind11/stl.h | 386 +++ .../pybind11/include/pybind11/stl_bind.h | 630 +++++ wrap/python/pybind11/pybind11/__init__.py | 28 + wrap/python/pybind11/pybind11/__main__.py | 37 + wrap/python/pybind11/pybind11/_version.py | 2 + wrap/python/pybind11/setup.cfg | 12 + wrap/python/pybind11/setup.py | 108 + wrap/python/pybind11/tests/CMakeLists.txt | 239 ++ wrap/python/pybind11/tests/conftest.py | 239 ++ .../python/pybind11/tests/constructor_stats.h | 276 +++ wrap/python/pybind11/tests/local_bindings.h | 64 + wrap/python/pybind11/tests/object.h | 175 ++ .../tests/pybind11_cross_module_tests.cpp | 123 + wrap/python/pybind11/tests/pybind11_tests.cpp | 93 + wrap/python/pybind11/tests/pybind11_tests.h | 65 + wrap/python/pybind11/tests/pytest.ini | 16 + wrap/python/pybind11/tests/test_buffers.cpp | 169 ++ wrap/python/pybind11/tests/test_buffers.py | 87 + .../pybind11/tests/test_builtin_casters.cpp | 170 ++ .../pybind11/tests/test_builtin_casters.py | 342 +++ .../pybind11/tests/test_call_policies.cpp | 100 + .../pybind11/tests/test_call_policies.py | 187 ++ wrap/python/pybind11/tests/test_callbacks.cpp | 168 ++ wrap/python/pybind11/tests/test_callbacks.py | 136 ++ wrap/python/pybind11/tests/test_chrono.cpp | 55 + wrap/python/pybind11/tests/test_chrono.py | 107 + wrap/python/pybind11/tests/test_class.cpp | 422 ++++ wrap/python/pybind11/tests/test_class.py | 281 +++ .../tests/test_cmake_build/CMakeLists.txt | 58 + .../pybind11/tests/test_cmake_build/embed.cpp | 21 + .../installed_embed/CMakeLists.txt | 15 + .../installed_function/CMakeLists.txt | 12 + .../installed_target/CMakeLists.txt | 22 + .../pybind11/tests/test_cmake_build/main.cpp | 6 + .../subdirectory_embed/CMakeLists.txt | 25 + .../subdirectory_function/CMakeLists.txt | 8 + .../subdirectory_target/CMakeLists.txt | 15 + .../pybind11/tests/test_cmake_build/test.py | 5 + .../tests/test_constants_and_functions.cpp | 127 + .../tests/test_constants_and_functions.py | 39 + wrap/python/pybind11/tests/test_copy_move.cpp | 213 ++ wrap/python/pybind11/tests/test_copy_move.py | 112 + .../pybind11/tests/test_docstring_options.cpp | 61 + .../pybind11/tests/test_docstring_options.py | 38 + wrap/python/pybind11/tests/test_eigen.cpp | 329 +++ wrap/python/pybind11/tests/test_eigen.py | 694 ++++++ .../pybind11/tests/test_embed/CMakeLists.txt | 41 + .../pybind11/tests/test_embed/catch.cpp | 22 + .../tests/test_embed/external_module.cpp | 23 + .../tests/test_embed/test_interpreter.cpp | 284 +++ .../tests/test_embed/test_interpreter.py | 9 + wrap/python/pybind11/tests/test_enum.cpp | 85 + wrap/python/pybind11/tests/test_enum.py | 167 ++ wrap/python/pybind11/tests/test_eval.cpp | 91 + wrap/python/pybind11/tests/test_eval.py | 17 + wrap/python/pybind11/tests/test_eval_call.py | 4 + .../python/pybind11/tests/test_exceptions.cpp | 196 ++ wrap/python/pybind11/tests/test_exceptions.py | 146 ++ .../tests/test_factory_constructors.cpp | 338 +++ .../tests/test_factory_constructors.py | 459 ++++ .../python/pybind11/tests/test_gil_scoped.cpp | 44 + wrap/python/pybind11/tests/test_gil_scoped.py | 80 + wrap/python/pybind11/tests/test_iostream.cpp | 73 + wrap/python/pybind11/tests/test_iostream.py | 214 ++ .../tests/test_kwargs_and_defaults.cpp | 102 + .../tests/test_kwargs_and_defaults.py | 147 ++ .../pybind11/tests/test_local_bindings.cpp | 101 + .../pybind11/tests/test_local_bindings.py | 226 ++ .../tests/test_methods_and_attributes.cpp | 454 ++++ .../tests/test_methods_and_attributes.py | 512 ++++ wrap/python/pybind11/tests/test_modules.cpp | 98 + wrap/python/pybind11/tests/test_modules.py | 72 + .../tests/test_multiple_inheritance.cpp | 220 ++ .../tests/test_multiple_inheritance.py | 349 +++ .../pybind11/tests/test_numpy_array.cpp | 309 +++ .../python/pybind11/tests/test_numpy_array.py | 421 ++++ .../pybind11/tests/test_numpy_dtypes.cpp | 466 ++++ .../pybind11/tests/test_numpy_dtypes.py | 310 +++ .../pybind11/tests/test_numpy_vectorize.cpp | 89 + .../pybind11/tests/test_numpy_vectorize.py | 196 ++ .../pybind11/tests/test_opaque_types.cpp | 67 + .../pybind11/tests/test_opaque_types.py | 46 + .../tests/test_operator_overloading.cpp | 169 ++ .../tests/test_operator_overloading.py | 106 + wrap/python/pybind11/tests/test_pickling.cpp | 130 + wrap/python/pybind11/tests/test_pickling.py | 42 + wrap/python/pybind11/tests/test_pytypes.cpp | 296 +++ wrap/python/pybind11/tests/test_pytypes.py | 253 ++ .../tests/test_sequences_and_iterators.cpp | 353 +++ .../tests/test_sequences_and_iterators.py | 171 ++ wrap/python/pybind11/tests/test_smart_ptr.cpp | 366 +++ wrap/python/pybind11/tests/test_smart_ptr.py | 285 +++ wrap/python/pybind11/tests/test_stl.cpp | 284 +++ wrap/python/pybind11/tests/test_stl.py | 241 ++ .../pybind11/tests/test_stl_binders.cpp | 107 + .../python/pybind11/tests/test_stl_binders.py | 225 ++ .../tests/test_tagbased_polymorphic.cpp | 136 ++ .../tests/test_tagbased_polymorphic.py | 20 + wrap/python/pybind11/tests/test_union.cpp | 22 + wrap/python/pybind11/tests/test_union.py | 8 + .../pybind11/tests/test_virtual_functions.cpp | 479 ++++ .../pybind11/tests/test_virtual_functions.py | 377 +++ wrap/python/pybind11/tools/FindCatch.cmake | 57 + wrap/python/pybind11/tools/FindEigen3.cmake | 81 + .../pybind11/tools/FindPythonLibsNew.cmake | 202 ++ wrap/python/pybind11/tools/check-style.sh | 70 + wrap/python/pybind11/tools/libsize.py | 38 + wrap/python/pybind11/tools/mkdoc.py | 379 +++ .../pybind11/tools/pybind11Config.cmake.in | 104 + .../python/pybind11/tools/pybind11Tools.cmake | 227 ++ 183 files changed, 40107 insertions(+) create mode 100644 wrap/python/pybind11/.appveyor.yml create mode 100644 wrap/python/pybind11/.gitignore create mode 100644 wrap/python/pybind11/.gitmodules create mode 100644 wrap/python/pybind11/.readthedocs.yml create mode 100644 wrap/python/pybind11/.travis.yml create mode 100644 wrap/python/pybind11/CMakeLists.txt create mode 100644 wrap/python/pybind11/CONTRIBUTING.md create mode 100644 wrap/python/pybind11/ISSUE_TEMPLATE.md create mode 100644 wrap/python/pybind11/LICENSE create mode 100644 wrap/python/pybind11/MANIFEST.in create mode 100644 wrap/python/pybind11/README.md create mode 100644 wrap/python/pybind11/docs/Doxyfile create mode 100644 wrap/python/pybind11/docs/_static/theme_overrides.css create mode 100644 wrap/python/pybind11/docs/advanced/cast/chrono.rst create mode 100644 wrap/python/pybind11/docs/advanced/cast/custom.rst create mode 100644 wrap/python/pybind11/docs/advanced/cast/eigen.rst create mode 100644 wrap/python/pybind11/docs/advanced/cast/functional.rst create mode 100644 wrap/python/pybind11/docs/advanced/cast/index.rst create mode 100644 wrap/python/pybind11/docs/advanced/cast/overview.rst create mode 100644 wrap/python/pybind11/docs/advanced/cast/stl.rst create mode 100644 wrap/python/pybind11/docs/advanced/cast/strings.rst create mode 100644 wrap/python/pybind11/docs/advanced/classes.rst create mode 100644 wrap/python/pybind11/docs/advanced/embedding.rst create mode 100644 wrap/python/pybind11/docs/advanced/exceptions.rst create mode 100644 wrap/python/pybind11/docs/advanced/functions.rst create mode 100644 wrap/python/pybind11/docs/advanced/misc.rst create mode 100644 wrap/python/pybind11/docs/advanced/pycpp/index.rst create mode 100644 wrap/python/pybind11/docs/advanced/pycpp/numpy.rst create mode 100644 wrap/python/pybind11/docs/advanced/pycpp/object.rst create mode 100644 wrap/python/pybind11/docs/advanced/pycpp/utilities.rst create mode 100644 wrap/python/pybind11/docs/advanced/smart_ptrs.rst create mode 100644 wrap/python/pybind11/docs/basics.rst create mode 100644 wrap/python/pybind11/docs/benchmark.py create mode 100644 wrap/python/pybind11/docs/benchmark.rst create mode 100644 wrap/python/pybind11/docs/changelog.rst create mode 100644 wrap/python/pybind11/docs/classes.rst create mode 100644 wrap/python/pybind11/docs/compiling.rst create mode 100644 wrap/python/pybind11/docs/conf.py create mode 100644 wrap/python/pybind11/docs/faq.rst create mode 100644 wrap/python/pybind11/docs/index.rst create mode 100644 wrap/python/pybind11/docs/intro.rst create mode 100644 wrap/python/pybind11/docs/limitations.rst create mode 100644 wrap/python/pybind11/docs/pybind11-logo.png create mode 100644 wrap/python/pybind11/docs/pybind11_vs_boost_python1.png create mode 100644 wrap/python/pybind11/docs/pybind11_vs_boost_python1.svg create mode 100644 wrap/python/pybind11/docs/pybind11_vs_boost_python2.png create mode 100644 wrap/python/pybind11/docs/pybind11_vs_boost_python2.svg create mode 100644 wrap/python/pybind11/docs/reference.rst create mode 100644 wrap/python/pybind11/docs/release.rst create mode 100644 wrap/python/pybind11/docs/requirements.txt create mode 100644 wrap/python/pybind11/docs/upgrade.rst create mode 100644 wrap/python/pybind11/include/pybind11/attr.h create mode 100644 wrap/python/pybind11/include/pybind11/buffer_info.h create mode 100644 wrap/python/pybind11/include/pybind11/cast.h create mode 100644 wrap/python/pybind11/include/pybind11/chrono.h create mode 100644 wrap/python/pybind11/include/pybind11/common.h create mode 100644 wrap/python/pybind11/include/pybind11/complex.h create mode 100644 wrap/python/pybind11/include/pybind11/detail/class.h create mode 100644 wrap/python/pybind11/include/pybind11/detail/common.h create mode 100644 wrap/python/pybind11/include/pybind11/detail/descr.h create mode 100644 wrap/python/pybind11/include/pybind11/detail/init.h create mode 100644 wrap/python/pybind11/include/pybind11/detail/internals.h create mode 100644 wrap/python/pybind11/include/pybind11/detail/typeid.h create mode 100644 wrap/python/pybind11/include/pybind11/eigen.h create mode 100644 wrap/python/pybind11/include/pybind11/embed.h create mode 100644 wrap/python/pybind11/include/pybind11/eval.h create mode 100644 wrap/python/pybind11/include/pybind11/functional.h create mode 100644 wrap/python/pybind11/include/pybind11/iostream.h create mode 100644 wrap/python/pybind11/include/pybind11/numpy.h create mode 100644 wrap/python/pybind11/include/pybind11/operators.h create mode 100644 wrap/python/pybind11/include/pybind11/options.h create mode 100644 wrap/python/pybind11/include/pybind11/pybind11.h create mode 100644 wrap/python/pybind11/include/pybind11/pytypes.h create mode 100644 wrap/python/pybind11/include/pybind11/stl.h create mode 100644 wrap/python/pybind11/include/pybind11/stl_bind.h create mode 100644 wrap/python/pybind11/pybind11/__init__.py create mode 100644 wrap/python/pybind11/pybind11/__main__.py create mode 100644 wrap/python/pybind11/pybind11/_version.py create mode 100644 wrap/python/pybind11/setup.cfg create mode 100644 wrap/python/pybind11/setup.py create mode 100644 wrap/python/pybind11/tests/CMakeLists.txt create mode 100644 wrap/python/pybind11/tests/conftest.py create mode 100644 wrap/python/pybind11/tests/constructor_stats.h create mode 100644 wrap/python/pybind11/tests/local_bindings.h create mode 100644 wrap/python/pybind11/tests/object.h create mode 100644 wrap/python/pybind11/tests/pybind11_cross_module_tests.cpp create mode 100644 wrap/python/pybind11/tests/pybind11_tests.cpp create mode 100644 wrap/python/pybind11/tests/pybind11_tests.h create mode 100644 wrap/python/pybind11/tests/pytest.ini create mode 100644 wrap/python/pybind11/tests/test_buffers.cpp create mode 100644 wrap/python/pybind11/tests/test_buffers.py create mode 100644 wrap/python/pybind11/tests/test_builtin_casters.cpp create mode 100644 wrap/python/pybind11/tests/test_builtin_casters.py create mode 100644 wrap/python/pybind11/tests/test_call_policies.cpp create mode 100644 wrap/python/pybind11/tests/test_call_policies.py create mode 100644 wrap/python/pybind11/tests/test_callbacks.cpp create mode 100644 wrap/python/pybind11/tests/test_callbacks.py create mode 100644 wrap/python/pybind11/tests/test_chrono.cpp create mode 100644 wrap/python/pybind11/tests/test_chrono.py create mode 100644 wrap/python/pybind11/tests/test_class.cpp create mode 100644 wrap/python/pybind11/tests/test_class.py create mode 100644 wrap/python/pybind11/tests/test_cmake_build/CMakeLists.txt create mode 100644 wrap/python/pybind11/tests/test_cmake_build/embed.cpp create mode 100644 wrap/python/pybind11/tests/test_cmake_build/installed_embed/CMakeLists.txt create mode 100644 wrap/python/pybind11/tests/test_cmake_build/installed_function/CMakeLists.txt create mode 100644 wrap/python/pybind11/tests/test_cmake_build/installed_target/CMakeLists.txt create mode 100644 wrap/python/pybind11/tests/test_cmake_build/main.cpp create mode 100644 wrap/python/pybind11/tests/test_cmake_build/subdirectory_embed/CMakeLists.txt create mode 100644 wrap/python/pybind11/tests/test_cmake_build/subdirectory_function/CMakeLists.txt create mode 100644 wrap/python/pybind11/tests/test_cmake_build/subdirectory_target/CMakeLists.txt create mode 100644 wrap/python/pybind11/tests/test_cmake_build/test.py create mode 100644 wrap/python/pybind11/tests/test_constants_and_functions.cpp create mode 100644 wrap/python/pybind11/tests/test_constants_and_functions.py create mode 100644 wrap/python/pybind11/tests/test_copy_move.cpp create mode 100644 wrap/python/pybind11/tests/test_copy_move.py create mode 100644 wrap/python/pybind11/tests/test_docstring_options.cpp create mode 100644 wrap/python/pybind11/tests/test_docstring_options.py create mode 100644 wrap/python/pybind11/tests/test_eigen.cpp create mode 100644 wrap/python/pybind11/tests/test_eigen.py create mode 100644 wrap/python/pybind11/tests/test_embed/CMakeLists.txt create mode 100644 wrap/python/pybind11/tests/test_embed/catch.cpp create mode 100644 wrap/python/pybind11/tests/test_embed/external_module.cpp create mode 100644 wrap/python/pybind11/tests/test_embed/test_interpreter.cpp create mode 100644 wrap/python/pybind11/tests/test_embed/test_interpreter.py create mode 100644 wrap/python/pybind11/tests/test_enum.cpp create mode 100644 wrap/python/pybind11/tests/test_enum.py create mode 100644 wrap/python/pybind11/tests/test_eval.cpp create mode 100644 wrap/python/pybind11/tests/test_eval.py create mode 100644 wrap/python/pybind11/tests/test_eval_call.py create mode 100644 wrap/python/pybind11/tests/test_exceptions.cpp create mode 100644 wrap/python/pybind11/tests/test_exceptions.py create mode 100644 wrap/python/pybind11/tests/test_factory_constructors.cpp create mode 100644 wrap/python/pybind11/tests/test_factory_constructors.py create mode 100644 wrap/python/pybind11/tests/test_gil_scoped.cpp create mode 100644 wrap/python/pybind11/tests/test_gil_scoped.py create mode 100644 wrap/python/pybind11/tests/test_iostream.cpp create mode 100644 wrap/python/pybind11/tests/test_iostream.py create mode 100644 wrap/python/pybind11/tests/test_kwargs_and_defaults.cpp create mode 100644 wrap/python/pybind11/tests/test_kwargs_and_defaults.py create mode 100644 wrap/python/pybind11/tests/test_local_bindings.cpp create mode 100644 wrap/python/pybind11/tests/test_local_bindings.py create mode 100644 wrap/python/pybind11/tests/test_methods_and_attributes.cpp create mode 100644 wrap/python/pybind11/tests/test_methods_and_attributes.py create mode 100644 wrap/python/pybind11/tests/test_modules.cpp create mode 100644 wrap/python/pybind11/tests/test_modules.py create mode 100644 wrap/python/pybind11/tests/test_multiple_inheritance.cpp create mode 100644 wrap/python/pybind11/tests/test_multiple_inheritance.py create mode 100644 wrap/python/pybind11/tests/test_numpy_array.cpp create mode 100644 wrap/python/pybind11/tests/test_numpy_array.py create mode 100644 wrap/python/pybind11/tests/test_numpy_dtypes.cpp create mode 100644 wrap/python/pybind11/tests/test_numpy_dtypes.py create mode 100644 wrap/python/pybind11/tests/test_numpy_vectorize.cpp create mode 100644 wrap/python/pybind11/tests/test_numpy_vectorize.py create mode 100644 wrap/python/pybind11/tests/test_opaque_types.cpp create mode 100644 wrap/python/pybind11/tests/test_opaque_types.py create mode 100644 wrap/python/pybind11/tests/test_operator_overloading.cpp create mode 100644 wrap/python/pybind11/tests/test_operator_overloading.py create mode 100644 wrap/python/pybind11/tests/test_pickling.cpp create mode 100644 wrap/python/pybind11/tests/test_pickling.py create mode 100644 wrap/python/pybind11/tests/test_pytypes.cpp create mode 100644 wrap/python/pybind11/tests/test_pytypes.py create mode 100644 wrap/python/pybind11/tests/test_sequences_and_iterators.cpp create mode 100644 wrap/python/pybind11/tests/test_sequences_and_iterators.py create mode 100644 wrap/python/pybind11/tests/test_smart_ptr.cpp create mode 100644 wrap/python/pybind11/tests/test_smart_ptr.py create mode 100644 wrap/python/pybind11/tests/test_stl.cpp create mode 100644 wrap/python/pybind11/tests/test_stl.py create mode 100644 wrap/python/pybind11/tests/test_stl_binders.cpp create mode 100644 wrap/python/pybind11/tests/test_stl_binders.py create mode 100644 wrap/python/pybind11/tests/test_tagbased_polymorphic.cpp create mode 100644 wrap/python/pybind11/tests/test_tagbased_polymorphic.py create mode 100644 wrap/python/pybind11/tests/test_union.cpp create mode 100644 wrap/python/pybind11/tests/test_union.py create mode 100644 wrap/python/pybind11/tests/test_virtual_functions.cpp create mode 100644 wrap/python/pybind11/tests/test_virtual_functions.py create mode 100644 wrap/python/pybind11/tools/FindCatch.cmake create mode 100644 wrap/python/pybind11/tools/FindEigen3.cmake create mode 100644 wrap/python/pybind11/tools/FindPythonLibsNew.cmake create mode 100755 wrap/python/pybind11/tools/check-style.sh create mode 100644 wrap/python/pybind11/tools/libsize.py create mode 100755 wrap/python/pybind11/tools/mkdoc.py create mode 100644 wrap/python/pybind11/tools/pybind11Config.cmake.in create mode 100644 wrap/python/pybind11/tools/pybind11Tools.cmake diff --git a/wrap/python/pybind11/.appveyor.yml b/wrap/python/pybind11/.appveyor.yml new file mode 100644 index 000000000..8fbb72610 --- /dev/null +++ b/wrap/python/pybind11/.appveyor.yml @@ -0,0 +1,70 @@ +version: 1.0.{build} +image: +- Visual Studio 2017 +- Visual Studio 2015 +test: off +skip_branch_with_pr: true +build: + parallel: true +platform: +- x64 +- x86 +environment: + matrix: + - PYTHON: 36 + CPP: 14 + CONFIG: Debug + - PYTHON: 27 + CPP: 14 + CONFIG: Debug + - CONDA: 36 + CPP: latest + CONFIG: Release +matrix: + exclude: + - image: Visual Studio 2015 + platform: x86 + - image: Visual Studio 2015 + CPP: latest + - image: Visual Studio 2017 + CPP: latest + platform: x86 +install: +- ps: | + if ($env:PLATFORM -eq "x64") { $env:CMAKE_ARCH = "x64" } + if ($env:APPVEYOR_JOB_NAME -like "*Visual Studio 2017*") { + $env:CMAKE_GENERATOR = "Visual Studio 15 2017" + $env:CMAKE_INCLUDE_PATH = "C:\Libraries\boost_1_64_0" + $env:CXXFLAGS = "-permissive-" + } else { + $env:CMAKE_GENERATOR = "Visual Studio 14 2015" + } + if ($env:PYTHON) { + if ($env:PLATFORM -eq "x64") { $env:PYTHON = "$env:PYTHON-x64" } + $env:PATH = "C:\Python$env:PYTHON\;C:\Python$env:PYTHON\Scripts\;$env:PATH" + python -W ignore -m pip install --upgrade pip wheel + python -W ignore -m pip install pytest numpy --no-warn-script-location + } elseif ($env:CONDA) { + if ($env:CONDA -eq "27") { $env:CONDA = "" } + if ($env:PLATFORM -eq "x64") { $env:CONDA = "$env:CONDA-x64" } + $env:PATH = "C:\Miniconda$env:CONDA\;C:\Miniconda$env:CONDA\Scripts\;$env:PATH" + $env:PYTHONHOME = "C:\Miniconda$env:CONDA" + conda --version + conda install -y -q pytest numpy scipy + } +- ps: | + Start-FileDownload 'http://bitbucket.org/eigen/eigen/get/3.3.3.zip' + 7z x 3.3.3.zip -y > $null + $env:CMAKE_INCLUDE_PATH = "eigen-eigen-67e894c6cd8f;$env:CMAKE_INCLUDE_PATH" +build_script: +- cmake -G "%CMAKE_GENERATOR%" -A "%CMAKE_ARCH%" + -DPYBIND11_CPP_STANDARD=/std:c++%CPP% + -DPYBIND11_WERROR=ON + -DDOWNLOAD_CATCH=ON + -DCMAKE_SUPPRESS_REGENERATION=1 + . +- set MSBuildLogger="C:\Program Files\AppVeyor\BuildAgent\Appveyor.MSBuildLogger.dll" +- cmake --build . --config %CONFIG% --target pytest -- /m /v:m /logger:%MSBuildLogger% +- cmake --build . --config %CONFIG% --target cpptest -- /m /v:m /logger:%MSBuildLogger% +- if "%CPP%"=="latest" (cmake --build . --config %CONFIG% --target test_cmake_build -- /m /v:m /logger:%MSBuildLogger%) +on_failure: if exist "tests\test_cmake_build" type tests\test_cmake_build\*.log* diff --git a/wrap/python/pybind11/.gitignore b/wrap/python/pybind11/.gitignore new file mode 100644 index 000000000..979fd4431 --- /dev/null +++ b/wrap/python/pybind11/.gitignore @@ -0,0 +1,38 @@ +CMakeCache.txt +CMakeFiles +Makefile +cmake_install.cmake +.DS_Store +*.so +*.pyd +*.dll +*.sln +*.sdf +*.opensdf +*.vcxproj +*.filters +example.dir +Win32 +x64 +Release +Debug +.vs +CTestTestfile.cmake +Testing +autogen +MANIFEST +/.ninja_* +/*.ninja +/docs/.build +*.py[co] +*.egg-info +*~ +.*.swp +.DS_Store +/dist +/build +/cmake/ +.cache/ +sosize-*.txt +pybind11Config*.cmake +pybind11Targets.cmake diff --git a/wrap/python/pybind11/.gitmodules b/wrap/python/pybind11/.gitmodules new file mode 100644 index 000000000..d063a8e89 --- /dev/null +++ b/wrap/python/pybind11/.gitmodules @@ -0,0 +1,3 @@ +[submodule "tools/clang"] + path = tools/clang + url = ../../wjakob/clang-cindex-python3 diff --git a/wrap/python/pybind11/.readthedocs.yml b/wrap/python/pybind11/.readthedocs.yml new file mode 100644 index 000000000..c9c61617c --- /dev/null +++ b/wrap/python/pybind11/.readthedocs.yml @@ -0,0 +1,3 @@ +python: + version: 3 +requirements_file: docs/requirements.txt diff --git a/wrap/python/pybind11/.travis.yml b/wrap/python/pybind11/.travis.yml new file mode 100644 index 000000000..4cc5cf07c --- /dev/null +++ b/wrap/python/pybind11/.travis.yml @@ -0,0 +1,280 @@ +language: cpp +matrix: + include: + # This config does a few things: + # - Checks C++ and Python code styles (check-style.sh and flake8). + # - Makes sure sphinx can build the docs without any errors or warnings. + # - Tests setup.py sdist and install (all header files should be present). + # - Makes sure that everything still works without optional deps (numpy/scipy/eigen) and + # also tests the automatic discovery functions in CMake (Python version, C++ standard). + - os: linux + dist: xenial # Necessary to run doxygen 1.8.15 + name: Style, docs, and pip + cache: false + before_install: + - pyenv global $(pyenv whence 2to3) # activate all python versions + - PY_CMD=python3 + - $PY_CMD -m pip install --user --upgrade pip wheel setuptools + install: + - $PY_CMD -m pip install --user --upgrade sphinx sphinx_rtd_theme breathe flake8 pep8-naming pytest + - curl -fsSL https://sourceforge.net/projects/doxygen/files/rel-1.8.15/doxygen-1.8.15.linux.bin.tar.gz/download | tar xz + - export PATH="$PWD/doxygen-1.8.15/bin:$PATH" + script: + - tools/check-style.sh + - flake8 + - $PY_CMD -m sphinx -W -b html docs docs/.build + - | + # Make sure setup.py distributes and installs all the headers + $PY_CMD setup.py sdist + $PY_CMD -m pip install --user -U ./dist/* + installed=$($PY_CMD -c "import pybind11; print(pybind11.get_include(True) + '/pybind11')") + diff -rq $installed ./include/pybind11 + - | + # Barebones build + cmake -DCMAKE_BUILD_TYPE=Debug -DPYBIND11_WERROR=ON -DDOWNLOAD_CATCH=ON -DPYTHON_EXECUTABLE=$(which $PY_CMD) . + make pytest -j 2 + make cpptest -j 2 + # The following are regular test configurations, including optional dependencies. + # With regard to each other they differ in Python version, C++ standard and compiler. + - os: linux + dist: trusty + name: Python 2.7, c++11, gcc 4.8 + env: PYTHON=2.7 CPP=11 GCC=4.8 + addons: + apt: + packages: + - cmake=2.\* + - cmake-data=2.\* + - os: linux + dist: trusty + name: Python 3.6, c++11, gcc 4.8 + env: PYTHON=3.6 CPP=11 GCC=4.8 + addons: + apt: + sources: + - deadsnakes + packages: + - python3.6-dev + - python3.6-venv + - cmake=2.\* + - cmake-data=2.\* + - os: linux + dist: trusty + env: PYTHON=2.7 CPP=14 GCC=6 CMAKE=1 + name: Python 2.7, c++14, gcc 4.8, CMake test + addons: + apt: + sources: + - ubuntu-toolchain-r-test + packages: + - g++-6 + - os: linux + dist: trusty + name: Python 3.5, c++14, gcc 6, Debug build + # N.B. `ensurepip` could be installed transitively by `python3.5-venv`, but + # seems to have apt conflicts (at least for Trusty). Use Docker instead. + services: docker + env: DOCKER=debian:stretch PYTHON=3.5 CPP=14 GCC=6 DEBUG=1 + - os: linux + dist: xenial + env: PYTHON=3.6 CPP=17 GCC=7 + name: Python 3.6, c++17, gcc 7 + addons: + apt: + sources: + - deadsnakes + - ubuntu-toolchain-r-test + packages: + - g++-7 + - python3.6-dev + - python3.6-venv + - os: linux + dist: xenial + env: PYTHON=3.6 CPP=17 CLANG=7 + name: Python 3.6, c++17, Clang 7 + addons: + apt: + sources: + - deadsnakes + - llvm-toolchain-xenial-7 + packages: + - python3.6-dev + - python3.6-venv + - clang-7 + - libclang-7-dev + - llvm-7-dev + - lld-7 + - libc++-7-dev + - libc++abi-7-dev # Why is this necessary??? + - os: osx + name: Python 2.7, c++14, AppleClang 7.3, CMake test + osx_image: xcode7.3 + env: PYTHON=2.7 CPP=14 CLANG CMAKE=1 + - os: osx + name: Python 3.7, c++14, AppleClang 9, Debug build + osx_image: xcode9 + env: PYTHON=3.7 CPP=14 CLANG DEBUG=1 + # Test a PyPy 2.7 build + - os: linux + dist: trusty + env: PYPY=5.8 PYTHON=2.7 CPP=11 GCC=4.8 + name: PyPy 5.8, Python 2.7, c++11, gcc 4.8 + addons: + apt: + packages: + - libblas-dev + - liblapack-dev + - gfortran + # Build in 32-bit mode and tests against the CMake-installed version + - os: linux + dist: trusty + services: docker + env: DOCKER=i386/debian:stretch PYTHON=3.5 CPP=14 GCC=6 INSTALL=1 + name: Python 3.4, c++14, gcc 6, 32-bit + script: + - | + # Consolidated 32-bit Docker Build + Install + set -ex + $SCRIPT_RUN_PREFIX sh -c " + set -ex + cmake ${CMAKE_EXTRA_ARGS} -DPYBIND11_INSTALL=1 -DPYBIND11_TEST=0 . + make install + cp -a tests /pybind11-tests + mkdir /build-tests && cd /build-tests + cmake ../pybind11-tests ${CMAKE_EXTRA_ARGS} -DPYBIND11_WERROR=ON + make pytest -j 2" + set +ex +cache: + directories: + - $HOME/.local/bin + - $HOME/.local/lib + - $HOME/.local/include + - $HOME/Library/Python +before_install: +- | + # Configure build variables + set -ex + if [ "$TRAVIS_OS_NAME" = "linux" ]; then + if [ -n "$CLANG" ]; then + export CXX=clang++-$CLANG CC=clang-$CLANG + EXTRA_PACKAGES+=" clang-$CLANG llvm-$CLANG-dev" + else + if [ -z "$GCC" ]; then GCC=4.8 + else EXTRA_PACKAGES+=" g++-$GCC" + fi + export CXX=g++-$GCC CC=gcc-$GCC + fi + elif [ "$TRAVIS_OS_NAME" = "osx" ]; then + export CXX=clang++ CC=clang; + fi + if [ -n "$CPP" ]; then CPP=-std=c++$CPP; fi + if [ "${PYTHON:0:1}" = "3" ]; then PY=3; fi + if [ -n "$DEBUG" ]; then CMAKE_EXTRA_ARGS+=" -DCMAKE_BUILD_TYPE=Debug"; fi + set +ex +- | + # Initialize environment + set -ex + if [ -n "$DOCKER" ]; then + docker pull $DOCKER + + containerid=$(docker run --detach --tty \ + --volume="$PWD":/pybind11 --workdir=/pybind11 \ + --env="CC=$CC" --env="CXX=$CXX" --env="DEBIAN_FRONTEND=$DEBIAN_FRONTEND" \ + --env=GCC_COLORS=\ \ + $DOCKER) + SCRIPT_RUN_PREFIX="docker exec --tty $containerid" + $SCRIPT_RUN_PREFIX sh -c 'for s in 0 15; do sleep $s; apt-get update && apt-get -qy dist-upgrade && break; done' + else + if [ "$PYPY" = "5.8" ]; then + curl -fSL https://bitbucket.org/pypy/pypy/downloads/pypy2-v5.8.0-linux64.tar.bz2 | tar xj + PY_CMD=$(echo `pwd`/pypy2-v5.8.0-linux64/bin/pypy) + CMAKE_EXTRA_ARGS+=" -DPYTHON_EXECUTABLE:FILEPATH=$PY_CMD" + else + PY_CMD=python$PYTHON + if [ "$TRAVIS_OS_NAME" = "osx" ]; then + if [ "$PY" = "3" ]; then + brew update && brew upgrade python + else + curl -fsSL https://bootstrap.pypa.io/get-pip.py | $PY_CMD - --user + fi + fi + fi + if [ "$PY" = 3 ] || [ -n "$PYPY" ]; then + $PY_CMD -m ensurepip --user + fi + $PY_CMD --version + $PY_CMD -m pip install --user --upgrade pip wheel + fi + set +ex +install: +- | + # Install dependencies + set -ex + cmake --version + if [ -n "$DOCKER" ]; then + if [ -n "$DEBUG" ]; then + PY_DEBUG="python$PYTHON-dbg python$PY-scipy-dbg" + CMAKE_EXTRA_ARGS+=" -DPYTHON_EXECUTABLE=/usr/bin/python${PYTHON}dm" + fi + $SCRIPT_RUN_PREFIX sh -c "for s in 0 15; do sleep \$s; \ + apt-get -qy --no-install-recommends install \ + $PY_DEBUG python$PYTHON-dev python$PY-pytest python$PY-scipy \ + libeigen3-dev libboost-dev cmake make ${EXTRA_PACKAGES} && break; done" + else + + if [ "$CLANG" = "7" ]; then + export CXXFLAGS="-stdlib=libc++" + fi + + export NPY_NUM_BUILD_JOBS=2 + echo "Installing pytest, numpy, scipy..." + local PIP_CMD="" + if [ -n $PYPY ]; then + # For expediency, install only versions that are available on the extra index. + travis_wait 30 \ + $PY_CMD -m pip install --user --upgrade --extra-index-url https://imaginary.ca/trusty-pypi \ + pytest numpy==1.15.4 scipy==1.2.0 + else + $PY_CMD -m pip install --user --upgrade pytest numpy scipy + fi + echo "done." + + mkdir eigen + curl -fsSL https://bitbucket.org/eigen/eigen/get/3.3.4.tar.bz2 | \ + tar --extract -j --directory=eigen --strip-components=1 + export CMAKE_INCLUDE_PATH="${CMAKE_INCLUDE_PATH:+$CMAKE_INCLUDE_PATH:}$PWD/eigen" + fi + set +ex +script: +- | + # CMake Configuration + set -ex + $SCRIPT_RUN_PREFIX cmake ${CMAKE_EXTRA_ARGS} \ + -DPYBIND11_PYTHON_VERSION=$PYTHON \ + -DPYBIND11_CPP_STANDARD=$CPP \ + -DPYBIND11_WERROR=${WERROR:-ON} \ + -DDOWNLOAD_CATCH=${DOWNLOAD_CATCH:-ON} \ + . + set +ex +- | + # pytest + set -ex + $SCRIPT_RUN_PREFIX make pytest -j 2 VERBOSE=1 + set +ex +- | + # cpptest + set -ex + $SCRIPT_RUN_PREFIX make cpptest -j 2 + set +ex +- | + # CMake Build Interface + set -ex + if [ -n "$CMAKE" ]; then $SCRIPT_RUN_PREFIX make test_cmake_build; fi + set +ex +after_failure: cat tests/test_cmake_build/*.log* +after_script: +- | + # Cleanup (Docker) + set -ex + if [ -n "$DOCKER" ]; then docker stop "$containerid"; docker rm "$containerid"; fi + set +ex diff --git a/wrap/python/pybind11/CMakeLists.txt b/wrap/python/pybind11/CMakeLists.txt new file mode 100644 index 000000000..85ecd9028 --- /dev/null +++ b/wrap/python/pybind11/CMakeLists.txt @@ -0,0 +1,157 @@ +# CMakeLists.txt -- Build system for the pybind11 modules +# +# Copyright (c) 2015 Wenzel Jakob +# +# All rights reserved. Use of this source code is governed by a +# BSD-style license that can be found in the LICENSE file. + +cmake_minimum_required(VERSION 2.8.12) + +if (POLICY CMP0048) + # cmake warns if loaded from a min-3.0-required parent dir, so silence the warning: + cmake_policy(SET CMP0048 NEW) +endif() + +# CMake versions < 3.4.0 do not support try_compile/pthread checks without C as active language. +if(CMAKE_VERSION VERSION_LESS 3.4.0) + project(pybind11) +else() + project(pybind11 CXX) +endif() + +# Check if pybind11 is being used directly or via add_subdirectory +set(PYBIND11_MASTER_PROJECT OFF) +if (CMAKE_CURRENT_SOURCE_DIR STREQUAL CMAKE_SOURCE_DIR) + set(PYBIND11_MASTER_PROJECT ON) +endif() + +option(PYBIND11_INSTALL "Install pybind11 header files?" ${PYBIND11_MASTER_PROJECT}) +option(PYBIND11_TEST "Build pybind11 test suite?" ${PYBIND11_MASTER_PROJECT}) + +list(APPEND CMAKE_MODULE_PATH "${CMAKE_CURRENT_LIST_DIR}/tools") + +include(pybind11Tools) + +# Cache variables so pybind11_add_module can be used in parent projects +set(PYBIND11_INCLUDE_DIR "${CMAKE_CURRENT_LIST_DIR}/include" CACHE INTERNAL "") +set(PYTHON_INCLUDE_DIRS ${PYTHON_INCLUDE_DIRS} CACHE INTERNAL "") +set(PYTHON_LIBRARIES ${PYTHON_LIBRARIES} CACHE INTERNAL "") +set(PYTHON_MODULE_PREFIX ${PYTHON_MODULE_PREFIX} CACHE INTERNAL "") +set(PYTHON_MODULE_EXTENSION ${PYTHON_MODULE_EXTENSION} CACHE INTERNAL "") +set(PYTHON_VERSION_MAJOR ${PYTHON_VERSION_MAJOR} CACHE INTERNAL "") +set(PYTHON_VERSION_MINOR ${PYTHON_VERSION_MINOR} CACHE INTERNAL "") + +# NB: when adding a header don't forget to also add it to setup.py +set(PYBIND11_HEADERS + include/pybind11/detail/class.h + include/pybind11/detail/common.h + include/pybind11/detail/descr.h + include/pybind11/detail/init.h + include/pybind11/detail/internals.h + include/pybind11/detail/typeid.h + include/pybind11/attr.h + include/pybind11/buffer_info.h + include/pybind11/cast.h + include/pybind11/chrono.h + include/pybind11/common.h + include/pybind11/complex.h + include/pybind11/options.h + include/pybind11/eigen.h + include/pybind11/embed.h + include/pybind11/eval.h + include/pybind11/functional.h + include/pybind11/numpy.h + include/pybind11/operators.h + include/pybind11/pybind11.h + include/pybind11/pytypes.h + include/pybind11/stl.h + include/pybind11/stl_bind.h +) +string(REPLACE "include/" "${CMAKE_CURRENT_SOURCE_DIR}/include/" + PYBIND11_HEADERS "${PYBIND11_HEADERS}") + +if (PYBIND11_TEST) + add_subdirectory(tests) +endif() + +include(GNUInstallDirs) +include(CMakePackageConfigHelpers) + +# extract project version from source +file(STRINGS "${PYBIND11_INCLUDE_DIR}/pybind11/detail/common.h" pybind11_version_defines + REGEX "#define PYBIND11_VERSION_(MAJOR|MINOR|PATCH) ") +foreach(ver ${pybind11_version_defines}) + if (ver MATCHES "#define PYBIND11_VERSION_(MAJOR|MINOR|PATCH) +([^ ]+)$") + set(PYBIND11_VERSION_${CMAKE_MATCH_1} "${CMAKE_MATCH_2}" CACHE INTERNAL "") + endif() +endforeach() +set(${PROJECT_NAME}_VERSION ${PYBIND11_VERSION_MAJOR}.${PYBIND11_VERSION_MINOR}.${PYBIND11_VERSION_PATCH}) +message(STATUS "pybind11 v${${PROJECT_NAME}_VERSION}") + +option (USE_PYTHON_INCLUDE_DIR "Install pybind11 headers in Python include directory instead of default installation prefix" OFF) +if (USE_PYTHON_INCLUDE_DIR) + file(RELATIVE_PATH CMAKE_INSTALL_INCLUDEDIR ${CMAKE_INSTALL_PREFIX} ${PYTHON_INCLUDE_DIRS}) +endif() + +if(NOT (CMAKE_VERSION VERSION_LESS 3.0)) # CMake >= 3.0 + # Build an interface library target: + add_library(pybind11 INTERFACE) + add_library(pybind11::pybind11 ALIAS pybind11) # to match exported target + target_include_directories(pybind11 INTERFACE $ + $ + $) + target_compile_options(pybind11 INTERFACE $) + + add_library(module INTERFACE) + add_library(pybind11::module ALIAS module) + if(NOT MSVC) + target_compile_options(module INTERFACE -fvisibility=hidden) + endif() + target_link_libraries(module INTERFACE pybind11::pybind11) + if(WIN32 OR CYGWIN) + target_link_libraries(module INTERFACE $) + elseif(APPLE) + target_link_libraries(module INTERFACE "-undefined dynamic_lookup") + endif() + + add_library(embed INTERFACE) + add_library(pybind11::embed ALIAS embed) + target_link_libraries(embed INTERFACE pybind11::pybind11 $) +endif() + +if (PYBIND11_INSTALL) + install(DIRECTORY ${PYBIND11_INCLUDE_DIR}/pybind11 DESTINATION ${CMAKE_INSTALL_INCLUDEDIR}) + # GNUInstallDirs "DATADIR" wrong here; CMake search path wants "share". + set(PYBIND11_CMAKECONFIG_INSTALL_DIR "share/cmake/${PROJECT_NAME}" CACHE STRING "install path for pybind11Config.cmake") + + configure_package_config_file(tools/${PROJECT_NAME}Config.cmake.in + "${CMAKE_CURRENT_BINARY_DIR}/${PROJECT_NAME}Config.cmake" + INSTALL_DESTINATION ${PYBIND11_CMAKECONFIG_INSTALL_DIR}) + # Remove CMAKE_SIZEOF_VOID_P from ConfigVersion.cmake since the library does + # not depend on architecture specific settings or libraries. + set(_PYBIND11_CMAKE_SIZEOF_VOID_P ${CMAKE_SIZEOF_VOID_P}) + unset(CMAKE_SIZEOF_VOID_P) + write_basic_package_version_file(${CMAKE_CURRENT_BINARY_DIR}/${PROJECT_NAME}ConfigVersion.cmake + VERSION ${${PROJECT_NAME}_VERSION} + COMPATIBILITY AnyNewerVersion) + set(CMAKE_SIZEOF_VOID_P ${_PYBIND11_CMAKE_SIZEOF_VOID_P}) + install(FILES ${CMAKE_CURRENT_BINARY_DIR}/${PROJECT_NAME}Config.cmake + ${CMAKE_CURRENT_BINARY_DIR}/${PROJECT_NAME}ConfigVersion.cmake + tools/FindPythonLibsNew.cmake + tools/pybind11Tools.cmake + DESTINATION ${PYBIND11_CMAKECONFIG_INSTALL_DIR}) + + if(NOT (CMAKE_VERSION VERSION_LESS 3.0)) + if(NOT PYBIND11_EXPORT_NAME) + set(PYBIND11_EXPORT_NAME "${PROJECT_NAME}Targets") + endif() + + install(TARGETS pybind11 module embed + EXPORT "${PYBIND11_EXPORT_NAME}") + if(PYBIND11_MASTER_PROJECT) + install(EXPORT "${PYBIND11_EXPORT_NAME}" + NAMESPACE "${PROJECT_NAME}::" + DESTINATION ${PYBIND11_CMAKECONFIG_INSTALL_DIR}) + endif() + endif() +endif() diff --git a/wrap/python/pybind11/CONTRIBUTING.md b/wrap/python/pybind11/CONTRIBUTING.md new file mode 100644 index 000000000..01596d94f --- /dev/null +++ b/wrap/python/pybind11/CONTRIBUTING.md @@ -0,0 +1,49 @@ +Thank you for your interest in this project! Please refer to the following +sections on how to contribute code and bug reports. + +### Reporting bugs + +At the moment, this project is run in the spare time of a single person +([Wenzel Jakob](http://rgl.epfl.ch/people/wjakob)) with very limited resources +for issue tracker tickets. Thus, before submitting a question or bug report, +please take a moment of your time and ensure that your issue isn't already +discussed in the project documentation provided at +[http://pybind11.readthedocs.org/en/latest](http://pybind11.readthedocs.org/en/latest). + +Assuming that you have identified a previously unknown problem or an important +question, it's essential that you submit a self-contained and minimal piece of +code that reproduces the problem. In other words: no external dependencies, +isolate the function(s) that cause breakage, submit matched and complete C++ +and Python snippets that can be easily compiled and run on my end. + +## Pull requests +Contributions are submitted, reviewed, and accepted using Github pull requests. +Please refer to [this +article](https://help.github.com/articles/using-pull-requests) for details and +adhere to the following rules to make the process as smooth as possible: + +* Make a new branch for every feature you're working on. +* Make small and clean pull requests that are easy to review but make sure they + do add value by themselves. +* Add tests for any new functionality and run the test suite (``make pytest``) + to ensure that no existing features break. +* Please run ``flake8`` and ``tools/check-style.sh`` to check your code matches + the project style. (Note that ``check-style.sh`` requires ``gawk``.) +* This project has a strong focus on providing general solutions using a + minimal amount of code, thus small pull requests are greatly preferred. + +### Licensing of contributions + +pybind11 is provided under a BSD-style license that can be found in the +``LICENSE`` file. By using, distributing, or contributing to this project, you +agree to the terms and conditions of this license. + +You are under no obligation whatsoever to provide any bug fixes, patches, or +upgrades to the features, functionality or performance of the source code +("Enhancements") to anyone; however, if you choose to make your Enhancements +available either publicly, or directly to the author of this software, without +imposing a separate written license agreement for such Enhancements, then you +hereby grant the following license: a non-exclusive, royalty-free perpetual +license to install, use, modify, prepare derivative works, incorporate into +other computer software, distribute, and sublicense such enhancements or +derivative works thereof, in binary and source code form. diff --git a/wrap/python/pybind11/ISSUE_TEMPLATE.md b/wrap/python/pybind11/ISSUE_TEMPLATE.md new file mode 100644 index 000000000..75df39981 --- /dev/null +++ b/wrap/python/pybind11/ISSUE_TEMPLATE.md @@ -0,0 +1,17 @@ +Make sure you've completed the following steps before submitting your issue -- thank you! + +1. Check if your question has already been answered in the [FAQ](http://pybind11.readthedocs.io/en/latest/faq.html) section. +2. Make sure you've read the [documentation](http://pybind11.readthedocs.io/en/latest/). Your issue may be addressed there. +3. If those resources didn't help and you only have a short question (not a bug report), consider asking in the [Gitter chat room](https://gitter.im/pybind/Lobby). +4. If you have a genuine bug report or a more complex question which is not answered in the previous items (or not suitable for chat), please fill in the details below. +5. Include a self-contained and minimal piece of code that reproduces the problem. If that's not possible, try to make the description as clear as possible. + +*After reading, remove this checklist and the template text in parentheses below.* + +## Issue description + +(Provide a short description, state the expected behavior and what actually happens.) + +## Reproducible example code + +(The code should be minimal, have no external dependencies, isolate the function(s) that cause breakage. Submit matched and complete C++ and Python snippets that can be easily compiled and run to diagnose the issue.) diff --git a/wrap/python/pybind11/LICENSE b/wrap/python/pybind11/LICENSE new file mode 100644 index 000000000..6f15578cc --- /dev/null +++ b/wrap/python/pybind11/LICENSE @@ -0,0 +1,29 @@ +Copyright (c) 2016 Wenzel Jakob , All rights reserved. + +Redistribution and use in source and binary forms, with or without +modification, are permitted provided that the following conditions are met: + +1. Redistributions of source code must retain the above copyright notice, this + list of conditions and the following disclaimer. + +2. Redistributions in binary form must reproduce the above copyright notice, + this list of conditions and the following disclaimer in the documentation + and/or other materials provided with the distribution. + +3. Neither the name of the copyright holder nor the names of its contributors + may be used to endorse or promote products derived from this software + without specific prior written permission. + +THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND +ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED +WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE +DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE +FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL +DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR +SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, +OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE +OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + +Please also refer to the file CONTRIBUTING.md, which clarifies licensing of +external contributions to this project including patches, pull requests, etc. diff --git a/wrap/python/pybind11/MANIFEST.in b/wrap/python/pybind11/MANIFEST.in new file mode 100644 index 000000000..6e57baeee --- /dev/null +++ b/wrap/python/pybind11/MANIFEST.in @@ -0,0 +1,2 @@ +recursive-include include/pybind11 *.h +include LICENSE README.md CONTRIBUTING.md diff --git a/wrap/python/pybind11/README.md b/wrap/python/pybind11/README.md new file mode 100644 index 000000000..35d2d76ff --- /dev/null +++ b/wrap/python/pybind11/README.md @@ -0,0 +1,129 @@ +![pybind11 logo](https://github.com/pybind/pybind11/raw/master/docs/pybind11-logo.png) + +# pybind11 — Seamless operability between C++11 and Python + +[![Documentation Status](https://readthedocs.org/projects/pybind11/badge/?version=master)](http://pybind11.readthedocs.org/en/master/?badge=master) +[![Documentation Status](https://readthedocs.org/projects/pybind11/badge/?version=stable)](http://pybind11.readthedocs.org/en/stable/?badge=stable) +[![Gitter chat](https://img.shields.io/gitter/room/gitterHQ/gitter.svg)](https://gitter.im/pybind/Lobby) +[![Build Status](https://travis-ci.org/pybind/pybind11.svg?branch=master)](https://travis-ci.org/pybind/pybind11) +[![Build status](https://ci.appveyor.com/api/projects/status/riaj54pn4h08xy40?svg=true)](https://ci.appveyor.com/project/wjakob/pybind11) + +**pybind11** is a lightweight header-only library that exposes C++ types in Python +and vice versa, mainly to create Python bindings of existing C++ code. Its +goals and syntax are similar to the excellent +[Boost.Python](http://www.boost.org/doc/libs/1_58_0/libs/python/doc/) library +by David Abrahams: to minimize boilerplate code in traditional extension +modules by inferring type information using compile-time introspection. + +The main issue with Boost.Python—and the reason for creating such a similar +project—is Boost. Boost is an enormously large and complex suite of utility +libraries that works with almost every C++ compiler in existence. This +compatibility has its cost: arcane template tricks and workarounds are +necessary to support the oldest and buggiest of compiler specimens. Now that +C++11-compatible compilers are widely available, this heavy machinery has +become an excessively large and unnecessary dependency. + +Think of this library as a tiny self-contained version of Boost.Python with +everything stripped away that isn't relevant for binding generation. Without +comments, the core header files only require ~4K lines of code and depend on +Python (2.7 or 3.x, or PyPy2.7 >= 5.7) and the C++ standard library. This +compact implementation was possible thanks to some of the new C++11 language +features (specifically: tuples, lambda functions and variadic templates). Since +its creation, this library has grown beyond Boost.Python in many ways, leading +to dramatically simpler binding code in many common situations. + +Tutorial and reference documentation is provided at +[http://pybind11.readthedocs.org/en/master](http://pybind11.readthedocs.org/en/master). +A PDF version of the manual is available +[here](https://media.readthedocs.org/pdf/pybind11/master/pybind11.pdf). + +## Core features +pybind11 can map the following core C++ features to Python + +- Functions accepting and returning custom data structures per value, reference, or pointer +- Instance methods and static methods +- Overloaded functions +- Instance attributes and static attributes +- Arbitrary exception types +- Enumerations +- Callbacks +- Iterators and ranges +- Custom operators +- Single and multiple inheritance +- STL data structures +- Smart pointers with reference counting like ``std::shared_ptr`` +- Internal references with correct reference counting +- C++ classes with virtual (and pure virtual) methods can be extended in Python + +## Goodies +In addition to the core functionality, pybind11 provides some extra goodies: + +- Python 2.7, 3.x, and PyPy (PyPy2.7 >= 5.7) are supported with an + implementation-agnostic interface. + +- It is possible to bind C++11 lambda functions with captured variables. The + lambda capture data is stored inside the resulting Python function object. + +- pybind11 uses C++11 move constructors and move assignment operators whenever + possible to efficiently transfer custom data types. + +- It's easy to expose the internal storage of custom data types through + Pythons' buffer protocols. This is handy e.g. for fast conversion between + C++ matrix classes like Eigen and NumPy without expensive copy operations. + +- pybind11 can automatically vectorize functions so that they are transparently + applied to all entries of one or more NumPy array arguments. + +- Python's slice-based access and assignment operations can be supported with + just a few lines of code. + +- Everything is contained in just a few header files; there is no need to link + against any additional libraries. + +- Binaries are generally smaller by a factor of at least 2 compared to + equivalent bindings generated by Boost.Python. A recent pybind11 conversion + of PyRosetta, an enormous Boost.Python binding project, + [reported](http://graylab.jhu.edu/RosettaCon2016/PyRosetta-4.pdf) a binary + size reduction of **5.4x** and compile time reduction by **5.8x**. + +- Function signatures are precomputed at compile time (using ``constexpr``), + leading to smaller binaries. + +- With little extra effort, C++ types can be pickled and unpickled similar to + regular Python objects. + +## Supported compilers + +1. Clang/LLVM 3.3 or newer (for Apple Xcode's clang, this is 5.0.0 or newer) +2. GCC 4.8 or newer +3. Microsoft Visual Studio 2015 Update 3 or newer +4. Intel C++ compiler 17 or newer (16 with pybind11 v2.0 and 15 with pybind11 v2.0 and a [workaround](https://github.com/pybind/pybind11/issues/276)) +5. Cygwin/GCC (tested on 2.5.1) + +## About + +This project was created by [Wenzel Jakob](http://rgl.epfl.ch/people/wjakob). +Significant features and/or improvements to the code were contributed by +Jonas Adler, +Lori A. Burns, +Sylvain Corlay, +Trent Houliston, +Axel Huebl, +@hulucc, +Sergey Lyskov +Johan Mabille, +Tomasz Miąsko, +Dean Moldovan, +Ben Pritchard, +Jason Rhinelander, +Boris Schäling, +Pim Schellart, +Henry Schreiner, +Ivan Smirnov, and +Patrick Stewart. + +### License + +pybind11 is provided under a BSD-style license that can be found in the +``LICENSE`` file. By using, distributing, or contributing to this project, +you agree to the terms and conditions of this license. diff --git a/wrap/python/pybind11/docs/Doxyfile b/wrap/python/pybind11/docs/Doxyfile new file mode 100644 index 000000000..1b9d1297c --- /dev/null +++ b/wrap/python/pybind11/docs/Doxyfile @@ -0,0 +1,20 @@ +PROJECT_NAME = pybind11 +INPUT = ../include/pybind11/ +RECURSIVE = YES + +GENERATE_HTML = NO +GENERATE_LATEX = NO +GENERATE_XML = YES +XML_OUTPUT = .build/doxygenxml +XML_PROGRAMLISTING = YES + +MACRO_EXPANSION = YES +EXPAND_ONLY_PREDEF = YES +EXPAND_AS_DEFINED = PYBIND11_RUNTIME_EXCEPTION + +ALIASES = "rst=\verbatim embed:rst" +ALIASES += "endrst=\endverbatim" + +QUIET = YES +WARNINGS = YES +WARN_IF_UNDOCUMENTED = NO diff --git a/wrap/python/pybind11/docs/_static/theme_overrides.css b/wrap/python/pybind11/docs/_static/theme_overrides.css new file mode 100644 index 000000000..1071809fa --- /dev/null +++ b/wrap/python/pybind11/docs/_static/theme_overrides.css @@ -0,0 +1,11 @@ +.wy-table-responsive table td, +.wy-table-responsive table th { + white-space: initial !important; +} +.rst-content table.docutils td { + vertical-align: top !important; +} +div[class^='highlight'] pre { + white-space: pre; + white-space: pre-wrap; +} diff --git a/wrap/python/pybind11/docs/advanced/cast/chrono.rst b/wrap/python/pybind11/docs/advanced/cast/chrono.rst new file mode 100644 index 000000000..8c6b3d7e5 --- /dev/null +++ b/wrap/python/pybind11/docs/advanced/cast/chrono.rst @@ -0,0 +1,81 @@ +Chrono +====== + +When including the additional header file :file:`pybind11/chrono.h` conversions +from C++11 chrono datatypes to python datetime objects are automatically enabled. +This header also enables conversions of python floats (often from sources such +as ``time.monotonic()``, ``time.perf_counter()`` and ``time.process_time()``) +into durations. + +An overview of clocks in C++11 +------------------------------ + +A point of confusion when using these conversions is the differences between +clocks provided in C++11. There are three clock types defined by the C++11 +standard and users can define their own if needed. Each of these clocks have +different properties and when converting to and from python will give different +results. + +The first clock defined by the standard is ``std::chrono::system_clock``. This +clock measures the current date and time. However, this clock changes with to +updates to the operating system time. For example, if your time is synchronised +with a time server this clock will change. This makes this clock a poor choice +for timing purposes but good for measuring the wall time. + +The second clock defined in the standard is ``std::chrono::steady_clock``. +This clock ticks at a steady rate and is never adjusted. This makes it excellent +for timing purposes, however the value in this clock does not correspond to the +current date and time. Often this clock will be the amount of time your system +has been on, although it does not have to be. This clock will never be the same +clock as the system clock as the system clock can change but steady clocks +cannot. + +The third clock defined in the standard is ``std::chrono::high_resolution_clock``. +This clock is the clock that has the highest resolution out of the clocks in the +system. It is normally a typedef to either the system clock or the steady clock +but can be its own independent clock. This is important as when using these +conversions as the types you get in python for this clock might be different +depending on the system. +If it is a typedef of the system clock, python will get datetime objects, but if +it is a different clock they will be timedelta objects. + +Provided conversions +-------------------- + +.. rubric:: C++ to Python + +- ``std::chrono::system_clock::time_point`` → ``datetime.datetime`` + System clock times are converted to python datetime instances. They are + in the local timezone, but do not have any timezone information attached + to them (they are naive datetime objects). + +- ``std::chrono::duration`` → ``datetime.timedelta`` + Durations are converted to timedeltas, any precision in the duration + greater than microseconds is lost by rounding towards zero. + +- ``std::chrono::[other_clocks]::time_point`` → ``datetime.timedelta`` + Any clock time that is not the system clock is converted to a time delta. + This timedelta measures the time from the clocks epoch to now. + +.. rubric:: Python to C++ + +- ``datetime.datetime`` → ``std::chrono::system_clock::time_point`` + Date/time objects are converted into system clock timepoints. Any + timezone information is ignored and the type is treated as a naive + object. + +- ``datetime.timedelta`` → ``std::chrono::duration`` + Time delta are converted into durations with microsecond precision. + +- ``datetime.timedelta`` → ``std::chrono::[other_clocks]::time_point`` + Time deltas that are converted into clock timepoints are treated as + the amount of time from the start of the clocks epoch. + +- ``float`` → ``std::chrono::duration`` + Floats that are passed to C++ as durations be interpreted as a number of + seconds. These will be converted to the duration using ``duration_cast`` + from the float. + +- ``float`` → ``std::chrono::[other_clocks]::time_point`` + Floats that are passed to C++ as time points will be interpreted as the + number of seconds from the start of the clocks epoch. diff --git a/wrap/python/pybind11/docs/advanced/cast/custom.rst b/wrap/python/pybind11/docs/advanced/cast/custom.rst new file mode 100644 index 000000000..e4f99ac5b --- /dev/null +++ b/wrap/python/pybind11/docs/advanced/cast/custom.rst @@ -0,0 +1,91 @@ +Custom type casters +=================== + +In very rare cases, applications may require custom type casters that cannot be +expressed using the abstractions provided by pybind11, thus requiring raw +Python C API calls. This is fairly advanced usage and should only be pursued by +experts who are familiar with the intricacies of Python reference counting. + +The following snippets demonstrate how this works for a very simple ``inty`` +type that that should be convertible from Python types that provide a +``__int__(self)`` method. + +.. code-block:: cpp + + struct inty { long long_value; }; + + void print(inty s) { + std::cout << s.long_value << std::endl; + } + +The following Python snippet demonstrates the intended usage from the Python side: + +.. code-block:: python + + class A: + def __int__(self): + return 123 + + from example import print + print(A()) + +To register the necessary conversion routines, it is necessary to add +a partial overload to the ``pybind11::detail::type_caster`` template. +Although this is an implementation detail, adding partial overloads to this +type is explicitly allowed. + +.. code-block:: cpp + + namespace pybind11 { namespace detail { + template <> struct type_caster { + public: + /** + * This macro establishes the name 'inty' in + * function signatures and declares a local variable + * 'value' of type inty + */ + PYBIND11_TYPE_CASTER(inty, _("inty")); + + /** + * Conversion part 1 (Python->C++): convert a PyObject into a inty + * instance or return false upon failure. The second argument + * indicates whether implicit conversions should be applied. + */ + bool load(handle src, bool) { + /* Extract PyObject from handle */ + PyObject *source = src.ptr(); + /* Try converting into a Python integer value */ + PyObject *tmp = PyNumber_Long(source); + if (!tmp) + return false; + /* Now try to convert into a C++ int */ + value.long_value = PyLong_AsLong(tmp); + Py_DECREF(tmp); + /* Ensure return code was OK (to avoid out-of-range errors etc) */ + return !(value.long_value == -1 && !PyErr_Occurred()); + } + + /** + * Conversion part 2 (C++ -> Python): convert an inty instance into + * a Python object. The second and third arguments are used to + * indicate the return value policy and parent object (for + * ``return_value_policy::reference_internal``) and are generally + * ignored by implicit casters. + */ + static handle cast(inty src, return_value_policy /* policy */, handle /* parent */) { + return PyLong_FromLong(src.long_value); + } + }; + }} // namespace pybind11::detail + +.. note:: + + A ``type_caster`` defined with ``PYBIND11_TYPE_CASTER(T, ...)`` requires + that ``T`` is default-constructible (``value`` is first default constructed + and then ``load()`` assigns to it). + +.. warning:: + + When using custom type casters, it's important to declare them consistently + in every compilation unit of the Python extension module. Otherwise, + undefined behavior can ensue. diff --git a/wrap/python/pybind11/docs/advanced/cast/eigen.rst b/wrap/python/pybind11/docs/advanced/cast/eigen.rst new file mode 100644 index 000000000..59ba08c3c --- /dev/null +++ b/wrap/python/pybind11/docs/advanced/cast/eigen.rst @@ -0,0 +1,310 @@ +Eigen +##### + +`Eigen `_ is C++ header-based library for dense and +sparse linear algebra. Due to its popularity and widespread adoption, pybind11 +provides transparent conversion and limited mapping support between Eigen and +Scientific Python linear algebra data types. + +To enable the built-in Eigen support you must include the optional header file +:file:`pybind11/eigen.h`. + +Pass-by-value +============= + +When binding a function with ordinary Eigen dense object arguments (for +example, ``Eigen::MatrixXd``), pybind11 will accept any input value that is +already (or convertible to) a ``numpy.ndarray`` with dimensions compatible with +the Eigen type, copy its values into a temporary Eigen variable of the +appropriate type, then call the function with this temporary variable. + +Sparse matrices are similarly copied to or from +``scipy.sparse.csr_matrix``/``scipy.sparse.csc_matrix`` objects. + +Pass-by-reference +================= + +One major limitation of the above is that every data conversion implicitly +involves a copy, which can be both expensive (for large matrices) and disallows +binding functions that change their (Matrix) arguments. Pybind11 allows you to +work around this by using Eigen's ``Eigen::Ref`` class much as you +would when writing a function taking a generic type in Eigen itself (subject to +some limitations discussed below). + +When calling a bound function accepting a ``Eigen::Ref`` +type, pybind11 will attempt to avoid copying by using an ``Eigen::Map`` object +that maps into the source ``numpy.ndarray`` data: this requires both that the +data types are the same (e.g. ``dtype='float64'`` and ``MatrixType::Scalar`` is +``double``); and that the storage is layout compatible. The latter limitation +is discussed in detail in the section below, and requires careful +consideration: by default, numpy matrices and Eigen matrices are *not* storage +compatible. + +If the numpy matrix cannot be used as is (either because its types differ, e.g. +passing an array of integers to an Eigen parameter requiring doubles, or +because the storage is incompatible), pybind11 makes a temporary copy and +passes the copy instead. + +When a bound function parameter is instead ``Eigen::Ref`` (note the +lack of ``const``), pybind11 will only allow the function to be called if it +can be mapped *and* if the numpy array is writeable (that is +``a.flags.writeable`` is true). Any access (including modification) made to +the passed variable will be transparently carried out directly on the +``numpy.ndarray``. + +This means you can can write code such as the following and have it work as +expected: + +.. code-block:: cpp + + void scale_by_2(Eigen::Ref v) { + v *= 2; + } + +Note, however, that you will likely run into limitations due to numpy and +Eigen's difference default storage order for data; see the below section on +:ref:`storage_orders` for details on how to bind code that won't run into such +limitations. + +.. note:: + + Passing by reference is not supported for sparse types. + +Returning values to Python +========================== + +When returning an ordinary dense Eigen matrix type to numpy (e.g. +``Eigen::MatrixXd`` or ``Eigen::RowVectorXf``) pybind11 keeps the matrix and +returns a numpy array that directly references the Eigen matrix: no copy of the +data is performed. The numpy array will have ``array.flags.owndata`` set to +``False`` to indicate that it does not own the data, and the lifetime of the +stored Eigen matrix will be tied to the returned ``array``. + +If you bind a function with a non-reference, ``const`` return type (e.g. +``const Eigen::MatrixXd``), the same thing happens except that pybind11 also +sets the numpy array's ``writeable`` flag to false. + +If you return an lvalue reference or pointer, the usual pybind11 rules apply, +as dictated by the binding function's return value policy (see the +documentation on :ref:`return_value_policies` for full details). That means, +without an explicit return value policy, lvalue references will be copied and +pointers will be managed by pybind11. In order to avoid copying, you should +explicitly specify an appropriate return value policy, as in the following +example: + +.. code-block:: cpp + + class MyClass { + Eigen::MatrixXd big_mat = Eigen::MatrixXd::Zero(10000, 10000); + public: + Eigen::MatrixXd &getMatrix() { return big_mat; } + const Eigen::MatrixXd &viewMatrix() { return big_mat; } + }; + + // Later, in binding code: + py::class_(m, "MyClass") + .def(py::init<>()) + .def("copy_matrix", &MyClass::getMatrix) // Makes a copy! + .def("get_matrix", &MyClass::getMatrix, py::return_value_policy::reference_internal) + .def("view_matrix", &MyClass::viewMatrix, py::return_value_policy::reference_internal) + ; + +.. code-block:: python + + a = MyClass() + m = a.get_matrix() # flags.writeable = True, flags.owndata = False + v = a.view_matrix() # flags.writeable = False, flags.owndata = False + c = a.copy_matrix() # flags.writeable = True, flags.owndata = True + # m[5,6] and v[5,6] refer to the same element, c[5,6] does not. + +Note in this example that ``py::return_value_policy::reference_internal`` is +used to tie the life of the MyClass object to the life of the returned arrays. + +You may also return an ``Eigen::Ref``, ``Eigen::Map`` or other map-like Eigen +object (for example, the return value of ``matrix.block()`` and related +methods) that map into a dense Eigen type. When doing so, the default +behaviour of pybind11 is to simply reference the returned data: you must take +care to ensure that this data remains valid! You may ask pybind11 to +explicitly *copy* such a return value by using the +``py::return_value_policy::copy`` policy when binding the function. You may +also use ``py::return_value_policy::reference_internal`` or a +``py::keep_alive`` to ensure the data stays valid as long as the returned numpy +array does. + +When returning such a reference of map, pybind11 additionally respects the +readonly-status of the returned value, marking the numpy array as non-writeable +if the reference or map was itself read-only. + +.. note:: + + Sparse types are always copied when returned. + +.. _storage_orders: + +Storage orders +============== + +Passing arguments via ``Eigen::Ref`` has some limitations that you must be +aware of in order to effectively pass matrices by reference. First and +foremost is that the default ``Eigen::Ref`` class requires +contiguous storage along columns (for column-major types, the default in Eigen) +or rows if ``MatrixType`` is specifically an ``Eigen::RowMajor`` storage type. +The former, Eigen's default, is incompatible with ``numpy``'s default row-major +storage, and so you will not be able to pass numpy arrays to Eigen by reference +without making one of two changes. + +(Note that this does not apply to vectors (or column or row matrices): for such +types the "row-major" and "column-major" distinction is meaningless). + +The first approach is to change the use of ``Eigen::Ref`` to the +more general ``Eigen::Ref>`` (or similar type with a fully dynamic stride type in the +third template argument). Since this is a rather cumbersome type, pybind11 +provides a ``py::EigenDRef`` type alias for your convenience (along +with EigenDMap for the equivalent Map, and EigenDStride for just the stride +type). + +This type allows Eigen to map into any arbitrary storage order. This is not +the default in Eigen for performance reasons: contiguous storage allows +vectorization that cannot be done when storage is not known to be contiguous at +compile time. The default ``Eigen::Ref`` stride type allows non-contiguous +storage along the outer dimension (that is, the rows of a column-major matrix +or columns of a row-major matrix), but not along the inner dimension. + +This type, however, has the added benefit of also being able to map numpy array +slices. For example, the following (contrived) example uses Eigen with a numpy +slice to multiply by 2 all coefficients that are both on even rows (0, 2, 4, +...) and in columns 2, 5, or 8: + +.. code-block:: cpp + + m.def("scale", [](py::EigenDRef m, double c) { m *= c; }); + +.. code-block:: python + + # a = np.array(...) + scale_by_2(myarray[0::2, 2:9:3]) + +The second approach to avoid copying is more intrusive: rearranging the +underlying data types to not run into the non-contiguous storage problem in the +first place. In particular, that means using matrices with ``Eigen::RowMajor`` +storage, where appropriate, such as: + +.. code-block:: cpp + + using RowMatrixXd = Eigen::Matrix; + // Use RowMatrixXd instead of MatrixXd + +Now bound functions accepting ``Eigen::Ref`` arguments will be +callable with numpy's (default) arrays without involving a copying. + +You can, alternatively, change the storage order that numpy arrays use by +adding the ``order='F'`` option when creating an array: + +.. code-block:: python + + myarray = np.array(source, order='F') + +Such an object will be passable to a bound function accepting an +``Eigen::Ref`` (or similar column-major Eigen type). + +One major caveat with this approach, however, is that it is not entirely as +easy as simply flipping all Eigen or numpy usage from one to the other: some +operations may alter the storage order of a numpy array. For example, ``a2 = +array.transpose()`` results in ``a2`` being a view of ``array`` that references +the same data, but in the opposite storage order! + +While this approach allows fully optimized vectorized calculations in Eigen, it +cannot be used with array slices, unlike the first approach. + +When *returning* a matrix to Python (either a regular matrix, a reference via +``Eigen::Ref<>``, or a map/block into a matrix), no special storage +consideration is required: the created numpy array will have the required +stride that allows numpy to properly interpret the array, whatever its storage +order. + +Failing rather than copying +=========================== + +The default behaviour when binding ``Eigen::Ref`` Eigen +references is to copy matrix values when passed a numpy array that does not +conform to the element type of ``MatrixType`` or does not have a compatible +stride layout. If you want to explicitly avoid copying in such a case, you +should bind arguments using the ``py::arg().noconvert()`` annotation (as +described in the :ref:`nonconverting_arguments` documentation). + +The following example shows an example of arguments that don't allow data +copying to take place: + +.. code-block:: cpp + + // The method and function to be bound: + class MyClass { + // ... + double some_method(const Eigen::Ref &matrix) { /* ... */ } + }; + float some_function(const Eigen::Ref &big, + const Eigen::Ref &small) { + // ... + } + + // The associated binding code: + using namespace pybind11::literals; // for "arg"_a + py::class_(m, "MyClass") + // ... other class definitions + .def("some_method", &MyClass::some_method, py::arg().noconvert()); + + m.def("some_function", &some_function, + "big"_a.noconvert(), // <- Don't allow copying for this arg + "small"_a // <- This one can be copied if needed + ); + +With the above binding code, attempting to call the the ``some_method(m)`` +method on a ``MyClass`` object, or attempting to call ``some_function(m, m2)`` +will raise a ``RuntimeError`` rather than making a temporary copy of the array. +It will, however, allow the ``m2`` argument to be copied into a temporary if +necessary. + +Note that explicitly specifying ``.noconvert()`` is not required for *mutable* +Eigen references (e.g. ``Eigen::Ref`` without ``const`` on the +``MatrixXd``): mutable references will never be called with a temporary copy. + +Vectors versus column/row matrices +================================== + +Eigen and numpy have fundamentally different notions of a vector. In Eigen, a +vector is simply a matrix with the number of columns or rows set to 1 at +compile time (for a column vector or row vector, respectively). Numpy, in +contrast, has comparable 2-dimensional 1xN and Nx1 arrays, but *also* has +1-dimensional arrays of size N. + +When passing a 2-dimensional 1xN or Nx1 array to Eigen, the Eigen type must +have matching dimensions: That is, you cannot pass a 2-dimensional Nx1 numpy +array to an Eigen value expecting a row vector, or a 1xN numpy array as a +column vector argument. + +On the other hand, pybind11 allows you to pass 1-dimensional arrays of length N +as Eigen parameters. If the Eigen type can hold a column vector of length N it +will be passed as such a column vector. If not, but the Eigen type constraints +will accept a row vector, it will be passed as a row vector. (The column +vector takes precedence when both are supported, for example, when passing a +1D numpy array to a MatrixXd argument). Note that the type need not be +explicitly a vector: it is permitted to pass a 1D numpy array of size 5 to an +Eigen ``Matrix``: you would end up with a 1x5 Eigen matrix. +Passing the same to an ``Eigen::MatrixXd`` would result in a 5x1 Eigen matrix. + +When returning an Eigen vector to numpy, the conversion is ambiguous: a row +vector of length 4 could be returned as either a 1D array of length 4, or as a +2D array of size 1x4. When encountering such a situation, pybind11 compromises +by considering the returned Eigen type: if it is a compile-time vector--that +is, the type has either the number of rows or columns set to 1 at compile +time--pybind11 converts to a 1D numpy array when returning the value. For +instances that are a vector only at run-time (e.g. ``MatrixXd``, +``Matrix``), pybind11 returns the vector as a 2D array to +numpy. If this isn't want you want, you can use ``array.reshape(...)`` to get +a view of the same data in the desired dimensions. + +.. seealso:: + + The file :file:`tests/test_eigen.cpp` contains a complete example that + shows how to pass Eigen sparse and dense data types in more detail. diff --git a/wrap/python/pybind11/docs/advanced/cast/functional.rst b/wrap/python/pybind11/docs/advanced/cast/functional.rst new file mode 100644 index 000000000..d9b460575 --- /dev/null +++ b/wrap/python/pybind11/docs/advanced/cast/functional.rst @@ -0,0 +1,109 @@ +Functional +########## + +The following features must be enabled by including :file:`pybind11/functional.h`. + + +Callbacks and passing anonymous functions +========================================= + +The C++11 standard brought lambda functions and the generic polymorphic +function wrapper ``std::function<>`` to the C++ programming language, which +enable powerful new ways of working with functions. Lambda functions come in +two flavors: stateless lambda function resemble classic function pointers that +link to an anonymous piece of code, while stateful lambda functions +additionally depend on captured variables that are stored in an anonymous +*lambda closure object*. + +Here is a simple example of a C++ function that takes an arbitrary function +(stateful or stateless) with signature ``int -> int`` as an argument and runs +it with the value 10. + +.. code-block:: cpp + + int func_arg(const std::function &f) { + return f(10); + } + +The example below is more involved: it takes a function of signature ``int -> int`` +and returns another function of the same kind. The return value is a stateful +lambda function, which stores the value ``f`` in the capture object and adds 1 to +its return value upon execution. + +.. code-block:: cpp + + std::function func_ret(const std::function &f) { + return [f](int i) { + return f(i) + 1; + }; + } + +This example demonstrates using python named parameters in C++ callbacks which +requires using ``py::cpp_function`` as a wrapper. Usage is similar to defining +methods of classes: + +.. code-block:: cpp + + py::cpp_function func_cpp() { + return py::cpp_function([](int i) { return i+1; }, + py::arg("number")); + } + +After including the extra header file :file:`pybind11/functional.h`, it is almost +trivial to generate binding code for all of these functions. + +.. code-block:: cpp + + #include + + PYBIND11_MODULE(example, m) { + m.def("func_arg", &func_arg); + m.def("func_ret", &func_ret); + m.def("func_cpp", &func_cpp); + } + +The following interactive session shows how to call them from Python. + +.. code-block:: pycon + + $ python + >>> import example + >>> def square(i): + ... return i * i + ... + >>> example.func_arg(square) + 100L + >>> square_plus_1 = example.func_ret(square) + >>> square_plus_1(4) + 17L + >>> plus_1 = func_cpp() + >>> plus_1(number=43) + 44L + +.. warning:: + + Keep in mind that passing a function from C++ to Python (or vice versa) + will instantiate a piece of wrapper code that translates function + invocations between the two languages. Naturally, this translation + increases the computational cost of each function call somewhat. A + problematic situation can arise when a function is copied back and forth + between Python and C++ many times in a row, in which case the underlying + wrappers will accumulate correspondingly. The resulting long sequence of + C++ -> Python -> C++ -> ... roundtrips can significantly decrease + performance. + + There is one exception: pybind11 detects case where a stateless function + (i.e. a function pointer or a lambda function without captured variables) + is passed as an argument to another C++ function exposed in Python. In this + case, there is no overhead. Pybind11 will extract the underlying C++ + function pointer from the wrapped function to sidestep a potential C++ -> + Python -> C++ roundtrip. This is demonstrated in :file:`tests/test_callbacks.cpp`. + +.. note:: + + This functionality is very useful when generating bindings for callbacks in + C++ libraries (e.g. GUI libraries, asynchronous networking libraries, etc.). + + The file :file:`tests/test_callbacks.cpp` contains a complete example + that demonstrates how to work with callbacks and anonymous functions in + more detail. diff --git a/wrap/python/pybind11/docs/advanced/cast/index.rst b/wrap/python/pybind11/docs/advanced/cast/index.rst new file mode 100644 index 000000000..54c10570b --- /dev/null +++ b/wrap/python/pybind11/docs/advanced/cast/index.rst @@ -0,0 +1,42 @@ +Type conversions +################ + +Apart from enabling cross-language function calls, a fundamental problem +that a binding tool like pybind11 must address is to provide access to +native Python types in C++ and vice versa. There are three fundamentally +different ways to do this—which approach is preferable for a particular type +depends on the situation at hand. + +1. Use a native C++ type everywhere. In this case, the type must be wrapped + using pybind11-generated bindings so that Python can interact with it. + +2. Use a native Python type everywhere. It will need to be wrapped so that + C++ functions can interact with it. + +3. Use a native C++ type on the C++ side and a native Python type on the + Python side. pybind11 refers to this as a *type conversion*. + + Type conversions are the most "natural" option in the sense that native + (non-wrapped) types are used everywhere. The main downside is that a copy + of the data must be made on every Python ↔ C++ transition: this is + needed since the C++ and Python versions of the same type generally won't + have the same memory layout. + + pybind11 can perform many kinds of conversions automatically. An overview + is provided in the table ":ref:`conversion_table`". + +The following subsections discuss the differences between these options in more +detail. The main focus in this section is on type conversions, which represent +the last case of the above list. + +.. toctree:: + :maxdepth: 1 + + overview + strings + stl + functional + chrono + eigen + custom + diff --git a/wrap/python/pybind11/docs/advanced/cast/overview.rst b/wrap/python/pybind11/docs/advanced/cast/overview.rst new file mode 100644 index 000000000..b0e32a52f --- /dev/null +++ b/wrap/python/pybind11/docs/advanced/cast/overview.rst @@ -0,0 +1,165 @@ +Overview +######## + +.. rubric:: 1. Native type in C++, wrapper in Python + +Exposing a custom C++ type using :class:`py::class_` was covered in detail +in the :doc:`/classes` section. There, the underlying data structure is +always the original C++ class while the :class:`py::class_` wrapper provides +a Python interface. Internally, when an object like this is sent from C++ to +Python, pybind11 will just add the outer wrapper layer over the native C++ +object. Getting it back from Python is just a matter of peeling off the +wrapper. + +.. rubric:: 2. Wrapper in C++, native type in Python + +This is the exact opposite situation. Now, we have a type which is native to +Python, like a ``tuple`` or a ``list``. One way to get this data into C++ is +with the :class:`py::object` family of wrappers. These are explained in more +detail in the :doc:`/advanced/pycpp/object` section. We'll just give a quick +example here: + +.. code-block:: cpp + + void print_list(py::list my_list) { + for (auto item : my_list) + std::cout << item << " "; + } + +.. code-block:: pycon + + >>> print_list([1, 2, 3]) + 1 2 3 + +The Python ``list`` is not converted in any way -- it's just wrapped in a C++ +:class:`py::list` class. At its core it's still a Python object. Copying a +:class:`py::list` will do the usual reference-counting like in Python. +Returning the object to Python will just remove the thin wrapper. + +.. rubric:: 3. Converting between native C++ and Python types + +In the previous two cases we had a native type in one language and a wrapper in +the other. Now, we have native types on both sides and we convert between them. + +.. code-block:: cpp + + void print_vector(const std::vector &v) { + for (auto item : v) + std::cout << item << "\n"; + } + +.. code-block:: pycon + + >>> print_vector([1, 2, 3]) + 1 2 3 + +In this case, pybind11 will construct a new ``std::vector`` and copy each +element from the Python ``list``. The newly constructed object will be passed +to ``print_vector``. The same thing happens in the other direction: a new +``list`` is made to match the value returned from C++. + +Lots of these conversions are supported out of the box, as shown in the table +below. They are very convenient, but keep in mind that these conversions are +fundamentally based on copying data. This is perfectly fine for small immutable +types but it may become quite expensive for large data structures. This can be +avoided by overriding the automatic conversion with a custom wrapper (i.e. the +above-mentioned approach 1). This requires some manual effort and more details +are available in the :ref:`opaque` section. + +.. _conversion_table: + +List of all builtin conversions +------------------------------- + +The following basic data types are supported out of the box (some may require +an additional extension header to be included). To pass other data structures +as arguments and return values, refer to the section on binding :ref:`classes`. + ++------------------------------------+---------------------------+-------------------------------+ +| Data type | Description | Header file | ++====================================+===========================+===============================+ +| ``int8_t``, ``uint8_t`` | 8-bit integers | :file:`pybind11/pybind11.h` | ++------------------------------------+---------------------------+-------------------------------+ +| ``int16_t``, ``uint16_t`` | 16-bit integers | :file:`pybind11/pybind11.h` | ++------------------------------------+---------------------------+-------------------------------+ +| ``int32_t``, ``uint32_t`` | 32-bit integers | :file:`pybind11/pybind11.h` | ++------------------------------------+---------------------------+-------------------------------+ +| ``int64_t``, ``uint64_t`` | 64-bit integers | :file:`pybind11/pybind11.h` | ++------------------------------------+---------------------------+-------------------------------+ +| ``ssize_t``, ``size_t`` | Platform-dependent size | :file:`pybind11/pybind11.h` | ++------------------------------------+---------------------------+-------------------------------+ +| ``float``, ``double`` | Floating point types | :file:`pybind11/pybind11.h` | ++------------------------------------+---------------------------+-------------------------------+ +| ``bool`` | Two-state Boolean type | :file:`pybind11/pybind11.h` | ++------------------------------------+---------------------------+-------------------------------+ +| ``char`` | Character literal | :file:`pybind11/pybind11.h` | ++------------------------------------+---------------------------+-------------------------------+ +| ``char16_t`` | UTF-16 character literal | :file:`pybind11/pybind11.h` | ++------------------------------------+---------------------------+-------------------------------+ +| ``char32_t`` | UTF-32 character literal | :file:`pybind11/pybind11.h` | ++------------------------------------+---------------------------+-------------------------------+ +| ``wchar_t`` | Wide character literal | :file:`pybind11/pybind11.h` | ++------------------------------------+---------------------------+-------------------------------+ +| ``const char *`` | UTF-8 string literal | :file:`pybind11/pybind11.h` | ++------------------------------------+---------------------------+-------------------------------+ +| ``const char16_t *`` | UTF-16 string literal | :file:`pybind11/pybind11.h` | ++------------------------------------+---------------------------+-------------------------------+ +| ``const char32_t *`` | UTF-32 string literal | :file:`pybind11/pybind11.h` | ++------------------------------------+---------------------------+-------------------------------+ +| ``const wchar_t *`` | Wide string literal | :file:`pybind11/pybind11.h` | ++------------------------------------+---------------------------+-------------------------------+ +| ``std::string`` | STL dynamic UTF-8 string | :file:`pybind11/pybind11.h` | ++------------------------------------+---------------------------+-------------------------------+ +| ``std::u16string`` | STL dynamic UTF-16 string | :file:`pybind11/pybind11.h` | ++------------------------------------+---------------------------+-------------------------------+ +| ``std::u32string`` | STL dynamic UTF-32 string | :file:`pybind11/pybind11.h` | ++------------------------------------+---------------------------+-------------------------------+ +| ``std::wstring`` | STL dynamic wide string | :file:`pybind11/pybind11.h` | ++------------------------------------+---------------------------+-------------------------------+ +| ``std::string_view``, | STL C++17 string views | :file:`pybind11/pybind11.h` | +| ``std::u16string_view``, etc. | | | ++------------------------------------+---------------------------+-------------------------------+ +| ``std::pair`` | Pair of two custom types | :file:`pybind11/pybind11.h` | ++------------------------------------+---------------------------+-------------------------------+ +| ``std::tuple<...>`` | Arbitrary tuple of types | :file:`pybind11/pybind11.h` | ++------------------------------------+---------------------------+-------------------------------+ +| ``std::reference_wrapper<...>`` | Reference type wrapper | :file:`pybind11/pybind11.h` | ++------------------------------------+---------------------------+-------------------------------+ +| ``std::complex`` | Complex numbers | :file:`pybind11/complex.h` | ++------------------------------------+---------------------------+-------------------------------+ +| ``std::array`` | STL static array | :file:`pybind11/stl.h` | ++------------------------------------+---------------------------+-------------------------------+ +| ``std::vector`` | STL dynamic array | :file:`pybind11/stl.h` | ++------------------------------------+---------------------------+-------------------------------+ +| ``std::deque`` | STL double-ended queue | :file:`pybind11/stl.h` | ++------------------------------------+---------------------------+-------------------------------+ +| ``std::valarray`` | STL value array | :file:`pybind11/stl.h` | ++------------------------------------+---------------------------+-------------------------------+ +| ``std::list`` | STL linked list | :file:`pybind11/stl.h` | ++------------------------------------+---------------------------+-------------------------------+ +| ``std::map`` | STL ordered map | :file:`pybind11/stl.h` | ++------------------------------------+---------------------------+-------------------------------+ +| ``std::unordered_map`` | STL unordered map | :file:`pybind11/stl.h` | ++------------------------------------+---------------------------+-------------------------------+ +| ``std::set`` | STL ordered set | :file:`pybind11/stl.h` | ++------------------------------------+---------------------------+-------------------------------+ +| ``std::unordered_set`` | STL unordered set | :file:`pybind11/stl.h` | ++------------------------------------+---------------------------+-------------------------------+ +| ``std::optional`` | STL optional type (C++17) | :file:`pybind11/stl.h` | ++------------------------------------+---------------------------+-------------------------------+ +| ``std::experimental::optional`` | STL optional type (exp.) | :file:`pybind11/stl.h` | ++------------------------------------+---------------------------+-------------------------------+ +| ``std::variant<...>`` | Type-safe union (C++17) | :file:`pybind11/stl.h` | ++------------------------------------+---------------------------+-------------------------------+ +| ``std::function<...>`` | STL polymorphic function | :file:`pybind11/functional.h` | ++------------------------------------+---------------------------+-------------------------------+ +| ``std::chrono::duration<...>`` | STL time duration | :file:`pybind11/chrono.h` | ++------------------------------------+---------------------------+-------------------------------+ +| ``std::chrono::time_point<...>`` | STL date/time | :file:`pybind11/chrono.h` | ++------------------------------------+---------------------------+-------------------------------+ +| ``Eigen::Matrix<...>`` | Eigen: dense matrix | :file:`pybind11/eigen.h` | ++------------------------------------+---------------------------+-------------------------------+ +| ``Eigen::Map<...>`` | Eigen: mapped memory | :file:`pybind11/eigen.h` | ++------------------------------------+---------------------------+-------------------------------+ +| ``Eigen::SparseMatrix<...>`` | Eigen: sparse matrix | :file:`pybind11/eigen.h` | ++------------------------------------+---------------------------+-------------------------------+ diff --git a/wrap/python/pybind11/docs/advanced/cast/stl.rst b/wrap/python/pybind11/docs/advanced/cast/stl.rst new file mode 100644 index 000000000..e48409f02 --- /dev/null +++ b/wrap/python/pybind11/docs/advanced/cast/stl.rst @@ -0,0 +1,240 @@ +STL containers +############## + +Automatic conversion +==================== + +When including the additional header file :file:`pybind11/stl.h`, conversions +between ``std::vector<>``/``std::deque<>``/``std::list<>``/``std::array<>``, +``std::set<>``/``std::unordered_set<>``, and +``std::map<>``/``std::unordered_map<>`` and the Python ``list``, ``set`` and +``dict`` data structures are automatically enabled. The types ``std::pair<>`` +and ``std::tuple<>`` are already supported out of the box with just the core +:file:`pybind11/pybind11.h` header. + +The major downside of these implicit conversions is that containers must be +converted (i.e. copied) on every Python->C++ and C++->Python transition, which +can have implications on the program semantics and performance. Please read the +next sections for more details and alternative approaches that avoid this. + +.. note:: + + Arbitrary nesting of any of these types is possible. + +.. seealso:: + + The file :file:`tests/test_stl.cpp` contains a complete + example that demonstrates how to pass STL data types in more detail. + +.. _cpp17_container_casters: + +C++17 library containers +======================== + +The :file:`pybind11/stl.h` header also includes support for ``std::optional<>`` +and ``std::variant<>``. These require a C++17 compiler and standard library. +In C++14 mode, ``std::experimental::optional<>`` is supported if available. + +Various versions of these containers also exist for C++11 (e.g. in Boost). +pybind11 provides an easy way to specialize the ``type_caster`` for such +types: + +.. code-block:: cpp + + // `boost::optional` as an example -- can be any `std::optional`-like container + namespace pybind11 { namespace detail { + template + struct type_caster> : optional_caster> {}; + }} + +The above should be placed in a header file and included in all translation units +where automatic conversion is needed. Similarly, a specialization can be provided +for custom variant types: + +.. code-block:: cpp + + // `boost::variant` as an example -- can be any `std::variant`-like container + namespace pybind11 { namespace detail { + template + struct type_caster> : variant_caster> {}; + + // Specifies the function used to visit the variant -- `apply_visitor` instead of `visit` + template <> + struct visit_helper { + template + static auto call(Args &&...args) -> decltype(boost::apply_visitor(args...)) { + return boost::apply_visitor(args...); + } + }; + }} // namespace pybind11::detail + +The ``visit_helper`` specialization is not required if your ``name::variant`` provides +a ``name::visit()`` function. For any other function name, the specialization must be +included to tell pybind11 how to visit the variant. + +.. note:: + + pybind11 only supports the modern implementation of ``boost::variant`` + which makes use of variadic templates. This requires Boost 1.56 or newer. + Additionally, on Windows, MSVC 2017 is required because ``boost::variant`` + falls back to the old non-variadic implementation on MSVC 2015. + +.. _opaque: + +Making opaque types +=================== + +pybind11 heavily relies on a template matching mechanism to convert parameters +and return values that are constructed from STL data types such as vectors, +linked lists, hash tables, etc. This even works in a recursive manner, for +instance to deal with lists of hash maps of pairs of elementary and custom +types, etc. + +However, a fundamental limitation of this approach is that internal conversions +between Python and C++ types involve a copy operation that prevents +pass-by-reference semantics. What does this mean? + +Suppose we bind the following function + +.. code-block:: cpp + + void append_1(std::vector &v) { + v.push_back(1); + } + +and call it from Python, the following happens: + +.. code-block:: pycon + + >>> v = [5, 6] + >>> append_1(v) + >>> print(v) + [5, 6] + +As you can see, when passing STL data structures by reference, modifications +are not propagated back the Python side. A similar situation arises when +exposing STL data structures using the ``def_readwrite`` or ``def_readonly`` +functions: + +.. code-block:: cpp + + /* ... definition ... */ + + class MyClass { + std::vector contents; + }; + + /* ... binding code ... */ + + py::class_(m, "MyClass") + .def(py::init<>()) + .def_readwrite("contents", &MyClass::contents); + +In this case, properties can be read and written in their entirety. However, an +``append`` operation involving such a list type has no effect: + +.. code-block:: pycon + + >>> m = MyClass() + >>> m.contents = [5, 6] + >>> print(m.contents) + [5, 6] + >>> m.contents.append(7) + >>> print(m.contents) + [5, 6] + +Finally, the involved copy operations can be costly when dealing with very +large lists. To deal with all of the above situations, pybind11 provides a +macro named ``PYBIND11_MAKE_OPAQUE(T)`` that disables the template-based +conversion machinery of types, thus rendering them *opaque*. The contents of +opaque objects are never inspected or extracted, hence they *can* be passed by +reference. For instance, to turn ``std::vector`` into an opaque type, add +the declaration + +.. code-block:: cpp + + PYBIND11_MAKE_OPAQUE(std::vector); + +before any binding code (e.g. invocations to ``class_::def()``, etc.). This +macro must be specified at the top level (and outside of any namespaces), since +it instantiates a partial template overload. If your binding code consists of +multiple compilation units, it must be present in every file (typically via a +common header) preceding any usage of ``std::vector``. Opaque types must +also have a corresponding ``class_`` declaration to associate them with a name +in Python, and to define a set of available operations, e.g.: + +.. code-block:: cpp + + py::class_>(m, "IntVector") + .def(py::init<>()) + .def("clear", &std::vector::clear) + .def("pop_back", &std::vector::pop_back) + .def("__len__", [](const std::vector &v) { return v.size(); }) + .def("__iter__", [](std::vector &v) { + return py::make_iterator(v.begin(), v.end()); + }, py::keep_alive<0, 1>()) /* Keep vector alive while iterator is used */ + // .... + +.. seealso:: + + The file :file:`tests/test_opaque_types.cpp` contains a complete + example that demonstrates how to create and expose opaque types using + pybind11 in more detail. + +.. _stl_bind: + +Binding STL containers +====================== + +The ability to expose STL containers as native Python objects is a fairly +common request, hence pybind11 also provides an optional header file named +:file:`pybind11/stl_bind.h` that does exactly this. The mapped containers try +to match the behavior of their native Python counterparts as much as possible. + +The following example showcases usage of :file:`pybind11/stl_bind.h`: + +.. code-block:: cpp + + // Don't forget this + #include + + PYBIND11_MAKE_OPAQUE(std::vector); + PYBIND11_MAKE_OPAQUE(std::map); + + // ... + + // later in binding code: + py::bind_vector>(m, "VectorInt"); + py::bind_map>(m, "MapStringDouble"); + +When binding STL containers pybind11 considers the types of the container's +elements to decide whether the container should be confined to the local module +(via the :ref:`module_local` feature). If the container element types are +anything other than already-bound custom types bound without +``py::module_local()`` the container binding will have ``py::module_local()`` +applied. This includes converting types such as numeric types, strings, Eigen +types; and types that have not yet been bound at the time of the stl container +binding. This module-local binding is designed to avoid potential conflicts +between module bindings (for example, from two separate modules each attempting +to bind ``std::vector`` as a python type). + +It is possible to override this behavior to force a definition to be either +module-local or global. To do so, you can pass the attributes +``py::module_local()`` (to make the binding module-local) or +``py::module_local(false)`` (to make the binding global) into the +``py::bind_vector`` or ``py::bind_map`` arguments: + +.. code-block:: cpp + + py::bind_vector>(m, "VectorInt", py::module_local(false)); + +Note, however, that such a global binding would make it impossible to load this +module at the same time as any other pybind module that also attempts to bind +the same container type (``std::vector`` in the above example). + +See :ref:`module_local` for more details on module-local bindings. + +.. seealso:: + + The file :file:`tests/test_stl_binders.cpp` shows how to use the + convenience STL container wrappers. diff --git a/wrap/python/pybind11/docs/advanced/cast/strings.rst b/wrap/python/pybind11/docs/advanced/cast/strings.rst new file mode 100644 index 000000000..e25701eca --- /dev/null +++ b/wrap/python/pybind11/docs/advanced/cast/strings.rst @@ -0,0 +1,305 @@ +Strings, bytes and Unicode conversions +###################################### + +.. note:: + + This section discusses string handling in terms of Python 3 strings. For + Python 2.7, replace all occurrences of ``str`` with ``unicode`` and + ``bytes`` with ``str``. Python 2.7 users may find it best to use ``from + __future__ import unicode_literals`` to avoid unintentionally using ``str`` + instead of ``unicode``. + +Passing Python strings to C++ +============================= + +When a Python ``str`` is passed from Python to a C++ function that accepts +``std::string`` or ``char *`` as arguments, pybind11 will encode the Python +string to UTF-8. All Python ``str`` can be encoded in UTF-8, so this operation +does not fail. + +The C++ language is encoding agnostic. It is the responsibility of the +programmer to track encodings. It's often easiest to simply `use UTF-8 +everywhere `_. + +.. code-block:: c++ + + m.def("utf8_test", + [](const std::string &s) { + cout << "utf-8 is icing on the cake.\n"; + cout << s; + } + ); + m.def("utf8_charptr", + [](const char *s) { + cout << "My favorite food is\n"; + cout << s; + } + ); + +.. code-block:: python + + >>> utf8_test('🎂') + utf-8 is icing on the cake. + 🎂 + + >>> utf8_charptr('🍕') + My favorite food is + 🍕 + +.. note:: + + Some terminal emulators do not support UTF-8 or emoji fonts and may not + display the example above correctly. + +The results are the same whether the C++ function accepts arguments by value or +reference, and whether or not ``const`` is used. + +Passing bytes to C++ +-------------------- + +A Python ``bytes`` object will be passed to C++ functions that accept +``std::string`` or ``char*`` *without* conversion. On Python 3, in order to +make a function *only* accept ``bytes`` (and not ``str``), declare it as taking +a ``py::bytes`` argument. + + +Returning C++ strings to Python +=============================== + +When a C++ function returns a ``std::string`` or ``char*`` to a Python caller, +**pybind11 will assume that the string is valid UTF-8** and will decode it to a +native Python ``str``, using the same API as Python uses to perform +``bytes.decode('utf-8')``. If this implicit conversion fails, pybind11 will +raise a ``UnicodeDecodeError``. + +.. code-block:: c++ + + m.def("std_string_return", + []() { + return std::string("This string needs to be UTF-8 encoded"); + } + ); + +.. code-block:: python + + >>> isinstance(example.std_string_return(), str) + True + + +Because UTF-8 is inclusive of pure ASCII, there is never any issue with +returning a pure ASCII string to Python. If there is any possibility that the +string is not pure ASCII, it is necessary to ensure the encoding is valid +UTF-8. + +.. warning:: + + Implicit conversion assumes that a returned ``char *`` is null-terminated. + If there is no null terminator a buffer overrun will occur. + +Explicit conversions +-------------------- + +If some C++ code constructs a ``std::string`` that is not a UTF-8 string, one +can perform a explicit conversion and return a ``py::str`` object. Explicit +conversion has the same overhead as implicit conversion. + +.. code-block:: c++ + + // This uses the Python C API to convert Latin-1 to Unicode + m.def("str_output", + []() { + std::string s = "Send your r\xe9sum\xe9 to Alice in HR"; // Latin-1 + py::str py_s = PyUnicode_DecodeLatin1(s.data(), s.length()); + return py_s; + } + ); + +.. code-block:: python + + >>> str_output() + 'Send your résumé to Alice in HR' + +The `Python C API +`_ provides +several built-in codecs. + + +One could also use a third party encoding library such as libiconv to transcode +to UTF-8. + +Return C++ strings without conversion +------------------------------------- + +If the data in a C++ ``std::string`` does not represent text and should be +returned to Python as ``bytes``, then one can return the data as a +``py::bytes`` object. + +.. code-block:: c++ + + m.def("return_bytes", + []() { + std::string s("\xba\xd0\xba\xd0"); // Not valid UTF-8 + return py::bytes(s); // Return the data without transcoding + } + ); + +.. code-block:: python + + >>> example.return_bytes() + b'\xba\xd0\xba\xd0' + + +Note the asymmetry: pybind11 will convert ``bytes`` to ``std::string`` without +encoding, but cannot convert ``std::string`` back to ``bytes`` implicitly. + +.. code-block:: c++ + + m.def("asymmetry", + [](std::string s) { // Accepts str or bytes from Python + return s; // Looks harmless, but implicitly converts to str + } + ); + +.. code-block:: python + + >>> isinstance(example.asymmetry(b"have some bytes"), str) + True + + >>> example.asymmetry(b"\xba\xd0\xba\xd0") # invalid utf-8 as bytes + UnicodeDecodeError: 'utf-8' codec can't decode byte 0xba in position 0: invalid start byte + + +Wide character strings +====================== + +When a Python ``str`` is passed to a C++ function expecting ``std::wstring``, +``wchar_t*``, ``std::u16string`` or ``std::u32string``, the ``str`` will be +encoded to UTF-16 or UTF-32 depending on how the C++ compiler implements each +type, in the platform's native endianness. When strings of these types are +returned, they are assumed to contain valid UTF-16 or UTF-32, and will be +decoded to Python ``str``. + +.. code-block:: c++ + + #define UNICODE + #include + + m.def("set_window_text", + [](HWND hwnd, std::wstring s) { + // Call SetWindowText with null-terminated UTF-16 string + ::SetWindowText(hwnd, s.c_str()); + } + ); + m.def("get_window_text", + [](HWND hwnd) { + const int buffer_size = ::GetWindowTextLength(hwnd) + 1; + auto buffer = std::make_unique< wchar_t[] >(buffer_size); + + ::GetWindowText(hwnd, buffer.data(), buffer_size); + + std::wstring text(buffer.get()); + + // wstring will be converted to Python str + return text; + } + ); + +.. warning:: + + Wide character strings may not work as described on Python 2.7 or Python + 3.3 compiled with ``--enable-unicode=ucs2``. + +Strings in multibyte encodings such as Shift-JIS must transcoded to a +UTF-8/16/32 before being returned to Python. + + +Character literals +================== + +C++ functions that accept character literals as input will receive the first +character of a Python ``str`` as their input. If the string is longer than one +Unicode character, trailing characters will be ignored. + +When a character literal is returned from C++ (such as a ``char`` or a +``wchar_t``), it will be converted to a ``str`` that represents the single +character. + +.. code-block:: c++ + + m.def("pass_char", [](char c) { return c; }); + m.def("pass_wchar", [](wchar_t w) { return w; }); + +.. code-block:: python + + >>> example.pass_char('A') + 'A' + +While C++ will cast integers to character types (``char c = 0x65;``), pybind11 +does not convert Python integers to characters implicitly. The Python function +``chr()`` can be used to convert integers to characters. + +.. code-block:: python + + >>> example.pass_char(0x65) + TypeError + + >>> example.pass_char(chr(0x65)) + 'A' + +If the desire is to work with an 8-bit integer, use ``int8_t`` or ``uint8_t`` +as the argument type. + +Grapheme clusters +----------------- + +A single grapheme may be represented by two or more Unicode characters. For +example 'é' is usually represented as U+00E9 but can also be expressed as the +combining character sequence U+0065 U+0301 (that is, the letter 'e' followed by +a combining acute accent). The combining character will be lost if the +two-character sequence is passed as an argument, even though it renders as a +single grapheme. + +.. code-block:: python + + >>> example.pass_wchar('é') + 'é' + + >>> combining_e_acute = 'e' + '\u0301' + + >>> combining_e_acute + 'é' + + >>> combining_e_acute == 'é' + False + + >>> example.pass_wchar(combining_e_acute) + 'e' + +Normalizing combining characters before passing the character literal to C++ +may resolve *some* of these issues: + +.. code-block:: python + + >>> example.pass_wchar(unicodedata.normalize('NFC', combining_e_acute)) + 'é' + +In some languages (Thai for example), there are `graphemes that cannot be +expressed as a single Unicode code point +`_, so there is +no way to capture them in a C++ character type. + + +C++17 string views +================== + +C++17 string views are automatically supported when compiling in C++17 mode. +They follow the same rules for encoding and decoding as the corresponding STL +string type (for example, a ``std::u16string_view`` argument will be passed +UTF-16-encoded data, and a returned ``std::string_view`` will be decoded as +UTF-8). + +References +========== + +* `The Absolute Minimum Every Software Developer Absolutely, Positively Must Know About Unicode and Character Sets (No Excuses!) `_ +* `C++ - Using STL Strings at Win32 API Boundaries `_ diff --git a/wrap/python/pybind11/docs/advanced/classes.rst b/wrap/python/pybind11/docs/advanced/classes.rst new file mode 100644 index 000000000..c9a0da5a1 --- /dev/null +++ b/wrap/python/pybind11/docs/advanced/classes.rst @@ -0,0 +1,1125 @@ +Classes +####### + +This section presents advanced binding code for classes and it is assumed +that you are already familiar with the basics from :doc:`/classes`. + +.. _overriding_virtuals: + +Overriding virtual functions in Python +====================================== + +Suppose that a C++ class or interface has a virtual function that we'd like to +to override from within Python (we'll focus on the class ``Animal``; ``Dog`` is +given as a specific example of how one would do this with traditional C++ +code). + +.. code-block:: cpp + + class Animal { + public: + virtual ~Animal() { } + virtual std::string go(int n_times) = 0; + }; + + class Dog : public Animal { + public: + std::string go(int n_times) override { + std::string result; + for (int i=0; igo(3); + } + +Normally, the binding code for these classes would look as follows: + +.. code-block:: cpp + + PYBIND11_MODULE(example, m) { + py::class_(m, "Animal") + .def("go", &Animal::go); + + py::class_(m, "Dog") + .def(py::init<>()); + + m.def("call_go", &call_go); + } + +However, these bindings are impossible to extend: ``Animal`` is not +constructible, and we clearly require some kind of "trampoline" that +redirects virtual calls back to Python. + +Defining a new type of ``Animal`` from within Python is possible but requires a +helper class that is defined as follows: + +.. code-block:: cpp + + class PyAnimal : public Animal { + public: + /* Inherit the constructors */ + using Animal::Animal; + + /* Trampoline (need one for each virtual function) */ + std::string go(int n_times) override { + PYBIND11_OVERLOAD_PURE( + std::string, /* Return type */ + Animal, /* Parent class */ + go, /* Name of function in C++ (must match Python name) */ + n_times /* Argument(s) */ + ); + } + }; + +The macro :c:macro:`PYBIND11_OVERLOAD_PURE` should be used for pure virtual +functions, and :c:macro:`PYBIND11_OVERLOAD` should be used for functions which have +a default implementation. There are also two alternate macros +:c:macro:`PYBIND11_OVERLOAD_PURE_NAME` and :c:macro:`PYBIND11_OVERLOAD_NAME` which +take a string-valued name argument between the *Parent class* and *Name of the +function* slots, which defines the name of function in Python. This is required +when the C++ and Python versions of the +function have different names, e.g. ``operator()`` vs ``__call__``. + +The binding code also needs a few minor adaptations (highlighted): + +.. code-block:: cpp + :emphasize-lines: 2,3 + + PYBIND11_MODULE(example, m) { + py::class_(m, "Animal") + .def(py::init<>()) + .def("go", &Animal::go); + + py::class_(m, "Dog") + .def(py::init<>()); + + m.def("call_go", &call_go); + } + +Importantly, pybind11 is made aware of the trampoline helper class by +specifying it as an extra template argument to :class:`class_`. (This can also +be combined with other template arguments such as a custom holder type; the +order of template types does not matter). Following this, we are able to +define a constructor as usual. + +Bindings should be made against the actual class, not the trampoline helper class. + +.. code-block:: cpp + :emphasize-lines: 3 + + py::class_(m, "Animal"); + .def(py::init<>()) + .def("go", &PyAnimal::go); /* <--- THIS IS WRONG, use &Animal::go */ + +Note, however, that the above is sufficient for allowing python classes to +extend ``Animal``, but not ``Dog``: see :ref:`virtual_and_inheritance` for the +necessary steps required to providing proper overload support for inherited +classes. + +The Python session below shows how to override ``Animal::go`` and invoke it via +a virtual method call. + +.. code-block:: pycon + + >>> from example import * + >>> d = Dog() + >>> call_go(d) + u'woof! woof! woof! ' + >>> class Cat(Animal): + ... def go(self, n_times): + ... return "meow! " * n_times + ... + >>> c = Cat() + >>> call_go(c) + u'meow! meow! meow! ' + +If you are defining a custom constructor in a derived Python class, you *must* +ensure that you explicitly call the bound C++ constructor using ``__init__``, +*regardless* of whether it is a default constructor or not. Otherwise, the +memory for the C++ portion of the instance will be left uninitialized, which +will generally leave the C++ instance in an invalid state and cause undefined +behavior if the C++ instance is subsequently used. + +Here is an example: + +.. code-block:: python + + class Dachshund(Dog): + def __init__(self, name): + Dog.__init__(self) # Without this, undefined behavior may occur if the C++ portions are referenced. + self.name = name + def bark(self): + return "yap!" + +Note that a direct ``__init__`` constructor *should be called*, and ``super()`` +should not be used. For simple cases of linear inheritance, ``super()`` +may work, but once you begin mixing Python and C++ multiple inheritance, +things will fall apart due to differences between Python's MRO and C++'s +mechanisms. + +Please take a look at the :ref:`macro_notes` before using this feature. + +.. note:: + + When the overridden type returns a reference or pointer to a type that + pybind11 converts from Python (for example, numeric values, std::string, + and other built-in value-converting types), there are some limitations to + be aware of: + + - because in these cases there is no C++ variable to reference (the value + is stored in the referenced Python variable), pybind11 provides one in + the PYBIND11_OVERLOAD macros (when needed) with static storage duration. + Note that this means that invoking the overloaded method on *any* + instance will change the referenced value stored in *all* instances of + that type. + + - Attempts to modify a non-const reference will not have the desired + effect: it will change only the static cache variable, but this change + will not propagate to underlying Python instance, and the change will be + replaced the next time the overload is invoked. + +.. seealso:: + + The file :file:`tests/test_virtual_functions.cpp` contains a complete + example that demonstrates how to override virtual functions using pybind11 + in more detail. + +.. _virtual_and_inheritance: + +Combining virtual functions and inheritance +=========================================== + +When combining virtual methods with inheritance, you need to be sure to provide +an override for each method for which you want to allow overrides from derived +python classes. For example, suppose we extend the above ``Animal``/``Dog`` +example as follows: + +.. code-block:: cpp + + class Animal { + public: + virtual std::string go(int n_times) = 0; + virtual std::string name() { return "unknown"; } + }; + class Dog : public Animal { + public: + std::string go(int n_times) override { + std::string result; + for (int i=0; i class PyAnimal : public AnimalBase { + public: + using AnimalBase::AnimalBase; // Inherit constructors + std::string go(int n_times) override { PYBIND11_OVERLOAD_PURE(std::string, AnimalBase, go, n_times); } + std::string name() override { PYBIND11_OVERLOAD(std::string, AnimalBase, name, ); } + }; + template class PyDog : public PyAnimal { + public: + using PyAnimal::PyAnimal; // Inherit constructors + // Override PyAnimal's pure virtual go() with a non-pure one: + std::string go(int n_times) override { PYBIND11_OVERLOAD(std::string, DogBase, go, n_times); } + std::string bark() override { PYBIND11_OVERLOAD(std::string, DogBase, bark, ); } + }; + +This technique has the advantage of requiring just one trampoline method to be +declared per virtual method and pure virtual method override. It does, +however, require the compiler to generate at least as many methods (and +possibly more, if both pure virtual and overridden pure virtual methods are +exposed, as above). + +The classes are then registered with pybind11 using: + +.. code-block:: cpp + + py::class_> animal(m, "Animal"); + py::class_> dog(m, "Dog"); + py::class_> husky(m, "Husky"); + // ... add animal, dog, husky definitions + +Note that ``Husky`` did not require a dedicated trampoline template class at +all, since it neither declares any new virtual methods nor provides any pure +virtual method implementations. + +With either the repeated-virtuals or templated trampoline methods in place, you +can now create a python class that inherits from ``Dog``: + +.. code-block:: python + + class ShihTzu(Dog): + def bark(self): + return "yip!" + +.. seealso:: + + See the file :file:`tests/test_virtual_functions.cpp` for complete examples + using both the duplication and templated trampoline approaches. + +.. _extended_aliases: + +Extended trampoline class functionality +======================================= + +.. _extended_class_functionality_forced_trampoline: + +Forced trampoline class initialisation +-------------------------------------- +The trampoline classes described in the previous sections are, by default, only +initialized when needed. More specifically, they are initialized when a python +class actually inherits from a registered type (instead of merely creating an +instance of the registered type), or when a registered constructor is only +valid for the trampoline class but not the registered class. This is primarily +for performance reasons: when the trampoline class is not needed for anything +except virtual method dispatching, not initializing the trampoline class +improves performance by avoiding needing to do a run-time check to see if the +inheriting python instance has an overloaded method. + +Sometimes, however, it is useful to always initialize a trampoline class as an +intermediate class that does more than just handle virtual method dispatching. +For example, such a class might perform extra class initialization, extra +destruction operations, and might define new members and methods to enable a +more python-like interface to a class. + +In order to tell pybind11 that it should *always* initialize the trampoline +class when creating new instances of a type, the class constructors should be +declared using ``py::init_alias()`` instead of the usual +``py::init()``. This forces construction via the trampoline class, +ensuring member initialization and (eventual) destruction. + +.. seealso:: + + See the file :file:`tests/test_virtual_functions.cpp` for complete examples + showing both normal and forced trampoline instantiation. + +Different method signatures +--------------------------- +The macro's introduced in :ref:`overriding_virtuals` cover most of the standard +use cases when exposing C++ classes to Python. Sometimes it is hard or unwieldy +to create a direct one-on-one mapping between the arguments and method return +type. + +An example would be when the C++ signature contains output arguments using +references (See also :ref:`faq_reference_arguments`). Another way of solving +this is to use the method body of the trampoline class to do conversions to the +input and return of the Python method. + +The main building block to do so is the :func:`get_overload`, this function +allows retrieving a method implemented in Python from within the trampoline's +methods. Consider for example a C++ method which has the signature +``bool myMethod(int32_t& value)``, where the return indicates whether +something should be done with the ``value``. This can be made convenient on the +Python side by allowing the Python function to return ``None`` or an ``int``: + +.. code-block:: cpp + + bool MyClass::myMethod(int32_t& value) + { + pybind11::gil_scoped_acquire gil; // Acquire the GIL while in this scope. + // Try to look up the overloaded method on the Python side. + pybind11::function overload = pybind11::get_overload(this, "myMethod"); + if (overload) { // method is found + auto obj = overload(value); // Call the Python function. + if (py::isinstance(obj)) { // check if it returned a Python integer type + value = obj.cast(); // Cast it and assign it to the value. + return true; // Return true; value should be used. + } else { + return false; // Python returned none, return false. + } + } + return false; // Alternatively return MyClass::myMethod(value); + } + + +.. _custom_constructors: + +Custom constructors +=================== + +The syntax for binding constructors was previously introduced, but it only +works when a constructor of the appropriate arguments actually exists on the +C++ side. To extend this to more general cases, pybind11 makes it possible +to bind factory functions as constructors. For example, suppose you have a +class like this: + +.. code-block:: cpp + + class Example { + private: + Example(int); // private constructor + public: + // Factory function: + static Example create(int a) { return Example(a); } + }; + + py::class_(m, "Example") + .def(py::init(&Example::create)); + +While it is possible to create a straightforward binding of the static +``create`` method, it may sometimes be preferable to expose it as a constructor +on the Python side. This can be accomplished by calling ``.def(py::init(...))`` +with the function reference returning the new instance passed as an argument. +It is also possible to use this approach to bind a function returning a new +instance by raw pointer or by the holder (e.g. ``std::unique_ptr``). + +The following example shows the different approaches: + +.. code-block:: cpp + + class Example { + private: + Example(int); // private constructor + public: + // Factory function - returned by value: + static Example create(int a) { return Example(a); } + + // These constructors are publicly callable: + Example(double); + Example(int, int); + Example(std::string); + }; + + py::class_(m, "Example") + // Bind the factory function as a constructor: + .def(py::init(&Example::create)) + // Bind a lambda function returning a pointer wrapped in a holder: + .def(py::init([](std::string arg) { + return std::unique_ptr(new Example(arg)); + })) + // Return a raw pointer: + .def(py::init([](int a, int b) { return new Example(a, b); })) + // You can mix the above with regular C++ constructor bindings as well: + .def(py::init()) + ; + +When the constructor is invoked from Python, pybind11 will call the factory +function and store the resulting C++ instance in the Python instance. + +When combining factory functions constructors with :ref:`virtual function +trampolines ` there are two approaches. The first is to +add a constructor to the alias class that takes a base value by +rvalue-reference. If such a constructor is available, it will be used to +construct an alias instance from the value returned by the factory function. +The second option is to provide two factory functions to ``py::init()``: the +first will be invoked when no alias class is required (i.e. when the class is +being used but not inherited from in Python), and the second will be invoked +when an alias is required. + +You can also specify a single factory function that always returns an alias +instance: this will result in behaviour similar to ``py::init_alias<...>()``, +as described in the :ref:`extended trampoline class documentation +`. + +The following example shows the different factory approaches for a class with +an alias: + +.. code-block:: cpp + + #include + class Example { + public: + // ... + virtual ~Example() = default; + }; + class PyExample : public Example { + public: + using Example::Example; + PyExample(Example &&base) : Example(std::move(base)) {} + }; + py::class_(m, "Example") + // Returns an Example pointer. If a PyExample is needed, the Example + // instance will be moved via the extra constructor in PyExample, above. + .def(py::init([]() { return new Example(); })) + // Two callbacks: + .def(py::init([]() { return new Example(); } /* no alias needed */, + []() { return new PyExample(); } /* alias needed */)) + // *Always* returns an alias instance (like py::init_alias<>()) + .def(py::init([]() { return new PyExample(); })) + ; + +Brace initialization +-------------------- + +``pybind11::init<>`` internally uses C++11 brace initialization to call the +constructor of the target class. This means that it can be used to bind +*implicit* constructors as well: + +.. code-block:: cpp + + struct Aggregate { + int a; + std::string b; + }; + + py::class_(m, "Aggregate") + .def(py::init()); + +.. note:: + + Note that brace initialization preferentially invokes constructor overloads + taking a ``std::initializer_list``. In the rare event that this causes an + issue, you can work around it by using ``py::init(...)`` with a lambda + function that constructs the new object as desired. + +.. _classes_with_non_public_destructors: + +Non-public destructors +====================== + +If a class has a private or protected destructor (as might e.g. be the case in +a singleton pattern), a compile error will occur when creating bindings via +pybind11. The underlying issue is that the ``std::unique_ptr`` holder type that +is responsible for managing the lifetime of instances will reference the +destructor even if no deallocations ever take place. In order to expose classes +with private or protected destructors, it is possible to override the holder +type via a holder type argument to ``class_``. Pybind11 provides a helper class +``py::nodelete`` that disables any destructor invocations. In this case, it is +crucial that instances are deallocated on the C++ side to avoid memory leaks. + +.. code-block:: cpp + + /* ... definition ... */ + + class MyClass { + private: + ~MyClass() { } + }; + + /* ... binding code ... */ + + py::class_>(m, "MyClass") + .def(py::init<>()) + +.. _implicit_conversions: + +Implicit conversions +==================== + +Suppose that instances of two types ``A`` and ``B`` are used in a project, and +that an ``A`` can easily be converted into an instance of type ``B`` (examples of this +could be a fixed and an arbitrary precision number type). + +.. code-block:: cpp + + py::class_(m, "A") + /// ... members ... + + py::class_(m, "B") + .def(py::init()) + /// ... members ... + + m.def("func", + [](const B &) { /* .... */ } + ); + +To invoke the function ``func`` using a variable ``a`` containing an ``A`` +instance, we'd have to write ``func(B(a))`` in Python. On the other hand, C++ +will automatically apply an implicit type conversion, which makes it possible +to directly write ``func(a)``. + +In this situation (i.e. where ``B`` has a constructor that converts from +``A``), the following statement enables similar implicit conversions on the +Python side: + +.. code-block:: cpp + + py::implicitly_convertible(); + +.. note:: + + Implicit conversions from ``A`` to ``B`` only work when ``B`` is a custom + data type that is exposed to Python via pybind11. + + To prevent runaway recursion, implicit conversions are non-reentrant: an + implicit conversion invoked as part of another implicit conversion of the + same type (i.e. from ``A`` to ``B``) will fail. + +.. _static_properties: + +Static properties +================= + +The section on :ref:`properties` discussed the creation of instance properties +that are implemented in terms of C++ getters and setters. + +Static properties can also be created in a similar way to expose getters and +setters of static class attributes. Note that the implicit ``self`` argument +also exists in this case and is used to pass the Python ``type`` subclass +instance. This parameter will often not be needed by the C++ side, and the +following example illustrates how to instantiate a lambda getter function +that ignores it: + +.. code-block:: cpp + + py::class_(m, "Foo") + .def_property_readonly_static("foo", [](py::object /* self */) { return Foo(); }); + +Operator overloading +==================== + +Suppose that we're given the following ``Vector2`` class with a vector addition +and scalar multiplication operation, all implemented using overloaded operators +in C++. + +.. code-block:: cpp + + class Vector2 { + public: + Vector2(float x, float y) : x(x), y(y) { } + + Vector2 operator+(const Vector2 &v) const { return Vector2(x + v.x, y + v.y); } + Vector2 operator*(float value) const { return Vector2(x * value, y * value); } + Vector2& operator+=(const Vector2 &v) { x += v.x; y += v.y; return *this; } + Vector2& operator*=(float v) { x *= v; y *= v; return *this; } + + friend Vector2 operator*(float f, const Vector2 &v) { + return Vector2(f * v.x, f * v.y); + } + + std::string toString() const { + return "[" + std::to_string(x) + ", " + std::to_string(y) + "]"; + } + private: + float x, y; + }; + +The following snippet shows how the above operators can be conveniently exposed +to Python. + +.. code-block:: cpp + + #include + + PYBIND11_MODULE(example, m) { + py::class_(m, "Vector2") + .def(py::init()) + .def(py::self + py::self) + .def(py::self += py::self) + .def(py::self *= float()) + .def(float() * py::self) + .def(py::self * float()) + .def("__repr__", &Vector2::toString); + } + +Note that a line like + +.. code-block:: cpp + + .def(py::self * float()) + +is really just short hand notation for + +.. code-block:: cpp + + .def("__mul__", [](const Vector2 &a, float b) { + return a * b; + }, py::is_operator()) + +This can be useful for exposing additional operators that don't exist on the +C++ side, or to perform other types of customization. The ``py::is_operator`` +flag marker is needed to inform pybind11 that this is an operator, which +returns ``NotImplemented`` when invoked with incompatible arguments rather than +throwing a type error. + +.. note:: + + To use the more convenient ``py::self`` notation, the additional + header file :file:`pybind11/operators.h` must be included. + +.. seealso:: + + The file :file:`tests/test_operator_overloading.cpp` contains a + complete example that demonstrates how to work with overloaded operators in + more detail. + +.. _pickling: + +Pickling support +================ + +Python's ``pickle`` module provides a powerful facility to serialize and +de-serialize a Python object graph into a binary data stream. To pickle and +unpickle C++ classes using pybind11, a ``py::pickle()`` definition must be +provided. Suppose the class in question has the following signature: + +.. code-block:: cpp + + class Pickleable { + public: + Pickleable(const std::string &value) : m_value(value) { } + const std::string &value() const { return m_value; } + + void setExtra(int extra) { m_extra = extra; } + int extra() const { return m_extra; } + private: + std::string m_value; + int m_extra = 0; + }; + +Pickling support in Python is enabled by defining the ``__setstate__`` and +``__getstate__`` methods [#f3]_. For pybind11 classes, use ``py::pickle()`` +to bind these two functions: + +.. code-block:: cpp + + py::class_(m, "Pickleable") + .def(py::init()) + .def("value", &Pickleable::value) + .def("extra", &Pickleable::extra) + .def("setExtra", &Pickleable::setExtra) + .def(py::pickle( + [](const Pickleable &p) { // __getstate__ + /* Return a tuple that fully encodes the state of the object */ + return py::make_tuple(p.value(), p.extra()); + }, + [](py::tuple t) { // __setstate__ + if (t.size() != 2) + throw std::runtime_error("Invalid state!"); + + /* Create a new C++ instance */ + Pickleable p(t[0].cast()); + + /* Assign any additional state */ + p.setExtra(t[1].cast()); + + return p; + } + )); + +The ``__setstate__`` part of the ``py::picke()`` definition follows the same +rules as the single-argument version of ``py::init()``. The return type can be +a value, pointer or holder type. See :ref:`custom_constructors` for details. + +An instance can now be pickled as follows: + +.. code-block:: python + + try: + import cPickle as pickle # Use cPickle on Python 2.7 + except ImportError: + import pickle + + p = Pickleable("test_value") + p.setExtra(15) + data = pickle.dumps(p, 2) + +Note that only the cPickle module is supported on Python 2.7. The second +argument to ``dumps`` is also crucial: it selects the pickle protocol version +2, since the older version 1 is not supported. Newer versions are also fine—for +instance, specify ``-1`` to always use the latest available version. Beware: +failure to follow these instructions will cause important pybind11 memory +allocation routines to be skipped during unpickling, which will likely lead to +memory corruption and/or segmentation faults. + +.. seealso:: + + The file :file:`tests/test_pickling.cpp` contains a complete example + that demonstrates how to pickle and unpickle types using pybind11 in more + detail. + +.. [#f3] http://docs.python.org/3/library/pickle.html#pickling-class-instances + +Multiple Inheritance +==================== + +pybind11 can create bindings for types that derive from multiple base types +(aka. *multiple inheritance*). To do so, specify all bases in the template +arguments of the ``class_`` declaration: + +.. code-block:: cpp + + py::class_(m, "MyType") + ... + +The base types can be specified in arbitrary order, and they can even be +interspersed with alias types and holder types (discussed earlier in this +document)---pybind11 will automatically find out which is which. The only +requirement is that the first template argument is the type to be declared. + +It is also permitted to inherit multiply from exported C++ classes in Python, +as well as inheriting from multiple Python and/or pybind11-exported classes. + +There is one caveat regarding the implementation of this feature: + +When only one base type is specified for a C++ type that actually has multiple +bases, pybind11 will assume that it does not participate in multiple +inheritance, which can lead to undefined behavior. In such cases, add the tag +``multiple_inheritance`` to the class constructor: + +.. code-block:: cpp + + py::class_(m, "MyType", py::multiple_inheritance()); + +The tag is redundant and does not need to be specified when multiple base types +are listed. + +.. _module_local: + +Module-local class bindings +=========================== + +When creating a binding for a class, pybind11 by default makes that binding +"global" across modules. What this means is that a type defined in one module +can be returned from any module resulting in the same Python type. For +example, this allows the following: + +.. code-block:: cpp + + // In the module1.cpp binding code for module1: + py::class_(m, "Pet") + .def(py::init()) + .def_readonly("name", &Pet::name); + +.. code-block:: cpp + + // In the module2.cpp binding code for module2: + m.def("create_pet", [](std::string name) { return new Pet(name); }); + +.. code-block:: pycon + + >>> from module1 import Pet + >>> from module2 import create_pet + >>> pet1 = Pet("Kitty") + >>> pet2 = create_pet("Doggy") + >>> pet2.name() + 'Doggy' + +When writing binding code for a library, this is usually desirable: this +allows, for example, splitting up a complex library into multiple Python +modules. + +In some cases, however, this can cause conflicts. For example, suppose two +unrelated modules make use of an external C++ library and each provide custom +bindings for one of that library's classes. This will result in an error when +a Python program attempts to import both modules (directly or indirectly) +because of conflicting definitions on the external type: + +.. code-block:: cpp + + // dogs.cpp + + // Binding for external library class: + py::class(m, "Pet") + .def("name", &pets::Pet::name); + + // Binding for local extension class: + py::class(m, "Dog") + .def(py::init()); + +.. code-block:: cpp + + // cats.cpp, in a completely separate project from the above dogs.cpp. + + // Binding for external library class: + py::class(m, "Pet") + .def("get_name", &pets::Pet::name); + + // Binding for local extending class: + py::class(m, "Cat") + .def(py::init()); + +.. code-block:: pycon + + >>> import cats + >>> import dogs + Traceback (most recent call last): + File "", line 1, in + ImportError: generic_type: type "Pet" is already registered! + +To get around this, you can tell pybind11 to keep the external class binding +localized to the module by passing the ``py::module_local()`` attribute into +the ``py::class_`` constructor: + +.. code-block:: cpp + + // Pet binding in dogs.cpp: + py::class(m, "Pet", py::module_local()) + .def("name", &pets::Pet::name); + +.. code-block:: cpp + + // Pet binding in cats.cpp: + py::class(m, "Pet", py::module_local()) + .def("get_name", &pets::Pet::name); + +This makes the Python-side ``dogs.Pet`` and ``cats.Pet`` into distinct classes, +avoiding the conflict and allowing both modules to be loaded. C++ code in the +``dogs`` module that casts or returns a ``Pet`` instance will result in a +``dogs.Pet`` Python instance, while C++ code in the ``cats`` module will result +in a ``cats.Pet`` Python instance. + +This does come with two caveats, however: First, external modules cannot return +or cast a ``Pet`` instance to Python (unless they also provide their own local +bindings). Second, from the Python point of view they are two distinct classes. + +Note that the locality only applies in the C++ -> Python direction. When +passing such a ``py::module_local`` type into a C++ function, the module-local +classes are still considered. This means that if the following function is +added to any module (including but not limited to the ``cats`` and ``dogs`` +modules above) it will be callable with either a ``dogs.Pet`` or ``cats.Pet`` +argument: + +.. code-block:: cpp + + m.def("pet_name", [](const pets::Pet &pet) { return pet.name(); }); + +For example, suppose the above function is added to each of ``cats.cpp``, +``dogs.cpp`` and ``frogs.cpp`` (where ``frogs.cpp`` is some other module that +does *not* bind ``Pets`` at all). + +.. code-block:: pycon + + >>> import cats, dogs, frogs # No error because of the added py::module_local() + >>> mycat, mydog = cats.Cat("Fluffy"), dogs.Dog("Rover") + >>> (cats.pet_name(mycat), dogs.pet_name(mydog)) + ('Fluffy', 'Rover') + >>> (cats.pet_name(mydog), dogs.pet_name(mycat), frogs.pet_name(mycat)) + ('Rover', 'Fluffy', 'Fluffy') + +It is possible to use ``py::module_local()`` registrations in one module even +if another module registers the same type globally: within the module with the +module-local definition, all C++ instances will be cast to the associated bound +Python type. In other modules any such values are converted to the global +Python type created elsewhere. + +.. note:: + + STL bindings (as provided via the optional :file:`pybind11/stl_bind.h` + header) apply ``py::module_local`` by default when the bound type might + conflict with other modules; see :ref:`stl_bind` for details. + +.. note:: + + The localization of the bound types is actually tied to the shared object + or binary generated by the compiler/linker. For typical modules created + with ``PYBIND11_MODULE()``, this distinction is not significant. It is + possible, however, when :ref:`embedding` to embed multiple modules in the + same binary (see :ref:`embedding_modules`). In such a case, the + localization will apply across all embedded modules within the same binary. + +.. seealso:: + + The file :file:`tests/test_local_bindings.cpp` contains additional examples + that demonstrate how ``py::module_local()`` works. + +Binding protected member functions +================================== + +It's normally not possible to expose ``protected`` member functions to Python: + +.. code-block:: cpp + + class A { + protected: + int foo() const { return 42; } + }; + + py::class_(m, "A") + .def("foo", &A::foo); // error: 'foo' is a protected member of 'A' + +On one hand, this is good because non-``public`` members aren't meant to be +accessed from the outside. But we may want to make use of ``protected`` +functions in derived Python classes. + +The following pattern makes this possible: + +.. code-block:: cpp + + class A { + protected: + int foo() const { return 42; } + }; + + class Publicist : public A { // helper type for exposing protected functions + public: + using A::foo; // inherited with different access modifier + }; + + py::class_(m, "A") // bind the primary class + .def("foo", &Publicist::foo); // expose protected methods via the publicist + +This works because ``&Publicist::foo`` is exactly the same function as +``&A::foo`` (same signature and address), just with a different access +modifier. The only purpose of the ``Publicist`` helper class is to make +the function name ``public``. + +If the intent is to expose ``protected`` ``virtual`` functions which can be +overridden in Python, the publicist pattern can be combined with the previously +described trampoline: + +.. code-block:: cpp + + class A { + public: + virtual ~A() = default; + + protected: + virtual int foo() const { return 42; } + }; + + class Trampoline : public A { + public: + int foo() const override { PYBIND11_OVERLOAD(int, A, foo, ); } + }; + + class Publicist : public A { + public: + using A::foo; + }; + + py::class_(m, "A") // <-- `Trampoline` here + .def("foo", &Publicist::foo); // <-- `Publicist` here, not `Trampoline`! + +.. note:: + + MSVC 2015 has a compiler bug (fixed in version 2017) which + requires a more explicit function binding in the form of + ``.def("foo", static_cast(&Publicist::foo));`` + where ``int (A::*)() const`` is the type of ``A::foo``. + +Custom automatic downcasters +============================ + +As explained in :ref:`inheritance`, pybind11 comes with built-in +understanding of the dynamic type of polymorphic objects in C++; that +is, returning a Pet to Python produces a Python object that knows it's +wrapping a Dog, if Pet has virtual methods and pybind11 knows about +Dog and this Pet is in fact a Dog. Sometimes, you might want to +provide this automatic downcasting behavior when creating bindings for +a class hierarchy that does not use standard C++ polymorphism, such as +LLVM [#f4]_. As long as there's some way to determine at runtime +whether a downcast is safe, you can proceed by specializing the +``pybind11::polymorphic_type_hook`` template: + +.. code-block:: cpp + + enum class PetKind { Cat, Dog, Zebra }; + struct Pet { // Not polymorphic: has no virtual methods + const PetKind kind; + int age = 0; + protected: + Pet(PetKind _kind) : kind(_kind) {} + }; + struct Dog : Pet { + Dog() : Pet(PetKind::Dog) {} + std::string sound = "woof!"; + std::string bark() const { return sound; } + }; + + namespace pybind11 { + template<> struct polymorphic_type_hook { + static const void *get(const Pet *src, const std::type_info*& type) { + // note that src may be nullptr + if (src && src->kind == PetKind::Dog) { + type = &typeid(Dog); + return static_cast(src); + } + return src; + } + }; + } // namespace pybind11 + +When pybind11 wants to convert a C++ pointer of type ``Base*`` to a +Python object, it calls ``polymorphic_type_hook::get()`` to +determine if a downcast is possible. The ``get()`` function should use +whatever runtime information is available to determine if its ``src`` +parameter is in fact an instance of some class ``Derived`` that +inherits from ``Base``. If it finds such a ``Derived``, it sets ``type += &typeid(Derived)`` and returns a pointer to the ``Derived`` object +that contains ``src``. Otherwise, it just returns ``src``, leaving +``type`` at its default value of nullptr. If you set ``type`` to a +type that pybind11 doesn't know about, no downcasting will occur, and +the original ``src`` pointer will be used with its static type +``Base*``. + +It is critical that the returned pointer and ``type`` argument of +``get()`` agree with each other: if ``type`` is set to something +non-null, the returned pointer must point to the start of an object +whose type is ``type``. If the hierarchy being exposed uses only +single inheritance, a simple ``return src;`` will achieve this just +fine, but in the general case, you must cast ``src`` to the +appropriate derived-class pointer (e.g. using +``static_cast(src)``) before allowing it to be returned as a +``void*``. + +.. [#f4] https://llvm.org/docs/HowToSetUpLLVMStyleRTTI.html + +.. note:: + + pybind11's standard support for downcasting objects whose types + have virtual methods is implemented using + ``polymorphic_type_hook`` too, using the standard C++ ability to + determine the most-derived type of a polymorphic object using + ``typeid()`` and to cast a base pointer to that most-derived type + (even if you don't know what it is) using ``dynamic_cast``. + +.. seealso:: + + The file :file:`tests/test_tagbased_polymorphic.cpp` contains a + more complete example, including a demonstration of how to provide + automatic downcasting for an entire class hierarchy without + writing one get() function for each class. diff --git a/wrap/python/pybind11/docs/advanced/embedding.rst b/wrap/python/pybind11/docs/advanced/embedding.rst new file mode 100644 index 000000000..393031603 --- /dev/null +++ b/wrap/python/pybind11/docs/advanced/embedding.rst @@ -0,0 +1,261 @@ +.. _embedding: + +Embedding the interpreter +######################### + +While pybind11 is mainly focused on extending Python using C++, it's also +possible to do the reverse: embed the Python interpreter into a C++ program. +All of the other documentation pages still apply here, so refer to them for +general pybind11 usage. This section will cover a few extra things required +for embedding. + +Getting started +=============== + +A basic executable with an embedded interpreter can be created with just a few +lines of CMake and the ``pybind11::embed`` target, as shown below. For more +information, see :doc:`/compiling`. + +.. code-block:: cmake + + cmake_minimum_required(VERSION 3.0) + project(example) + + find_package(pybind11 REQUIRED) # or `add_subdirectory(pybind11)` + + add_executable(example main.cpp) + target_link_libraries(example PRIVATE pybind11::embed) + +The essential structure of the ``main.cpp`` file looks like this: + +.. code-block:: cpp + + #include // everything needed for embedding + namespace py = pybind11; + + int main() { + py::scoped_interpreter guard{}; // start the interpreter and keep it alive + + py::print("Hello, World!"); // use the Python API + } + +The interpreter must be initialized before using any Python API, which includes +all the functions and classes in pybind11. The RAII guard class `scoped_interpreter` +takes care of the interpreter lifetime. After the guard is destroyed, the interpreter +shuts down and clears its memory. No Python functions can be called after this. + +Executing Python code +===================== + +There are a few different ways to run Python code. One option is to use `eval`, +`exec` or `eval_file`, as explained in :ref:`eval`. Here is a quick example in +the context of an executable with an embedded interpreter: + +.. code-block:: cpp + + #include + namespace py = pybind11; + + int main() { + py::scoped_interpreter guard{}; + + py::exec(R"( + kwargs = dict(name="World", number=42) + message = "Hello, {name}! The answer is {number}".format(**kwargs) + print(message) + )"); + } + +Alternatively, similar results can be achieved using pybind11's API (see +:doc:`/advanced/pycpp/index` for more details). + +.. code-block:: cpp + + #include + namespace py = pybind11; + using namespace py::literals; + + int main() { + py::scoped_interpreter guard{}; + + auto kwargs = py::dict("name"_a="World", "number"_a=42); + auto message = "Hello, {name}! The answer is {number}"_s.format(**kwargs); + py::print(message); + } + +The two approaches can also be combined: + +.. code-block:: cpp + + #include + #include + + namespace py = pybind11; + using namespace py::literals; + + int main() { + py::scoped_interpreter guard{}; + + auto locals = py::dict("name"_a="World", "number"_a=42); + py::exec(R"( + message = "Hello, {name}! The answer is {number}".format(**locals()) + )", py::globals(), locals); + + auto message = locals["message"].cast(); + std::cout << message; + } + +Importing modules +================= + +Python modules can be imported using `module::import()`: + +.. code-block:: cpp + + py::module sys = py::module::import("sys"); + py::print(sys.attr("path")); + +For convenience, the current working directory is included in ``sys.path`` when +embedding the interpreter. This makes it easy to import local Python files: + +.. code-block:: python + + """calc.py located in the working directory""" + + def add(i, j): + return i + j + + +.. code-block:: cpp + + py::module calc = py::module::import("calc"); + py::object result = calc.attr("add")(1, 2); + int n = result.cast(); + assert(n == 3); + +Modules can be reloaded using `module::reload()` if the source is modified e.g. +by an external process. This can be useful in scenarios where the application +imports a user defined data processing script which needs to be updated after +changes by the user. Note that this function does not reload modules recursively. + +.. _embedding_modules: + +Adding embedded modules +======================= + +Embedded binary modules can be added using the `PYBIND11_EMBEDDED_MODULE` macro. +Note that the definition must be placed at global scope. They can be imported +like any other module. + +.. code-block:: cpp + + #include + namespace py = pybind11; + + PYBIND11_EMBEDDED_MODULE(fast_calc, m) { + // `m` is a `py::module` which is used to bind functions and classes + m.def("add", [](int i, int j) { + return i + j; + }); + } + + int main() { + py::scoped_interpreter guard{}; + + auto fast_calc = py::module::import("fast_calc"); + auto result = fast_calc.attr("add")(1, 2).cast(); + assert(result == 3); + } + +Unlike extension modules where only a single binary module can be created, on +the embedded side an unlimited number of modules can be added using multiple +`PYBIND11_EMBEDDED_MODULE` definitions (as long as they have unique names). + +These modules are added to Python's list of builtins, so they can also be +imported in pure Python files loaded by the interpreter. Everything interacts +naturally: + +.. code-block:: python + + """py_module.py located in the working directory""" + import cpp_module + + a = cpp_module.a + b = a + 1 + + +.. code-block:: cpp + + #include + namespace py = pybind11; + + PYBIND11_EMBEDDED_MODULE(cpp_module, m) { + m.attr("a") = 1; + } + + int main() { + py::scoped_interpreter guard{}; + + auto py_module = py::module::import("py_module"); + + auto locals = py::dict("fmt"_a="{} + {} = {}", **py_module.attr("__dict__")); + assert(locals["a"].cast() == 1); + assert(locals["b"].cast() == 2); + + py::exec(R"( + c = a + b + message = fmt.format(a, b, c) + )", py::globals(), locals); + + assert(locals["c"].cast() == 3); + assert(locals["message"].cast() == "1 + 2 = 3"); + } + + +Interpreter lifetime +==================== + +The Python interpreter shuts down when `scoped_interpreter` is destroyed. After +this, creating a new instance will restart the interpreter. Alternatively, the +`initialize_interpreter` / `finalize_interpreter` pair of functions can be used +to directly set the state at any time. + +Modules created with pybind11 can be safely re-initialized after the interpreter +has been restarted. However, this may not apply to third-party extension modules. +The issue is that Python itself cannot completely unload extension modules and +there are several caveats with regard to interpreter restarting. In short, not +all memory may be freed, either due to Python reference cycles or user-created +global data. All the details can be found in the CPython documentation. + +.. warning:: + + Creating two concurrent `scoped_interpreter` guards is a fatal error. So is + calling `initialize_interpreter` for a second time after the interpreter + has already been initialized. + + Do not use the raw CPython API functions ``Py_Initialize`` and + ``Py_Finalize`` as these do not properly handle the lifetime of + pybind11's internal data. + + +Sub-interpreter support +======================= + +Creating multiple copies of `scoped_interpreter` is not possible because it +represents the main Python interpreter. Sub-interpreters are something different +and they do permit the existence of multiple interpreters. This is an advanced +feature of the CPython API and should be handled with care. pybind11 does not +currently offer a C++ interface for sub-interpreters, so refer to the CPython +documentation for all the details regarding this feature. + +We'll just mention a couple of caveats the sub-interpreters support in pybind11: + + 1. Sub-interpreters will not receive independent copies of embedded modules. + Instead, these are shared and modifications in one interpreter may be + reflected in another. + + 2. Managing multiple threads, multiple interpreters and the GIL can be + challenging and there are several caveats here, even within the pure + CPython API (please refer to the Python docs for details). As for + pybind11, keep in mind that `gil_scoped_release` and `gil_scoped_acquire` + do not take sub-interpreters into account. diff --git a/wrap/python/pybind11/docs/advanced/exceptions.rst b/wrap/python/pybind11/docs/advanced/exceptions.rst new file mode 100644 index 000000000..75ac24ae9 --- /dev/null +++ b/wrap/python/pybind11/docs/advanced/exceptions.rst @@ -0,0 +1,142 @@ +Exceptions +########## + +Built-in exception translation +============================== + +When C++ code invoked from Python throws an ``std::exception``, it is +automatically converted into a Python ``Exception``. pybind11 defines multiple +special exception classes that will map to different types of Python +exceptions: + +.. tabularcolumns:: |p{0.5\textwidth}|p{0.45\textwidth}| + ++--------------------------------------+--------------------------------------+ +| C++ exception type | Python exception type | ++======================================+======================================+ +| :class:`std::exception` | ``RuntimeError`` | ++--------------------------------------+--------------------------------------+ +| :class:`std::bad_alloc` | ``MemoryError`` | ++--------------------------------------+--------------------------------------+ +| :class:`std::domain_error` | ``ValueError`` | ++--------------------------------------+--------------------------------------+ +| :class:`std::invalid_argument` | ``ValueError`` | ++--------------------------------------+--------------------------------------+ +| :class:`std::length_error` | ``ValueError`` | ++--------------------------------------+--------------------------------------+ +| :class:`std::out_of_range` | ``IndexError`` | ++--------------------------------------+--------------------------------------+ +| :class:`std::range_error` | ``ValueError`` | ++--------------------------------------+--------------------------------------+ +| :class:`pybind11::stop_iteration` | ``StopIteration`` (used to implement | +| | custom iterators) | ++--------------------------------------+--------------------------------------+ +| :class:`pybind11::index_error` | ``IndexError`` (used to indicate out | +| | of bounds access in ``__getitem__``, | +| | ``__setitem__``, etc.) | ++--------------------------------------+--------------------------------------+ +| :class:`pybind11::value_error` | ``ValueError`` (used to indicate | +| | wrong value passed in | +| | ``container.remove(...)``) | ++--------------------------------------+--------------------------------------+ +| :class:`pybind11::key_error` | ``KeyError`` (used to indicate out | +| | of bounds access in ``__getitem__``, | +| | ``__setitem__`` in dict-like | +| | objects, etc.) | ++--------------------------------------+--------------------------------------+ +| :class:`pybind11::error_already_set` | Indicates that the Python exception | +| | flag has already been set via Python | +| | API calls from C++ code; this C++ | +| | exception is used to propagate such | +| | a Python exception back to Python. | ++--------------------------------------+--------------------------------------+ + +When a Python function invoked from C++ throws an exception, it is converted +into a C++ exception of type :class:`error_already_set` whose string payload +contains a textual summary. + +There is also a special exception :class:`cast_error` that is thrown by +:func:`handle::call` when the input arguments cannot be converted to Python +objects. + +Registering custom translators +============================== + +If the default exception conversion policy described above is insufficient, +pybind11 also provides support for registering custom exception translators. +To register a simple exception conversion that translates a C++ exception into +a new Python exception using the C++ exception's ``what()`` method, a helper +function is available: + +.. code-block:: cpp + + py::register_exception(module, "PyExp"); + +This call creates a Python exception class with the name ``PyExp`` in the given +module and automatically converts any encountered exceptions of type ``CppExp`` +into Python exceptions of type ``PyExp``. + +When more advanced exception translation is needed, the function +``py::register_exception_translator(translator)`` can be used to register +functions that can translate arbitrary exception types (and which may include +additional logic to do so). The function takes a stateless callable (e.g. a +function pointer or a lambda function without captured variables) with the call +signature ``void(std::exception_ptr)``. + +When a C++ exception is thrown, the registered exception translators are tried +in reverse order of registration (i.e. the last registered translator gets the +first shot at handling the exception). + +Inside the translator, ``std::rethrow_exception`` should be used within +a try block to re-throw the exception. One or more catch clauses to catch +the appropriate exceptions should then be used with each clause using +``PyErr_SetString`` to set a Python exception or ``ex(string)`` to set +the python exception to a custom exception type (see below). + +To declare a custom Python exception type, declare a ``py::exception`` variable +and use this in the associated exception translator (note: it is often useful +to make this a static declaration when using it inside a lambda expression +without requiring capturing). + + +The following example demonstrates this for a hypothetical exception classes +``MyCustomException`` and ``OtherException``: the first is translated to a +custom python exception ``MyCustomError``, while the second is translated to a +standard python RuntimeError: + +.. code-block:: cpp + + static py::exception exc(m, "MyCustomError"); + py::register_exception_translator([](std::exception_ptr p) { + try { + if (p) std::rethrow_exception(p); + } catch (const MyCustomException &e) { + exc(e.what()); + } catch (const OtherException &e) { + PyErr_SetString(PyExc_RuntimeError, e.what()); + } + }); + +Multiple exceptions can be handled by a single translator, as shown in the +example above. If the exception is not caught by the current translator, the +previously registered one gets a chance. + +If none of the registered exception translators is able to handle the +exception, it is handled by the default converter as described in the previous +section. + +.. seealso:: + + The file :file:`tests/test_exceptions.cpp` contains examples + of various custom exception translators and custom exception types. + +.. note:: + + You must call either ``PyErr_SetString`` or a custom exception's call + operator (``exc(string)``) for every exception caught in a custom exception + translator. Failure to do so will cause Python to crash with ``SystemError: + error return without exception set``. + + Exceptions that you do not plan to handle should simply not be caught, or + may be explicitly (re-)thrown to delegate it to the other, + previously-declared existing exception translators. diff --git a/wrap/python/pybind11/docs/advanced/functions.rst b/wrap/python/pybind11/docs/advanced/functions.rst new file mode 100644 index 000000000..3e1a3ff0e --- /dev/null +++ b/wrap/python/pybind11/docs/advanced/functions.rst @@ -0,0 +1,507 @@ +Functions +######### + +Before proceeding with this section, make sure that you are already familiar +with the basics of binding functions and classes, as explained in :doc:`/basics` +and :doc:`/classes`. The following guide is applicable to both free and member +functions, i.e. *methods* in Python. + +.. _return_value_policies: + +Return value policies +===================== + +Python and C++ use fundamentally different ways of managing the memory and +lifetime of objects managed by them. This can lead to issues when creating +bindings for functions that return a non-trivial type. Just by looking at the +type information, it is not clear whether Python should take charge of the +returned value and eventually free its resources, or if this is handled on the +C++ side. For this reason, pybind11 provides a several *return value policy* +annotations that can be passed to the :func:`module::def` and +:func:`class_::def` functions. The default policy is +:enum:`return_value_policy::automatic`. + +Return value policies are tricky, and it's very important to get them right. +Just to illustrate what can go wrong, consider the following simple example: + +.. code-block:: cpp + + /* Function declaration */ + Data *get_data() { return _data; /* (pointer to a static data structure) */ } + ... + + /* Binding code */ + m.def("get_data", &get_data); // <-- KABOOM, will cause crash when called from Python + +What's going on here? When ``get_data()`` is called from Python, the return +value (a native C++ type) must be wrapped to turn it into a usable Python type. +In this case, the default return value policy (:enum:`return_value_policy::automatic`) +causes pybind11 to assume ownership of the static ``_data`` instance. + +When Python's garbage collector eventually deletes the Python +wrapper, pybind11 will also attempt to delete the C++ instance (via ``operator +delete()``) due to the implied ownership. At this point, the entire application +will come crashing down, though errors could also be more subtle and involve +silent data corruption. + +In the above example, the policy :enum:`return_value_policy::reference` should have +been specified so that the global data instance is only *referenced* without any +implied transfer of ownership, i.e.: + +.. code-block:: cpp + + m.def("get_data", &get_data, return_value_policy::reference); + +On the other hand, this is not the right policy for many other situations, +where ignoring ownership could lead to resource leaks. +As a developer using pybind11, it's important to be familiar with the different +return value policies, including which situation calls for which one of them. +The following table provides an overview of available policies: + +.. tabularcolumns:: |p{0.5\textwidth}|p{0.45\textwidth}| + ++--------------------------------------------------+----------------------------------------------------------------------------+ +| Return value policy | Description | ++==================================================+============================================================================+ +| :enum:`return_value_policy::take_ownership` | Reference an existing object (i.e. do not create a new copy) and take | +| | ownership. Python will call the destructor and delete operator when the | +| | object's reference count reaches zero. Undefined behavior ensues when the | +| | C++ side does the same, or when the data was not dynamically allocated. | ++--------------------------------------------------+----------------------------------------------------------------------------+ +| :enum:`return_value_policy::copy` | Create a new copy of the returned object, which will be owned by Python. | +| | This policy is comparably safe because the lifetimes of the two instances | +| | are decoupled. | ++--------------------------------------------------+----------------------------------------------------------------------------+ +| :enum:`return_value_policy::move` | Use ``std::move`` to move the return value contents into a new instance | +| | that will be owned by Python. This policy is comparably safe because the | +| | lifetimes of the two instances (move source and destination) are decoupled.| ++--------------------------------------------------+----------------------------------------------------------------------------+ +| :enum:`return_value_policy::reference` | Reference an existing object, but do not take ownership. The C++ side is | +| | responsible for managing the object's lifetime and deallocating it when | +| | it is no longer used. Warning: undefined behavior will ensue when the C++ | +| | side deletes an object that is still referenced and used by Python. | ++--------------------------------------------------+----------------------------------------------------------------------------+ +| :enum:`return_value_policy::reference_internal` | Indicates that the lifetime of the return value is tied to the lifetime | +| | of a parent object, namely the implicit ``this``, or ``self`` argument of | +| | the called method or property. Internally, this policy works just like | +| | :enum:`return_value_policy::reference` but additionally applies a | +| | ``keep_alive<0, 1>`` *call policy* (described in the next section) that | +| | prevents the parent object from being garbage collected as long as the | +| | return value is referenced by Python. This is the default policy for | +| | property getters created via ``def_property``, ``def_readwrite``, etc. | ++--------------------------------------------------+----------------------------------------------------------------------------+ +| :enum:`return_value_policy::automatic` | **Default policy.** This policy falls back to the policy | +| | :enum:`return_value_policy::take_ownership` when the return value is a | +| | pointer. Otherwise, it uses :enum:`return_value_policy::move` or | +| | :enum:`return_value_policy::copy` for rvalue and lvalue references, | +| | respectively. See above for a description of what all of these different | +| | policies do. | ++--------------------------------------------------+----------------------------------------------------------------------------+ +| :enum:`return_value_policy::automatic_reference` | As above, but use policy :enum:`return_value_policy::reference` when the | +| | return value is a pointer. This is the default conversion policy for | +| | function arguments when calling Python functions manually from C++ code | +| | (i.e. via handle::operator()). You probably won't need to use this. | ++--------------------------------------------------+----------------------------------------------------------------------------+ + +Return value policies can also be applied to properties: + +.. code-block:: cpp + + class_(m, "MyClass") + .def_property("data", &MyClass::getData, &MyClass::setData, + py::return_value_policy::copy); + +Technically, the code above applies the policy to both the getter and the +setter function, however, the setter doesn't really care about *return* +value policies which makes this a convenient terse syntax. Alternatively, +targeted arguments can be passed through the :class:`cpp_function` constructor: + +.. code-block:: cpp + + class_(m, "MyClass") + .def_property("data" + py::cpp_function(&MyClass::getData, py::return_value_policy::copy), + py::cpp_function(&MyClass::setData) + ); + +.. warning:: + + Code with invalid return value policies might access uninitialized memory or + free data structures multiple times, which can lead to hard-to-debug + non-determinism and segmentation faults, hence it is worth spending the + time to understand all the different options in the table above. + +.. note:: + + One important aspect of the above policies is that they only apply to + instances which pybind11 has *not* seen before, in which case the policy + clarifies essential questions about the return value's lifetime and + ownership. When pybind11 knows the instance already (as identified by its + type and address in memory), it will return the existing Python object + wrapper rather than creating a new copy. + +.. note:: + + The next section on :ref:`call_policies` discusses *call policies* that can be + specified *in addition* to a return value policy from the list above. Call + policies indicate reference relationships that can involve both return values + and parameters of functions. + +.. note:: + + As an alternative to elaborate call policies and lifetime management logic, + consider using smart pointers (see the section on :ref:`smart_pointers` for + details). Smart pointers can tell whether an object is still referenced from + C++ or Python, which generally eliminates the kinds of inconsistencies that + can lead to crashes or undefined behavior. For functions returning smart + pointers, it is not necessary to specify a return value policy. + +.. _call_policies: + +Additional call policies +======================== + +In addition to the above return value policies, further *call policies* can be +specified to indicate dependencies between parameters or ensure a certain state +for the function call. + +Keep alive +---------- + +In general, this policy is required when the C++ object is any kind of container +and another object is being added to the container. ``keep_alive`` +indicates that the argument with index ``Patient`` should be kept alive at least +until the argument with index ``Nurse`` is freed by the garbage collector. Argument +indices start at one, while zero refers to the return value. For methods, index +``1`` refers to the implicit ``this`` pointer, while regular arguments begin at +index ``2``. Arbitrarily many call policies can be specified. When a ``Nurse`` +with value ``None`` is detected at runtime, the call policy does nothing. + +When the nurse is not a pybind11-registered type, the implementation internally +relies on the ability to create a *weak reference* to the nurse object. When +the nurse object is not a pybind11-registered type and does not support weak +references, an exception will be thrown. + +Consider the following example: here, the binding code for a list append +operation ties the lifetime of the newly added element to the underlying +container: + +.. code-block:: cpp + + py::class_(m, "List") + .def("append", &List::append, py::keep_alive<1, 2>()); + +For consistency, the argument indexing is identical for constructors. Index +``1`` still refers to the implicit ``this`` pointer, i.e. the object which is +being constructed. Index ``0`` refers to the return type which is presumed to +be ``void`` when a constructor is viewed like a function. The following example +ties the lifetime of the constructor element to the constructed object: + +.. code-block:: cpp + + py::class_(m, "Nurse") + .def(py::init(), py::keep_alive<1, 2>()); + +.. note:: + + ``keep_alive`` is analogous to the ``with_custodian_and_ward`` (if Nurse, + Patient != 0) and ``with_custodian_and_ward_postcall`` (if Nurse/Patient == + 0) policies from Boost.Python. + +Call guard +---------- + +The ``call_guard`` policy allows any scope guard type ``T`` to be placed +around the function call. For example, this definition: + +.. code-block:: cpp + + m.def("foo", foo, py::call_guard()); + +is equivalent to the following pseudocode: + +.. code-block:: cpp + + m.def("foo", [](args...) { + T scope_guard; + return foo(args...); // forwarded arguments + }); + +The only requirement is that ``T`` is default-constructible, but otherwise any +scope guard will work. This is very useful in combination with `gil_scoped_release`. +See :ref:`gil`. + +Multiple guards can also be specified as ``py::call_guard``. The +constructor order is left to right and destruction happens in reverse. + +.. seealso:: + + The file :file:`tests/test_call_policies.cpp` contains a complete example + that demonstrates using `keep_alive` and `call_guard` in more detail. + +.. _python_objects_as_args: + +Python objects as arguments +=========================== + +pybind11 exposes all major Python types using thin C++ wrapper classes. These +wrapper classes can also be used as parameters of functions in bindings, which +makes it possible to directly work with native Python types on the C++ side. +For instance, the following statement iterates over a Python ``dict``: + +.. code-block:: cpp + + void print_dict(py::dict dict) { + /* Easily interact with Python types */ + for (auto item : dict) + std::cout << "key=" << std::string(py::str(item.first)) << ", " + << "value=" << std::string(py::str(item.second)) << std::endl; + } + +It can be exported: + +.. code-block:: cpp + + m.def("print_dict", &print_dict); + +And used in Python as usual: + +.. code-block:: pycon + + >>> print_dict({'foo': 123, 'bar': 'hello'}) + key=foo, value=123 + key=bar, value=hello + +For more information on using Python objects in C++, see :doc:`/advanced/pycpp/index`. + +Accepting \*args and \*\*kwargs +=============================== + +Python provides a useful mechanism to define functions that accept arbitrary +numbers of arguments and keyword arguments: + +.. code-block:: python + + def generic(*args, **kwargs): + ... # do something with args and kwargs + +Such functions can also be created using pybind11: + +.. code-block:: cpp + + void generic(py::args args, py::kwargs kwargs) { + /// .. do something with args + if (kwargs) + /// .. do something with kwargs + } + + /// Binding code + m.def("generic", &generic); + +The class ``py::args`` derives from ``py::tuple`` and ``py::kwargs`` derives +from ``py::dict``. + +You may also use just one or the other, and may combine these with other +arguments as long as the ``py::args`` and ``py::kwargs`` arguments are the last +arguments accepted by the function. + +Please refer to the other examples for details on how to iterate over these, +and on how to cast their entries into C++ objects. A demonstration is also +available in ``tests/test_kwargs_and_defaults.cpp``. + +.. note:: + + When combining \*args or \*\*kwargs with :ref:`keyword_args` you should + *not* include ``py::arg`` tags for the ``py::args`` and ``py::kwargs`` + arguments. + +Default arguments revisited +=========================== + +The section on :ref:`default_args` previously discussed basic usage of default +arguments using pybind11. One noteworthy aspect of their implementation is that +default arguments are converted to Python objects right at declaration time. +Consider the following example: + +.. code-block:: cpp + + py::class_("MyClass") + .def("myFunction", py::arg("arg") = SomeType(123)); + +In this case, pybind11 must already be set up to deal with values of the type +``SomeType`` (via a prior instantiation of ``py::class_``), or an +exception will be thrown. + +Another aspect worth highlighting is that the "preview" of the default argument +in the function signature is generated using the object's ``__repr__`` method. +If not available, the signature may not be very helpful, e.g.: + +.. code-block:: pycon + + FUNCTIONS + ... + | myFunction(...) + | Signature : (MyClass, arg : SomeType = ) -> NoneType + ... + +The first way of addressing this is by defining ``SomeType.__repr__``. +Alternatively, it is possible to specify the human-readable preview of the +default argument manually using the ``arg_v`` notation: + +.. code-block:: cpp + + py::class_("MyClass") + .def("myFunction", py::arg_v("arg", SomeType(123), "SomeType(123)")); + +Sometimes it may be necessary to pass a null pointer value as a default +argument. In this case, remember to cast it to the underlying type in question, +like so: + +.. code-block:: cpp + + py::class_("MyClass") + .def("myFunction", py::arg("arg") = (SomeType *) nullptr); + +.. _nonconverting_arguments: + +Non-converting arguments +======================== + +Certain argument types may support conversion from one type to another. Some +examples of conversions are: + +* :ref:`implicit_conversions` declared using ``py::implicitly_convertible()`` +* Calling a method accepting a double with an integer argument +* Calling a ``std::complex`` argument with a non-complex python type + (for example, with a float). (Requires the optional ``pybind11/complex.h`` + header). +* Calling a function taking an Eigen matrix reference with a numpy array of the + wrong type or of an incompatible data layout. (Requires the optional + ``pybind11/eigen.h`` header). + +This behaviour is sometimes undesirable: the binding code may prefer to raise +an error rather than convert the argument. This behaviour can be obtained +through ``py::arg`` by calling the ``.noconvert()`` method of the ``py::arg`` +object, such as: + +.. code-block:: cpp + + m.def("floats_only", [](double f) { return 0.5 * f; }, py::arg("f").noconvert()); + m.def("floats_preferred", [](double f) { return 0.5 * f; }, py::arg("f")); + +Attempting the call the second function (the one without ``.noconvert()``) with +an integer will succeed, but attempting to call the ``.noconvert()`` version +will fail with a ``TypeError``: + +.. code-block:: pycon + + >>> floats_preferred(4) + 2.0 + >>> floats_only(4) + Traceback (most recent call last): + File "", line 1, in + TypeError: floats_only(): incompatible function arguments. The following argument types are supported: + 1. (f: float) -> float + + Invoked with: 4 + +You may, of course, combine this with the :var:`_a` shorthand notation (see +:ref:`keyword_args`) and/or :ref:`default_args`. It is also permitted to omit +the argument name by using the ``py::arg()`` constructor without an argument +name, i.e. by specifying ``py::arg().noconvert()``. + +.. note:: + + When specifying ``py::arg`` options it is necessary to provide the same + number of options as the bound function has arguments. Thus if you want to + enable no-convert behaviour for just one of several arguments, you will + need to specify a ``py::arg()`` annotation for each argument with the + no-convert argument modified to ``py::arg().noconvert()``. + +.. _none_arguments: + +Allow/Prohibiting None arguments +================================ + +When a C++ type registered with :class:`py::class_` is passed as an argument to +a function taking the instance as pointer or shared holder (e.g. ``shared_ptr`` +or a custom, copyable holder as described in :ref:`smart_pointers`), pybind +allows ``None`` to be passed from Python which results in calling the C++ +function with ``nullptr`` (or an empty holder) for the argument. + +To explicitly enable or disable this behaviour, using the +``.none`` method of the :class:`py::arg` object: + +.. code-block:: cpp + + py::class_(m, "Dog").def(py::init<>()); + py::class_(m, "Cat").def(py::init<>()); + m.def("bark", [](Dog *dog) -> std::string { + if (dog) return "woof!"; /* Called with a Dog instance */ + else return "(no dog)"; /* Called with None, dog == nullptr */ + }, py::arg("dog").none(true)); + m.def("meow", [](Cat *cat) -> std::string { + // Can't be called with None argument + return "meow"; + }, py::arg("cat").none(false)); + +With the above, the Python call ``bark(None)`` will return the string ``"(no +dog)"``, while attempting to call ``meow(None)`` will raise a ``TypeError``: + +.. code-block:: pycon + + >>> from animals import Dog, Cat, bark, meow + >>> bark(Dog()) + 'woof!' + >>> meow(Cat()) + 'meow' + >>> bark(None) + '(no dog)' + >>> meow(None) + Traceback (most recent call last): + File "", line 1, in + TypeError: meow(): incompatible function arguments. The following argument types are supported: + 1. (cat: animals.Cat) -> str + + Invoked with: None + +The default behaviour when the tag is unspecified is to allow ``None``. + +.. note:: + + Even when ``.none(true)`` is specified for an argument, ``None`` will be converted to a + ``nullptr`` *only* for custom and :ref:`opaque ` types. Pointers to built-in types + (``double *``, ``int *``, ...) and STL types (``std::vector *``, ...; if ``pybind11/stl.h`` + is included) are copied when converted to C++ (see :doc:`/advanced/cast/overview`) and will + not allow ``None`` as argument. To pass optional argument of these copied types consider + using ``std::optional`` + +Overload resolution order +========================= + +When a function or method with multiple overloads is called from Python, +pybind11 determines which overload to call in two passes. The first pass +attempts to call each overload without allowing argument conversion (as if +every argument had been specified as ``py::arg().noconvert()`` as described +above). + +If no overload succeeds in the no-conversion first pass, a second pass is +attempted in which argument conversion is allowed (except where prohibited via +an explicit ``py::arg().noconvert()`` attribute in the function definition). + +If the second pass also fails a ``TypeError`` is raised. + +Within each pass, overloads are tried in the order they were registered with +pybind11. + +What this means in practice is that pybind11 will prefer any overload that does +not require conversion of arguments to an overload that does, but otherwise prefers +earlier-defined overloads to later-defined ones. + +.. note:: + + pybind11 does *not* further prioritize based on the number/pattern of + overloaded arguments. That is, pybind11 does not prioritize a function + requiring one conversion over one requiring three, but only prioritizes + overloads requiring no conversion at all to overloads that require + conversion of at least one argument. diff --git a/wrap/python/pybind11/docs/advanced/misc.rst b/wrap/python/pybind11/docs/advanced/misc.rst new file mode 100644 index 000000000..5b38ec759 --- /dev/null +++ b/wrap/python/pybind11/docs/advanced/misc.rst @@ -0,0 +1,306 @@ +Miscellaneous +############# + +.. _macro_notes: + +General notes regarding convenience macros +========================================== + +pybind11 provides a few convenience macros such as +:func:`PYBIND11_DECLARE_HOLDER_TYPE` and ``PYBIND11_OVERLOAD_*``. Since these +are "just" macros that are evaluated in the preprocessor (which has no concept +of types), they *will* get confused by commas in a template argument; for +example, consider: + +.. code-block:: cpp + + PYBIND11_OVERLOAD(MyReturnType, Class, func) + +The limitation of the C preprocessor interprets this as five arguments (with new +arguments beginning after each comma) rather than three. To get around this, +there are two alternatives: you can use a type alias, or you can wrap the type +using the ``PYBIND11_TYPE`` macro: + +.. code-block:: cpp + + // Version 1: using a type alias + using ReturnType = MyReturnType; + using ClassType = Class; + PYBIND11_OVERLOAD(ReturnType, ClassType, func); + + // Version 2: using the PYBIND11_TYPE macro: + PYBIND11_OVERLOAD(PYBIND11_TYPE(MyReturnType), + PYBIND11_TYPE(Class), func) + +The ``PYBIND11_MAKE_OPAQUE`` macro does *not* require the above workarounds. + +.. _gil: + +Global Interpreter Lock (GIL) +============================= + +When calling a C++ function from Python, the GIL is always held. +The classes :class:`gil_scoped_release` and :class:`gil_scoped_acquire` can be +used to acquire and release the global interpreter lock in the body of a C++ +function call. In this way, long-running C++ code can be parallelized using +multiple Python threads. Taking :ref:`overriding_virtuals` as an example, this +could be realized as follows (important changes highlighted): + +.. code-block:: cpp + :emphasize-lines: 8,9,31,32 + + class PyAnimal : public Animal { + public: + /* Inherit the constructors */ + using Animal::Animal; + + /* Trampoline (need one for each virtual function) */ + std::string go(int n_times) { + /* Acquire GIL before calling Python code */ + py::gil_scoped_acquire acquire; + + PYBIND11_OVERLOAD_PURE( + std::string, /* Return type */ + Animal, /* Parent class */ + go, /* Name of function */ + n_times /* Argument(s) */ + ); + } + }; + + PYBIND11_MODULE(example, m) { + py::class_ animal(m, "Animal"); + animal + .def(py::init<>()) + .def("go", &Animal::go); + + py::class_(m, "Dog", animal) + .def(py::init<>()); + + m.def("call_go", [](Animal *animal) -> std::string { + /* Release GIL before calling into (potentially long-running) C++ code */ + py::gil_scoped_release release; + return call_go(animal); + }); + } + +The ``call_go`` wrapper can also be simplified using the `call_guard` policy +(see :ref:`call_policies`) which yields the same result: + +.. code-block:: cpp + + m.def("call_go", &call_go, py::call_guard()); + + +Binding sequence data types, iterators, the slicing protocol, etc. +================================================================== + +Please refer to the supplemental example for details. + +.. seealso:: + + The file :file:`tests/test_sequences_and_iterators.cpp` contains a + complete example that shows how to bind a sequence data type, including + length queries (``__len__``), iterators (``__iter__``), the slicing + protocol and other kinds of useful operations. + + +Partitioning code over multiple extension modules +================================================= + +It's straightforward to split binding code over multiple extension modules, +while referencing types that are declared elsewhere. Everything "just" works +without any special precautions. One exception to this rule occurs when +extending a type declared in another extension module. Recall the basic example +from Section :ref:`inheritance`. + +.. code-block:: cpp + + py::class_ pet(m, "Pet"); + pet.def(py::init()) + .def_readwrite("name", &Pet::name); + + py::class_(m, "Dog", pet /* <- specify parent */) + .def(py::init()) + .def("bark", &Dog::bark); + +Suppose now that ``Pet`` bindings are defined in a module named ``basic``, +whereas the ``Dog`` bindings are defined somewhere else. The challenge is of +course that the variable ``pet`` is not available anymore though it is needed +to indicate the inheritance relationship to the constructor of ``class_``. +However, it can be acquired as follows: + +.. code-block:: cpp + + py::object pet = (py::object) py::module::import("basic").attr("Pet"); + + py::class_(m, "Dog", pet) + .def(py::init()) + .def("bark", &Dog::bark); + +Alternatively, you can specify the base class as a template parameter option to +``class_``, which performs an automated lookup of the corresponding Python +type. Like the above code, however, this also requires invoking the ``import`` +function once to ensure that the pybind11 binding code of the module ``basic`` +has been executed: + +.. code-block:: cpp + + py::module::import("basic"); + + py::class_(m, "Dog") + .def(py::init()) + .def("bark", &Dog::bark); + +Naturally, both methods will fail when there are cyclic dependencies. + +Note that pybind11 code compiled with hidden-by-default symbol visibility (e.g. +via the command line flag ``-fvisibility=hidden`` on GCC/Clang), which is +required for proper pybind11 functionality, can interfere with the ability to +access types defined in another extension module. Working around this requires +manually exporting types that are accessed by multiple extension modules; +pybind11 provides a macro to do just this: + +.. code-block:: cpp + + class PYBIND11_EXPORT Dog : public Animal { + ... + }; + +Note also that it is possible (although would rarely be required) to share arbitrary +C++ objects between extension modules at runtime. Internal library data is shared +between modules using capsule machinery [#f6]_ which can be also utilized for +storing, modifying and accessing user-defined data. Note that an extension module +will "see" other extensions' data if and only if they were built with the same +pybind11 version. Consider the following example: + +.. code-block:: cpp + + auto data = (MyData *) py::get_shared_data("mydata"); + if (!data) + data = (MyData *) py::set_shared_data("mydata", new MyData(42)); + +If the above snippet was used in several separately compiled extension modules, +the first one to be imported would create a ``MyData`` instance and associate +a ``"mydata"`` key with a pointer to it. Extensions that are imported later +would be then able to access the data behind the same pointer. + +.. [#f6] https://docs.python.org/3/extending/extending.html#using-capsules + +Module Destructors +================== + +pybind11 does not provide an explicit mechanism to invoke cleanup code at +module destruction time. In rare cases where such functionality is required, it +is possible to emulate it using Python capsules or weak references with a +destruction callback. + +.. code-block:: cpp + + auto cleanup_callback = []() { + // perform cleanup here -- this function is called with the GIL held + }; + + m.add_object("_cleanup", py::capsule(cleanup_callback)); + +This approach has the potential downside that instances of classes exposed +within the module may still be alive when the cleanup callback is invoked +(whether this is acceptable will generally depend on the application). + +Alternatively, the capsule may also be stashed within a type object, which +ensures that it not called before all instances of that type have been +collected: + +.. code-block:: cpp + + auto cleanup_callback = []() { /* ... */ }; + m.attr("BaseClass").attr("_cleanup") = py::capsule(cleanup_callback); + +Both approaches also expose a potentially dangerous ``_cleanup`` attribute in +Python, which may be undesirable from an API standpoint (a premature explicit +call from Python might lead to undefined behavior). Yet another approach that +avoids this issue involves weak reference with a cleanup callback: + +.. code-block:: cpp + + // Register a callback function that is invoked when the BaseClass object is colelcted + py::cpp_function cleanup_callback( + [](py::handle weakref) { + // perform cleanup here -- this function is called with the GIL held + + weakref.dec_ref(); // release weak reference + } + ); + + // Create a weak reference with a cleanup callback and initially leak it + (void) py::weakref(m.attr("BaseClass"), cleanup_callback).release(); + +.. note:: + + PyPy (at least version 5.9) does not garbage collect objects when the + interpreter exits. An alternative approach (which also works on CPython) is to use + the :py:mod:`atexit` module [#f7]_, for example: + + .. code-block:: cpp + + auto atexit = py::module::import("atexit"); + atexit.attr("register")(py::cpp_function([]() { + // perform cleanup here -- this function is called with the GIL held + })); + + .. [#f7] https://docs.python.org/3/library/atexit.html + + +Generating documentation using Sphinx +===================================== + +Sphinx [#f4]_ has the ability to inspect the signatures and documentation +strings in pybind11-based extension modules to automatically generate beautiful +documentation in a variety formats. The python_example repository [#f5]_ contains a +simple example repository which uses this approach. + +There are two potential gotchas when using this approach: first, make sure that +the resulting strings do not contain any :kbd:`TAB` characters, which break the +docstring parsing routines. You may want to use C++11 raw string literals, +which are convenient for multi-line comments. Conveniently, any excess +indentation will be automatically be removed by Sphinx. However, for this to +work, it is important that all lines are indented consistently, i.e.: + +.. code-block:: cpp + + // ok + m.def("foo", &foo, R"mydelimiter( + The foo function + + Parameters + ---------- + )mydelimiter"); + + // *not ok* + m.def("foo", &foo, R"mydelimiter(The foo function + + Parameters + ---------- + )mydelimiter"); + +By default, pybind11 automatically generates and prepends a signature to the docstring of a function +registered with ``module::def()`` and ``class_::def()``. Sometimes this +behavior is not desirable, because you want to provide your own signature or remove +the docstring completely to exclude the function from the Sphinx documentation. +The class ``options`` allows you to selectively suppress auto-generated signatures: + +.. code-block:: cpp + + PYBIND11_MODULE(example, m) { + py::options options; + options.disable_function_signatures(); + + m.def("add", [](int a, int b) { return a + b; }, "A function which adds two numbers"); + } + +Note that changes to the settings affect only function bindings created during the +lifetime of the ``options`` instance. When it goes out of scope at the end of the module's init function, +the default settings are restored to prevent unwanted side effects. + +.. [#f4] http://www.sphinx-doc.org +.. [#f5] http://github.com/pybind/python_example diff --git a/wrap/python/pybind11/docs/advanced/pycpp/index.rst b/wrap/python/pybind11/docs/advanced/pycpp/index.rst new file mode 100644 index 000000000..6885bdcff --- /dev/null +++ b/wrap/python/pybind11/docs/advanced/pycpp/index.rst @@ -0,0 +1,13 @@ +Python C++ interface +#################### + +pybind11 exposes Python types and functions using thin C++ wrappers, which +makes it possible to conveniently call Python code from C++ without resorting +to Python's C API. + +.. toctree:: + :maxdepth: 2 + + object + numpy + utilities diff --git a/wrap/python/pybind11/docs/advanced/pycpp/numpy.rst b/wrap/python/pybind11/docs/advanced/pycpp/numpy.rst new file mode 100644 index 000000000..458f99e97 --- /dev/null +++ b/wrap/python/pybind11/docs/advanced/pycpp/numpy.rst @@ -0,0 +1,386 @@ +.. _numpy: + +NumPy +##### + +Buffer protocol +=============== + +Python supports an extremely general and convenient approach for exchanging +data between plugin libraries. Types can expose a buffer view [#f2]_, which +provides fast direct access to the raw internal data representation. Suppose we +want to bind the following simplistic Matrix class: + +.. code-block:: cpp + + class Matrix { + public: + Matrix(size_t rows, size_t cols) : m_rows(rows), m_cols(cols) { + m_data = new float[rows*cols]; + } + float *data() { return m_data; } + size_t rows() const { return m_rows; } + size_t cols() const { return m_cols; } + private: + size_t m_rows, m_cols; + float *m_data; + }; + +The following binding code exposes the ``Matrix`` contents as a buffer object, +making it possible to cast Matrices into NumPy arrays. It is even possible to +completely avoid copy operations with Python expressions like +``np.array(matrix_instance, copy = False)``. + +.. code-block:: cpp + + py::class_(m, "Matrix", py::buffer_protocol()) + .def_buffer([](Matrix &m) -> py::buffer_info { + return py::buffer_info( + m.data(), /* Pointer to buffer */ + sizeof(float), /* Size of one scalar */ + py::format_descriptor::format(), /* Python struct-style format descriptor */ + 2, /* Number of dimensions */ + { m.rows(), m.cols() }, /* Buffer dimensions */ + { sizeof(float) * m.cols(), /* Strides (in bytes) for each index */ + sizeof(float) } + ); + }); + +Supporting the buffer protocol in a new type involves specifying the special +``py::buffer_protocol()`` tag in the ``py::class_`` constructor and calling the +``def_buffer()`` method with a lambda function that creates a +``py::buffer_info`` description record on demand describing a given matrix +instance. The contents of ``py::buffer_info`` mirror the Python buffer protocol +specification. + +.. code-block:: cpp + + struct buffer_info { + void *ptr; + ssize_t itemsize; + std::string format; + ssize_t ndim; + std::vector shape; + std::vector strides; + }; + +To create a C++ function that can take a Python buffer object as an argument, +simply use the type ``py::buffer`` as one of its arguments. Buffers can exist +in a great variety of configurations, hence some safety checks are usually +necessary in the function body. Below, you can see an basic example on how to +define a custom constructor for the Eigen double precision matrix +(``Eigen::MatrixXd``) type, which supports initialization from compatible +buffer objects (e.g. a NumPy matrix). + +.. code-block:: cpp + + /* Bind MatrixXd (or some other Eigen type) to Python */ + typedef Eigen::MatrixXd Matrix; + + typedef Matrix::Scalar Scalar; + constexpr bool rowMajor = Matrix::Flags & Eigen::RowMajorBit; + + py::class_(m, "Matrix", py::buffer_protocol()) + .def("__init__", [](Matrix &m, py::buffer b) { + typedef Eigen::Stride Strides; + + /* Request a buffer descriptor from Python */ + py::buffer_info info = b.request(); + + /* Some sanity checks ... */ + if (info.format != py::format_descriptor::format()) + throw std::runtime_error("Incompatible format: expected a double array!"); + + if (info.ndim != 2) + throw std::runtime_error("Incompatible buffer dimension!"); + + auto strides = Strides( + info.strides[rowMajor ? 0 : 1] / (py::ssize_t)sizeof(Scalar), + info.strides[rowMajor ? 1 : 0] / (py::ssize_t)sizeof(Scalar)); + + auto map = Eigen::Map( + static_cast(info.ptr), info.shape[0], info.shape[1], strides); + + new (&m) Matrix(map); + }); + +For reference, the ``def_buffer()`` call for this Eigen data type should look +as follows: + +.. code-block:: cpp + + .def_buffer([](Matrix &m) -> py::buffer_info { + return py::buffer_info( + m.data(), /* Pointer to buffer */ + sizeof(Scalar), /* Size of one scalar */ + py::format_descriptor::format(), /* Python struct-style format descriptor */ + 2, /* Number of dimensions */ + { m.rows(), m.cols() }, /* Buffer dimensions */ + { sizeof(Scalar) * (rowMajor ? m.cols() : 1), + sizeof(Scalar) * (rowMajor ? 1 : m.rows()) } + /* Strides (in bytes) for each index */ + ); + }) + +For a much easier approach of binding Eigen types (although with some +limitations), refer to the section on :doc:`/advanced/cast/eigen`. + +.. seealso:: + + The file :file:`tests/test_buffers.cpp` contains a complete example + that demonstrates using the buffer protocol with pybind11 in more detail. + +.. [#f2] http://docs.python.org/3/c-api/buffer.html + +Arrays +====== + +By exchanging ``py::buffer`` with ``py::array`` in the above snippet, we can +restrict the function so that it only accepts NumPy arrays (rather than any +type of Python object satisfying the buffer protocol). + +In many situations, we want to define a function which only accepts a NumPy +array of a certain data type. This is possible via the ``py::array_t`` +template. For instance, the following function requires the argument to be a +NumPy array containing double precision values. + +.. code-block:: cpp + + void f(py::array_t array); + +When it is invoked with a different type (e.g. an integer or a list of +integers), the binding code will attempt to cast the input into a NumPy array +of the requested type. Note that this feature requires the +:file:`pybind11/numpy.h` header to be included. + +Data in NumPy arrays is not guaranteed to packed in a dense manner; +furthermore, entries can be separated by arbitrary column and row strides. +Sometimes, it can be useful to require a function to only accept dense arrays +using either the C (row-major) or Fortran (column-major) ordering. This can be +accomplished via a second template argument with values ``py::array::c_style`` +or ``py::array::f_style``. + +.. code-block:: cpp + + void f(py::array_t array); + +The ``py::array::forcecast`` argument is the default value of the second +template parameter, and it ensures that non-conforming arguments are converted +into an array satisfying the specified requirements instead of trying the next +function overload. + +Structured types +================ + +In order for ``py::array_t`` to work with structured (record) types, we first +need to register the memory layout of the type. This can be done via +``PYBIND11_NUMPY_DTYPE`` macro, called in the plugin definition code, which +expects the type followed by field names: + +.. code-block:: cpp + + struct A { + int x; + double y; + }; + + struct B { + int z; + A a; + }; + + // ... + PYBIND11_MODULE(test, m) { + // ... + + PYBIND11_NUMPY_DTYPE(A, x, y); + PYBIND11_NUMPY_DTYPE(B, z, a); + /* now both A and B can be used as template arguments to py::array_t */ + } + +The structure should consist of fundamental arithmetic types, ``std::complex``, +previously registered substructures, and arrays of any of the above. Both C++ +arrays and ``std::array`` are supported. While there is a static assertion to +prevent many types of unsupported structures, it is still the user's +responsibility to use only "plain" structures that can be safely manipulated as +raw memory without violating invariants. + +Vectorizing functions +===================== + +Suppose we want to bind a function with the following signature to Python so +that it can process arbitrary NumPy array arguments (vectors, matrices, general +N-D arrays) in addition to its normal arguments: + +.. code-block:: cpp + + double my_func(int x, float y, double z); + +After including the ``pybind11/numpy.h`` header, this is extremely simple: + +.. code-block:: cpp + + m.def("vectorized_func", py::vectorize(my_func)); + +Invoking the function like below causes 4 calls to be made to ``my_func`` with +each of the array elements. The significant advantage of this compared to +solutions like ``numpy.vectorize()`` is that the loop over the elements runs +entirely on the C++ side and can be crunched down into a tight, optimized loop +by the compiler. The result is returned as a NumPy array of type +``numpy.dtype.float64``. + +.. code-block:: pycon + + >>> x = np.array([[1, 3],[5, 7]]) + >>> y = np.array([[2, 4],[6, 8]]) + >>> z = 3 + >>> result = vectorized_func(x, y, z) + +The scalar argument ``z`` is transparently replicated 4 times. The input +arrays ``x`` and ``y`` are automatically converted into the right types (they +are of type ``numpy.dtype.int64`` but need to be ``numpy.dtype.int32`` and +``numpy.dtype.float32``, respectively). + +.. note:: + + Only arithmetic, complex, and POD types passed by value or by ``const &`` + reference are vectorized; all other arguments are passed through as-is. + Functions taking rvalue reference arguments cannot be vectorized. + +In cases where the computation is too complicated to be reduced to +``vectorize``, it will be necessary to create and access the buffer contents +manually. The following snippet contains a complete example that shows how this +works (the code is somewhat contrived, since it could have been done more +simply using ``vectorize``). + +.. code-block:: cpp + + #include + #include + + namespace py = pybind11; + + py::array_t add_arrays(py::array_t input1, py::array_t input2) { + py::buffer_info buf1 = input1.request(), buf2 = input2.request(); + + if (buf1.ndim != 1 || buf2.ndim != 1) + throw std::runtime_error("Number of dimensions must be one"); + + if (buf1.size != buf2.size) + throw std::runtime_error("Input shapes must match"); + + /* No pointer is passed, so NumPy will allocate the buffer */ + auto result = py::array_t(buf1.size); + + py::buffer_info buf3 = result.request(); + + double *ptr1 = (double *) buf1.ptr, + *ptr2 = (double *) buf2.ptr, + *ptr3 = (double *) buf3.ptr; + + for (size_t idx = 0; idx < buf1.shape[0]; idx++) + ptr3[idx] = ptr1[idx] + ptr2[idx]; + + return result; + } + + PYBIND11_MODULE(test, m) { + m.def("add_arrays", &add_arrays, "Add two NumPy arrays"); + } + +.. seealso:: + + The file :file:`tests/test_numpy_vectorize.cpp` contains a complete + example that demonstrates using :func:`vectorize` in more detail. + +Direct access +============= + +For performance reasons, particularly when dealing with very large arrays, it +is often desirable to directly access array elements without internal checking +of dimensions and bounds on every access when indices are known to be already +valid. To avoid such checks, the ``array`` class and ``array_t`` template +class offer an unchecked proxy object that can be used for this unchecked +access through the ``unchecked`` and ``mutable_unchecked`` methods, +where ``N`` gives the required dimensionality of the array: + +.. code-block:: cpp + + m.def("sum_3d", [](py::array_t x) { + auto r = x.unchecked<3>(); // x must have ndim = 3; can be non-writeable + double sum = 0; + for (ssize_t i = 0; i < r.shape(0); i++) + for (ssize_t j = 0; j < r.shape(1); j++) + for (ssize_t k = 0; k < r.shape(2); k++) + sum += r(i, j, k); + return sum; + }); + m.def("increment_3d", [](py::array_t x) { + auto r = x.mutable_unchecked<3>(); // Will throw if ndim != 3 or flags.writeable is false + for (ssize_t i = 0; i < r.shape(0); i++) + for (ssize_t j = 0; j < r.shape(1); j++) + for (ssize_t k = 0; k < r.shape(2); k++) + r(i, j, k) += 1.0; + }, py::arg().noconvert()); + +To obtain the proxy from an ``array`` object, you must specify both the data +type and number of dimensions as template arguments, such as ``auto r = +myarray.mutable_unchecked()``. + +If the number of dimensions is not known at compile time, you can omit the +dimensions template parameter (i.e. calling ``arr_t.unchecked()`` or +``arr.unchecked()``. This will give you a proxy object that works in the +same way, but results in less optimizable code and thus a small efficiency +loss in tight loops. + +Note that the returned proxy object directly references the array's data, and +only reads its shape, strides, and writeable flag when constructed. You must +take care to ensure that the referenced array is not destroyed or reshaped for +the duration of the returned object, typically by limiting the scope of the +returned instance. + +The returned proxy object supports some of the same methods as ``py::array`` so +that it can be used as a drop-in replacement for some existing, index-checked +uses of ``py::array``: + +- ``r.ndim()`` returns the number of dimensions + +- ``r.data(1, 2, ...)`` and ``r.mutable_data(1, 2, ...)``` returns a pointer to + the ``const T`` or ``T`` data, respectively, at the given indices. The + latter is only available to proxies obtained via ``a.mutable_unchecked()``. + +- ``itemsize()`` returns the size of an item in bytes, i.e. ``sizeof(T)``. + +- ``ndim()`` returns the number of dimensions. + +- ``shape(n)`` returns the size of dimension ``n`` + +- ``size()`` returns the total number of elements (i.e. the product of the shapes). + +- ``nbytes()`` returns the number of bytes used by the referenced elements + (i.e. ``itemsize()`` times ``size()``). + +.. seealso:: + + The file :file:`tests/test_numpy_array.cpp` contains additional examples + demonstrating the use of this feature. + +Ellipsis +======== + +Python 3 provides a convenient ``...`` ellipsis notation that is often used to +slice multidimensional arrays. For instance, the following snippet extracts the +middle dimensions of a tensor with the first and last index set to zero. + +.. code-block:: python + + a = # a NumPy array + b = a[0, ..., 0] + +The function ``py::ellipsis()`` function can be used to perform the same +operation on the C++ side: + +.. code-block:: cpp + + py::array a = /* A NumPy array */; + py::array b = a[py::make_tuple(0, py::ellipsis(), 0)]; diff --git a/wrap/python/pybind11/docs/advanced/pycpp/object.rst b/wrap/python/pybind11/docs/advanced/pycpp/object.rst new file mode 100644 index 000000000..117131edc --- /dev/null +++ b/wrap/python/pybind11/docs/advanced/pycpp/object.rst @@ -0,0 +1,170 @@ +Python types +############ + +Available wrappers +================== + +All major Python types are available as thin C++ wrapper classes. These +can also be used as function parameters -- see :ref:`python_objects_as_args`. + +Available types include :class:`handle`, :class:`object`, :class:`bool_`, +:class:`int_`, :class:`float_`, :class:`str`, :class:`bytes`, :class:`tuple`, +:class:`list`, :class:`dict`, :class:`slice`, :class:`none`, :class:`capsule`, +:class:`iterable`, :class:`iterator`, :class:`function`, :class:`buffer`, +:class:`array`, and :class:`array_t`. + +Casting back and forth +====================== + +In this kind of mixed code, it is often necessary to convert arbitrary C++ +types to Python, which can be done using :func:`py::cast`: + +.. code-block:: cpp + + MyClass *cls = ..; + py::object obj = py::cast(cls); + +The reverse direction uses the following syntax: + +.. code-block:: cpp + + py::object obj = ...; + MyClass *cls = obj.cast(); + +When conversion fails, both directions throw the exception :class:`cast_error`. + +.. _python_libs: + +Accessing Python libraries from C++ +=================================== + +It is also possible to import objects defined in the Python standard +library or available in the current Python environment (``sys.path``) and work +with these in C++. + +This example obtains a reference to the Python ``Decimal`` class. + +.. code-block:: cpp + + // Equivalent to "from decimal import Decimal" + py::object Decimal = py::module::import("decimal").attr("Decimal"); + +.. code-block:: cpp + + // Try to import scipy + py::object scipy = py::module::import("scipy"); + return scipy.attr("__version__"); + +.. _calling_python_functions: + +Calling Python functions +======================== + +It is also possible to call Python classes, functions and methods +via ``operator()``. + +.. code-block:: cpp + + // Construct a Python object of class Decimal + py::object pi = Decimal("3.14159"); + +.. code-block:: cpp + + // Use Python to make our directories + py::object os = py::module::import("os"); + py::object makedirs = os.attr("makedirs"); + makedirs("/tmp/path/to/somewhere"); + +One can convert the result obtained from Python to a pure C++ version +if a ``py::class_`` or type conversion is defined. + +.. code-block:: cpp + + py::function f = <...>; + py::object result_py = f(1234, "hello", some_instance); + MyClass &result = result_py.cast(); + +.. _calling_python_methods: + +Calling Python methods +======================== + +To call an object's method, one can again use ``.attr`` to obtain access to the +Python method. + +.. code-block:: cpp + + // Calculate e^π in decimal + py::object exp_pi = pi.attr("exp")(); + py::print(py::str(exp_pi)); + +In the example above ``pi.attr("exp")`` is a *bound method*: it will always call +the method for that same instance of the class. Alternately one can create an +*unbound method* via the Python class (instead of instance) and pass the ``self`` +object explicitly, followed by other arguments. + +.. code-block:: cpp + + py::object decimal_exp = Decimal.attr("exp"); + + // Compute the e^n for n=0..4 + for (int n = 0; n < 5; n++) { + py::print(decimal_exp(Decimal(n)); + } + +Keyword arguments +================= + +Keyword arguments are also supported. In Python, there is the usual call syntax: + +.. code-block:: python + + def f(number, say, to): + ... # function code + + f(1234, say="hello", to=some_instance) # keyword call in Python + +In C++, the same call can be made using: + +.. code-block:: cpp + + using namespace pybind11::literals; // to bring in the `_a` literal + f(1234, "say"_a="hello", "to"_a=some_instance); // keyword call in C++ + +Unpacking arguments +=================== + +Unpacking of ``*args`` and ``**kwargs`` is also possible and can be mixed with +other arguments: + +.. code-block:: cpp + + // * unpacking + py::tuple args = py::make_tuple(1234, "hello", some_instance); + f(*args); + + // ** unpacking + py::dict kwargs = py::dict("number"_a=1234, "say"_a="hello", "to"_a=some_instance); + f(**kwargs); + + // mixed keywords, * and ** unpacking + py::tuple args = py::make_tuple(1234); + py::dict kwargs = py::dict("to"_a=some_instance); + f(*args, "say"_a="hello", **kwargs); + +Generalized unpacking according to PEP448_ is also supported: + +.. code-block:: cpp + + py::dict kwargs1 = py::dict("number"_a=1234); + py::dict kwargs2 = py::dict("to"_a=some_instance); + f(**kwargs1, "say"_a="hello", **kwargs2); + +.. seealso:: + + The file :file:`tests/test_pytypes.cpp` contains a complete + example that demonstrates passing native Python types in more detail. The + file :file:`tests/test_callbacks.cpp` presents a few examples of calling + Python functions from C++, including keywords arguments and unpacking. + +.. _PEP448: https://www.python.org/dev/peps/pep-0448/ diff --git a/wrap/python/pybind11/docs/advanced/pycpp/utilities.rst b/wrap/python/pybind11/docs/advanced/pycpp/utilities.rst new file mode 100644 index 000000000..369e7c94d --- /dev/null +++ b/wrap/python/pybind11/docs/advanced/pycpp/utilities.rst @@ -0,0 +1,144 @@ +Utilities +######### + +Using Python's print function in C++ +==================================== + +The usual way to write output in C++ is using ``std::cout`` while in Python one +would use ``print``. Since these methods use different buffers, mixing them can +lead to output order issues. To resolve this, pybind11 modules can use the +:func:`py::print` function which writes to Python's ``sys.stdout`` for consistency. + +Python's ``print`` function is replicated in the C++ API including optional +keyword arguments ``sep``, ``end``, ``file``, ``flush``. Everything works as +expected in Python: + +.. code-block:: cpp + + py::print(1, 2.0, "three"); // 1 2.0 three + py::print(1, 2.0, "three", "sep"_a="-"); // 1-2.0-three + + auto args = py::make_tuple("unpacked", true); + py::print("->", *args, "end"_a="<-"); // -> unpacked True <- + +.. _ostream_redirect: + +Capturing standard output from ostream +====================================== + +Often, a library will use the streams ``std::cout`` and ``std::cerr`` to print, +but this does not play well with Python's standard ``sys.stdout`` and ``sys.stderr`` +redirection. Replacing a library's printing with `py::print ` may not +be feasible. This can be fixed using a guard around the library function that +redirects output to the corresponding Python streams: + +.. code-block:: cpp + + #include + + ... + + // Add a scoped redirect for your noisy code + m.def("noisy_func", []() { + py::scoped_ostream_redirect stream( + std::cout, // std::ostream& + py::module::import("sys").attr("stdout") // Python output + ); + call_noisy_func(); + }); + +This method respects flushes on the output streams and will flush if needed +when the scoped guard is destroyed. This allows the output to be redirected in +real time, such as to a Jupyter notebook. The two arguments, the C++ stream and +the Python output, are optional, and default to standard output if not given. An +extra type, `py::scoped_estream_redirect `, is identical +except for defaulting to ``std::cerr`` and ``sys.stderr``; this can be useful with +`py::call_guard`, which allows multiple items, but uses the default constructor: + +.. code-block:: py + + // Alternative: Call single function using call guard + m.def("noisy_func", &call_noisy_function, + py::call_guard()); + +The redirection can also be done in Python with the addition of a context +manager, using the `py::add_ostream_redirect() ` function: + +.. code-block:: cpp + + py::add_ostream_redirect(m, "ostream_redirect"); + +The name in Python defaults to ``ostream_redirect`` if no name is passed. This +creates the following context manager in Python: + +.. code-block:: python + + with ostream_redirect(stdout=True, stderr=True): + noisy_function() + +It defaults to redirecting both streams, though you can use the keyword +arguments to disable one of the streams if needed. + +.. note:: + + The above methods will not redirect C-level output to file descriptors, such + as ``fprintf``. For those cases, you'll need to redirect the file + descriptors either directly in C or with Python's ``os.dup2`` function + in an operating-system dependent way. + +.. _eval: + +Evaluating Python expressions from strings and files +==================================================== + +pybind11 provides the `eval`, `exec` and `eval_file` functions to evaluate +Python expressions and statements. The following example illustrates how they +can be used. + +.. code-block:: cpp + + // At beginning of file + #include + + ... + + // Evaluate in scope of main module + py::object scope = py::module::import("__main__").attr("__dict__"); + + // Evaluate an isolated expression + int result = py::eval("my_variable + 10", scope).cast(); + + // Evaluate a sequence of statements + py::exec( + "print('Hello')\n" + "print('world!');", + scope); + + // Evaluate the statements in an separate Python file on disk + py::eval_file("script.py", scope); + +C++11 raw string literals are also supported and quite handy for this purpose. +The only requirement is that the first statement must be on a new line following +the raw string delimiter ``R"(``, ensuring all lines have common leading indent: + +.. code-block:: cpp + + py::exec(R"( + x = get_answer() + if x == 42: + print('Hello World!') + else: + print('Bye!') + )", scope + ); + +.. note:: + + `eval` and `eval_file` accept a template parameter that describes how the + string/file should be interpreted. Possible choices include ``eval_expr`` + (isolated expression), ``eval_single_statement`` (a single statement, return + value is always ``none``), and ``eval_statements`` (sequence of statements, + return value is always ``none``). `eval` defaults to ``eval_expr``, + `eval_file` defaults to ``eval_statements`` and `exec` is just a shortcut + for ``eval``. diff --git a/wrap/python/pybind11/docs/advanced/smart_ptrs.rst b/wrap/python/pybind11/docs/advanced/smart_ptrs.rst new file mode 100644 index 000000000..da57748ca --- /dev/null +++ b/wrap/python/pybind11/docs/advanced/smart_ptrs.rst @@ -0,0 +1,173 @@ +Smart pointers +############## + +std::unique_ptr +=============== + +Given a class ``Example`` with Python bindings, it's possible to return +instances wrapped in C++11 unique pointers, like so + +.. code-block:: cpp + + std::unique_ptr create_example() { return std::unique_ptr(new Example()); } + +.. code-block:: cpp + + m.def("create_example", &create_example); + +In other words, there is nothing special that needs to be done. While returning +unique pointers in this way is allowed, it is *illegal* to use them as function +arguments. For instance, the following function signature cannot be processed +by pybind11. + +.. code-block:: cpp + + void do_something_with_example(std::unique_ptr ex) { ... } + +The above signature would imply that Python needs to give up ownership of an +object that is passed to this function, which is generally not possible (for +instance, the object might be referenced elsewhere). + +std::shared_ptr +=============== + +The binding generator for classes, :class:`class_`, can be passed a template +type that denotes a special *holder* type that is used to manage references to +the object. If no such holder type template argument is given, the default for +a type named ``Type`` is ``std::unique_ptr``, which means that the object +is deallocated when Python's reference count goes to zero. + +It is possible to switch to other types of reference counting wrappers or smart +pointers, which is useful in codebases that rely on them. For instance, the +following snippet causes ``std::shared_ptr`` to be used instead. + +.. code-block:: cpp + + py::class_ /* <- holder type */> obj(m, "Example"); + +Note that any particular class can only be associated with a single holder type. + +One potential stumbling block when using holder types is that they need to be +applied consistently. Can you guess what's broken about the following binding +code? + +.. code-block:: cpp + + class Child { }; + + class Parent { + public: + Parent() : child(std::make_shared()) { } + Child *get_child() { return child.get(); } /* Hint: ** DON'T DO THIS ** */ + private: + std::shared_ptr child; + }; + + PYBIND11_MODULE(example, m) { + py::class_>(m, "Child"); + + py::class_>(m, "Parent") + .def(py::init<>()) + .def("get_child", &Parent::get_child); + } + +The following Python code will cause undefined behavior (and likely a +segmentation fault). + +.. code-block:: python + + from example import Parent + print(Parent().get_child()) + +The problem is that ``Parent::get_child()`` returns a pointer to an instance of +``Child``, but the fact that this instance is already managed by +``std::shared_ptr<...>`` is lost when passing raw pointers. In this case, +pybind11 will create a second independent ``std::shared_ptr<...>`` that also +claims ownership of the pointer. In the end, the object will be freed **twice** +since these shared pointers have no way of knowing about each other. + +There are two ways to resolve this issue: + +1. For types that are managed by a smart pointer class, never use raw pointers + in function arguments or return values. In other words: always consistently + wrap pointers into their designated holder types (such as + ``std::shared_ptr<...>``). In this case, the signature of ``get_child()`` + should be modified as follows: + +.. code-block:: cpp + + std::shared_ptr get_child() { return child; } + +2. Adjust the definition of ``Child`` by specifying + ``std::enable_shared_from_this`` (see cppreference_ for details) as a + base class. This adds a small bit of information to ``Child`` that allows + pybind11 to realize that there is already an existing + ``std::shared_ptr<...>`` and communicate with it. In this case, the + declaration of ``Child`` should look as follows: + +.. _cppreference: http://en.cppreference.com/w/cpp/memory/enable_shared_from_this + +.. code-block:: cpp + + class Child : public std::enable_shared_from_this { }; + +.. _smart_pointers: + +Custom smart pointers +===================== + +pybind11 supports ``std::unique_ptr`` and ``std::shared_ptr`` right out of the +box. For any other custom smart pointer, transparent conversions can be enabled +using a macro invocation similar to the following. It must be declared at the +top namespace level before any binding code: + +.. code-block:: cpp + + PYBIND11_DECLARE_HOLDER_TYPE(T, SmartPtr); + +The first argument of :func:`PYBIND11_DECLARE_HOLDER_TYPE` should be a +placeholder name that is used as a template parameter of the second argument. +Thus, feel free to use any identifier, but use it consistently on both sides; +also, don't use the name of a type that already exists in your codebase. + +The macro also accepts a third optional boolean parameter that is set to false +by default. Specify + +.. code-block:: cpp + + PYBIND11_DECLARE_HOLDER_TYPE(T, SmartPtr, true); + +if ``SmartPtr`` can always be initialized from a ``T*`` pointer without the +risk of inconsistencies (such as multiple independent ``SmartPtr`` instances +believing that they are the sole owner of the ``T*`` pointer). A common +situation where ``true`` should be passed is when the ``T`` instances use +*intrusive* reference counting. + +Please take a look at the :ref:`macro_notes` before using this feature. + +By default, pybind11 assumes that your custom smart pointer has a standard +interface, i.e. provides a ``.get()`` member function to access the underlying +raw pointer. If this is not the case, pybind11's ``holder_helper`` must be +specialized: + +.. code-block:: cpp + + // Always needed for custom holder types + PYBIND11_DECLARE_HOLDER_TYPE(T, SmartPtr); + + // Only needed if the type's `.get()` goes by another name + namespace pybind11 { namespace detail { + template + struct holder_helper> { // <-- specialization + static const T *get(const SmartPtr &p) { return p.getPointer(); } + }; + }} + +The above specialization informs pybind11 that the custom ``SmartPtr`` class +provides ``.get()`` functionality via ``.getPointer()``. + +.. seealso:: + + The file :file:`tests/test_smart_ptr.cpp` contains a complete example + that demonstrates how to work with custom reference-counting holder types + in more detail. diff --git a/wrap/python/pybind11/docs/basics.rst b/wrap/python/pybind11/docs/basics.rst new file mode 100644 index 000000000..447250ed9 --- /dev/null +++ b/wrap/python/pybind11/docs/basics.rst @@ -0,0 +1,293 @@ +.. _basics: + +First steps +########### + +This sections demonstrates the basic features of pybind11. Before getting +started, make sure that development environment is set up to compile the +included set of test cases. + + +Compiling the test cases +======================== + +Linux/MacOS +----------- + +On Linux you'll need to install the **python-dev** or **python3-dev** packages as +well as **cmake**. On Mac OS, the included python version works out of the box, +but **cmake** must still be installed. + +After installing the prerequisites, run + +.. code-block:: bash + + mkdir build + cd build + cmake .. + make check -j 4 + +The last line will both compile and run the tests. + +Windows +------- + +On Windows, only **Visual Studio 2015** and newer are supported since pybind11 relies +on various C++11 language features that break older versions of Visual Studio. + +To compile and run the tests: + +.. code-block:: batch + + mkdir build + cd build + cmake .. + cmake --build . --config Release --target check + +This will create a Visual Studio project, compile and run the target, all from the +command line. + +.. Note:: + + If all tests fail, make sure that the Python binary and the testcases are compiled + for the same processor type and bitness (i.e. either **i386** or **x86_64**). You + can specify **x86_64** as the target architecture for the generated Visual Studio + project using ``cmake -A x64 ..``. + +.. seealso:: + + Advanced users who are already familiar with Boost.Python may want to skip + the tutorial and look at the test cases in the :file:`tests` directory, + which exercise all features of pybind11. + +Header and namespace conventions +================================ + +For brevity, all code examples assume that the following two lines are present: + +.. code-block:: cpp + + #include + + namespace py = pybind11; + +Some features may require additional headers, but those will be specified as needed. + +.. _simple_example: + +Creating bindings for a simple function +======================================= + +Let's start by creating Python bindings for an extremely simple function, which +adds two numbers and returns their result: + +.. code-block:: cpp + + int add(int i, int j) { + return i + j; + } + +For simplicity [#f1]_, we'll put both this function and the binding code into +a file named :file:`example.cpp` with the following contents: + +.. code-block:: cpp + + #include + + int add(int i, int j) { + return i + j; + } + + PYBIND11_MODULE(example, m) { + m.doc() = "pybind11 example plugin"; // optional module docstring + + m.def("add", &add, "A function which adds two numbers"); + } + +.. [#f1] In practice, implementation and binding code will generally be located + in separate files. + +The :func:`PYBIND11_MODULE` macro creates a function that will be called when an +``import`` statement is issued from within Python. The module name (``example``) +is given as the first macro argument (it should not be in quotes). The second +argument (``m``) defines a variable of type :class:`py::module ` which +is the main interface for creating bindings. The method :func:`module::def` +generates binding code that exposes the ``add()`` function to Python. + +.. note:: + + Notice how little code was needed to expose our function to Python: all + details regarding the function's parameters and return value were + automatically inferred using template metaprogramming. This overall + approach and the used syntax are borrowed from Boost.Python, though the + underlying implementation is very different. + +pybind11 is a header-only library, hence it is not necessary to link against +any special libraries and there are no intermediate (magic) translation steps. +On Linux, the above example can be compiled using the following command: + +.. code-block:: bash + + $ c++ -O3 -Wall -shared -std=c++11 -fPIC `python3 -m pybind11 --includes` example.cpp -o example`python3-config --extension-suffix` + +For more details on the required compiler flags on Linux and MacOS, see +:ref:`building_manually`. For complete cross-platform compilation instructions, +refer to the :ref:`compiling` page. + +The `python_example`_ and `cmake_example`_ repositories are also a good place +to start. They are both complete project examples with cross-platform build +systems. The only difference between the two is that `python_example`_ uses +Python's ``setuptools`` to build the module, while `cmake_example`_ uses CMake +(which may be preferable for existing C++ projects). + +.. _python_example: https://github.com/pybind/python_example +.. _cmake_example: https://github.com/pybind/cmake_example + +Building the above C++ code will produce a binary module file that can be +imported to Python. Assuming that the compiled module is located in the +current directory, the following interactive Python session shows how to +load and execute the example: + +.. code-block:: pycon + + $ python + Python 2.7.10 (default, Aug 22 2015, 20:33:39) + [GCC 4.2.1 Compatible Apple LLVM 7.0.0 (clang-700.0.59.1)] on darwin + Type "help", "copyright", "credits" or "license" for more information. + >>> import example + >>> example.add(1, 2) + 3L + >>> + +.. _keyword_args: + +Keyword arguments +================= + +With a simple modification code, it is possible to inform Python about the +names of the arguments ("i" and "j" in this case). + +.. code-block:: cpp + + m.def("add", &add, "A function which adds two numbers", + py::arg("i"), py::arg("j")); + +:class:`arg` is one of several special tag classes which can be used to pass +metadata into :func:`module::def`. With this modified binding code, we can now +call the function using keyword arguments, which is a more readable alternative +particularly for functions taking many parameters: + +.. code-block:: pycon + + >>> import example + >>> example.add(i=1, j=2) + 3L + +The keyword names also appear in the function signatures within the documentation. + +.. code-block:: pycon + + >>> help(example) + + .... + + FUNCTIONS + add(...) + Signature : (i: int, j: int) -> int + + A function which adds two numbers + +A shorter notation for named arguments is also available: + +.. code-block:: cpp + + // regular notation + m.def("add1", &add, py::arg("i"), py::arg("j")); + // shorthand + using namespace pybind11::literals; + m.def("add2", &add, "i"_a, "j"_a); + +The :var:`_a` suffix forms a C++11 literal which is equivalent to :class:`arg`. +Note that the literal operator must first be made visible with the directive +``using namespace pybind11::literals``. This does not bring in anything else +from the ``pybind11`` namespace except for literals. + +.. _default_args: + +Default arguments +================= + +Suppose now that the function to be bound has default arguments, e.g.: + +.. code-block:: cpp + + int add(int i = 1, int j = 2) { + return i + j; + } + +Unfortunately, pybind11 cannot automatically extract these parameters, since they +are not part of the function's type information. However, they are simple to specify +using an extension of :class:`arg`: + +.. code-block:: cpp + + m.def("add", &add, "A function which adds two numbers", + py::arg("i") = 1, py::arg("j") = 2); + +The default values also appear within the documentation. + +.. code-block:: pycon + + >>> help(example) + + .... + + FUNCTIONS + add(...) + Signature : (i: int = 1, j: int = 2) -> int + + A function which adds two numbers + +The shorthand notation is also available for default arguments: + +.. code-block:: cpp + + // regular notation + m.def("add1", &add, py::arg("i") = 1, py::arg("j") = 2); + // shorthand + m.def("add2", &add, "i"_a=1, "j"_a=2); + +Exporting variables +=================== + +To expose a value from C++, use the ``attr`` function to register it in a +module as shown below. Built-in types and general objects (more on that later) +are automatically converted when assigned as attributes, and can be explicitly +converted using the function ``py::cast``. + +.. code-block:: cpp + + PYBIND11_MODULE(example, m) { + m.attr("the_answer") = 42; + py::object world = py::cast("World"); + m.attr("what") = world; + } + +These are then accessible from Python: + +.. code-block:: pycon + + >>> import example + >>> example.the_answer + 42 + >>> example.what + 'World' + +.. _supported_types: + +Supported data types +==================== + +A large number of data types are supported out of the box and can be used +seamlessly as functions arguments, return values or with ``py::cast`` in general. +For a full overview, see the :doc:`advanced/cast/index` section. diff --git a/wrap/python/pybind11/docs/benchmark.py b/wrap/python/pybind11/docs/benchmark.py new file mode 100644 index 000000000..6dc0604ea --- /dev/null +++ b/wrap/python/pybind11/docs/benchmark.py @@ -0,0 +1,88 @@ +import random +import os +import time +import datetime as dt + +nfns = 4 # Functions per class +nargs = 4 # Arguments per function + + +def generate_dummy_code_pybind11(nclasses=10): + decl = "" + bindings = "" + + for cl in range(nclasses): + decl += "class cl%03i;\n" % cl + decl += '\n' + + for cl in range(nclasses): + decl += "class cl%03i {\n" % cl + decl += "public:\n" + bindings += ' py::class_(m, "cl%03i")\n' % (cl, cl) + for fn in range(nfns): + ret = random.randint(0, nclasses - 1) + params = [random.randint(0, nclasses - 1) for i in range(nargs)] + decl += " cl%03i *fn_%03i(" % (ret, fn) + decl += ", ".join("cl%03i *" % p for p in params) + decl += ");\n" + bindings += ' .def("fn_%03i", &cl%03i::fn_%03i)\n' % \ + (fn, cl, fn) + decl += "};\n\n" + bindings += ' ;\n' + + result = "#include \n\n" + result += "namespace py = pybind11;\n\n" + result += decl + '\n' + result += "PYBIND11_MODULE(example, m) {\n" + result += bindings + result += "}" + return result + + +def generate_dummy_code_boost(nclasses=10): + decl = "" + bindings = "" + + for cl in range(nclasses): + decl += "class cl%03i;\n" % cl + decl += '\n' + + for cl in range(nclasses): + decl += "class cl%03i {\n" % cl + decl += "public:\n" + bindings += ' py::class_("cl%03i")\n' % (cl, cl) + for fn in range(nfns): + ret = random.randint(0, nclasses - 1) + params = [random.randint(0, nclasses - 1) for i in range(nargs)] + decl += " cl%03i *fn_%03i(" % (ret, fn) + decl += ", ".join("cl%03i *" % p for p in params) + decl += ");\n" + bindings += ' .def("fn_%03i", &cl%03i::fn_%03i, py::return_value_policy())\n' % \ + (fn, cl, fn) + decl += "};\n\n" + bindings += ' ;\n' + + result = "#include \n\n" + result += "namespace py = boost::python;\n\n" + result += decl + '\n' + result += "BOOST_PYTHON_MODULE(example) {\n" + result += bindings + result += "}" + return result + + +for codegen in [generate_dummy_code_pybind11, generate_dummy_code_boost]: + print ("{") + for i in range(0, 10): + nclasses = 2 ** i + with open("test.cpp", "w") as f: + f.write(codegen(nclasses)) + n1 = dt.datetime.now() + os.system("g++ -Os -shared -rdynamic -undefined dynamic_lookup " + "-fvisibility=hidden -std=c++14 test.cpp -I include " + "-I /System/Library/Frameworks/Python.framework/Headers -o test.so") + n2 = dt.datetime.now() + elapsed = (n2 - n1).total_seconds() + size = os.stat('test.so').st_size + print(" {%i, %f, %i}," % (nclasses * nfns, elapsed, size)) + print ("}") diff --git a/wrap/python/pybind11/docs/benchmark.rst b/wrap/python/pybind11/docs/benchmark.rst new file mode 100644 index 000000000..59d533df9 --- /dev/null +++ b/wrap/python/pybind11/docs/benchmark.rst @@ -0,0 +1,97 @@ +Benchmark +========= + +The following is the result of a synthetic benchmark comparing both compilation +time and module size of pybind11 against Boost.Python. A detailed report about a +Boost.Python to pybind11 conversion of a real project is available here: [#f1]_. + +.. [#f1] http://graylab.jhu.edu/RosettaCon2016/PyRosetta-4.pdf + +Setup +----- + +A python script (see the ``docs/benchmark.py`` file) was used to generate a set +of files with dummy classes whose count increases for each successive benchmark +(between 1 and 2048 classes in powers of two). Each class has four methods with +a randomly generated signature with a return value and four arguments. (There +was no particular reason for this setup other than the desire to generate many +unique function signatures whose count could be controlled in a simple way.) + +Here is an example of the binding code for one class: + +.. code-block:: cpp + + ... + class cl034 { + public: + cl279 *fn_000(cl084 *, cl057 *, cl065 *, cl042 *); + cl025 *fn_001(cl098 *, cl262 *, cl414 *, cl121 *); + cl085 *fn_002(cl445 *, cl297 *, cl145 *, cl421 *); + cl470 *fn_003(cl200 *, cl323 *, cl332 *, cl492 *); + }; + ... + + PYBIND11_MODULE(example, m) { + ... + py::class_(m, "cl034") + .def("fn_000", &cl034::fn_000) + .def("fn_001", &cl034::fn_001) + .def("fn_002", &cl034::fn_002) + .def("fn_003", &cl034::fn_003) + ... + } + +The Boost.Python version looks almost identical except that a return value +policy had to be specified as an argument to ``def()``. For both libraries, +compilation was done with + +.. code-block:: bash + + Apple LLVM version 7.0.2 (clang-700.1.81) + +and the following compilation flags + +.. code-block:: bash + + g++ -Os -shared -rdynamic -undefined dynamic_lookup -fvisibility=hidden -std=c++14 + +Compilation time +---------------- + +The following log-log plot shows how the compilation time grows for an +increasing number of class and function declarations. pybind11 includes many +fewer headers, which initially leads to shorter compilation times, but the +performance is ultimately fairly similar (pybind11 is 19.8 seconds faster for +the largest largest file with 2048 classes and a total of 8192 methods -- a +modest **1.2x** speedup relative to Boost.Python, which required 116.35 +seconds). + +.. only:: not latex + + .. image:: pybind11_vs_boost_python1.svg + +.. only:: latex + + .. image:: pybind11_vs_boost_python1.png + +Module size +----------- + +Differences between the two libraries become much more pronounced when +considering the file size of the generated Python plugin: for the largest file, +the binary generated by Boost.Python required 16.8 MiB, which was **2.17 +times** / **9.1 megabytes** larger than the output generated by pybind11. For +very small inputs, Boost.Python has an edge in the plot below -- however, note +that it stores many definitions in an external library, whose size was not +included here, hence the comparison is slightly shifted in Boost.Python's +favor. + +.. only:: not latex + + .. image:: pybind11_vs_boost_python2.svg + +.. only:: latex + + .. image:: pybind11_vs_boost_python2.png + + diff --git a/wrap/python/pybind11/docs/changelog.rst b/wrap/python/pybind11/docs/changelog.rst new file mode 100644 index 000000000..f99d3516a --- /dev/null +++ b/wrap/python/pybind11/docs/changelog.rst @@ -0,0 +1,1158 @@ +.. _changelog: + +Changelog +######### + +Starting with version 1.8.0, pybind11 releases use a `semantic versioning +`_ policy. + + +v2.3.1 (Not yet released) +----------------------------------------------------- + +* TBA + +v2.3.0 (June 11, 2019) +----------------------------------------------------- + +* Significantly reduced module binary size (10-20%) when compiled in C++11 mode + with GCC/Clang, or in any mode with MSVC. Function signatures are now always + precomputed at compile time (this was previously only available in C++14 mode + for non-MSVC compilers). + `#934 `_. + +* Add basic support for tag-based static polymorphism, where classes + provide a method to returns the desired type of an instance. + `#1326 `_. + +* Python type wrappers (``py::handle``, ``py::object``, etc.) + now support map Python's number protocol onto C++ arithmetic + operators such as ``operator+``, ``operator/=``, etc. + `#1511 `_. + +* A number of improvements related to enumerations: + + 1. The ``enum_`` implementation was rewritten from scratch to reduce + code bloat. Rather than instantiating a full implementation for each + enumeration, most code is now contained in a generic base class. + `#1511 `_. + + 2. The ``value()`` method of ``py::enum_`` now accepts an optional + docstring that will be shown in the documentation of the associated + enumeration. `#1160 `_. + + 3. check for already existing enum value and throw an error if present. + `#1453 `_. + +* Support for over-aligned type allocation via C++17's aligned ``new`` + statement. `#1582 `_. + +* Added ``py::ellipsis()`` method for slicing of multidimensional NumPy arrays + `#1502 `_. + +* Numerous Improvements to the ``mkdoc.py`` script for extracting documentation + from C++ header files. + `#1788 `_. + +* ``pybind11_add_module()``: allow including Python as a ``SYSTEM`` include path. + `#1416 `_. + +* ``pybind11/stl.h`` does not convert strings to ``vector`` anymore. + `#1258 `_. + +* Mark static methods as such to fix auto-generated Sphinx documentation. + `#1732 `_. + +* Re-throw forced unwind exceptions (e.g. during pthread termination). + `#1208 `_. + +* Added ``__contains__`` method to the bindings of maps (``std::map``, + ``std::unordered_map``). + `#1767 `_. + +* Improvements to ``gil_scoped_acquire``. + `#1211 `_. + +* Type caster support for ``std::deque``. + `#1609 `_. + +* Support for ``std::unique_ptr`` holders, whose deleters differ between a base and derived + class. `#1353 `_. + +* Construction of STL array/vector-like data structures from + iterators. Added an ``extend()`` operation. + `#1709 `_, + +* CMake build system improvements for projects that include non-C++ + files (e.g. plain C, CUDA) in ``pybind11_add_module`` et al. + `#1678 `_. + +* Fixed asynchronous invocation and deallocation of Python functions + wrapped in ``std::function``. + `#1595 `_. + +* Fixes regarding return value policy propagation in STL type casters. + `#1603 `_. + +* Fixed scoped enum comparisons. + `#1571 `_. + +* Fixed iostream redirection for code that releases the GIL. + `#1368 `_, + +* A number of CI-related fixes. + `#1757 `_, + `#1744 `_, + `#1670 `_. + + +v2.2.4 (September 11, 2018) +----------------------------------------------------- + +* Use new Python 3.7 Thread Specific Storage (TSS) implementation if available. + `#1454 `_, + `#1517 `_. + +* Fixes for newer MSVC versions and C++17 mode. + `#1347 `_, + `#1462 `_. + +* Propagate return value policies to type-specific casters + when casting STL containers. + `#1455 `_. + +* Allow ostream-redirection of more than 1024 characters. + `#1479 `_. + +* Set ``Py_DEBUG`` define when compiling against a debug Python build. + `#1438 `_. + +* Untangle integer logic in number type caster to work for custom + types that may only be castable to a restricted set of builtin types. + `#1442 `_. + +* CMake build system: Remember Python version in cache file. + `#1434 `_. + +* Fix for custom smart pointers: use ``std::addressof`` to obtain holder + address instead of ``operator&``. + `#1435 `_. + +* Properly report exceptions thrown during module initialization. + `#1362 `_. + +* Fixed a segmentation fault when creating empty-shaped NumPy array. + `#1371 `_. + +* The version of Intel C++ compiler must be >= 2017, and this is now checked by + the header files. `#1363 `_. + +* A few minor typo fixes and improvements to the test suite, and + patches that silence compiler warnings. + +* Vectors now support construction from generators, as well as ``extend()`` from a + list or generator. + `#1496 `_. + + +v2.2.3 (April 29, 2018) +----------------------------------------------------- + +* The pybind11 header location detection was replaced by a new implementation + that no longer depends on ``pip`` internals (the recently released ``pip`` + 10 has restricted access to this API). + `#1190 `_. + +* Small adjustment to an implementation detail to work around a compiler segmentation fault in Clang 3.3/3.4. + `#1350 `_. + +* The minimal supported version of the Intel compiler was >= 17.0 since + pybind11 v2.1. This check is now explicit, and a compile-time error is raised + if the compiler meet the requirement. + `#1363 `_. + +* Fixed an endianness-related fault in the test suite. + `#1287 `_. + +v2.2.2 (February 7, 2018) +----------------------------------------------------- + +* Fixed a segfault when combining embedded interpreter + shutdown/reinitialization with external loaded pybind11 modules. + `#1092 `_. + +* Eigen support: fixed a bug where Nx1/1xN numpy inputs couldn't be passed as + arguments to Eigen vectors (which for Eigen are simply compile-time fixed + Nx1/1xN matrices). + `#1106 `_. + +* Clarified to license by moving the licensing of contributions from + ``LICENSE`` into ``CONTRIBUTING.md``: the licensing of contributions is not + actually part of the software license as distributed. This isn't meant to be + a substantial change in the licensing of the project, but addresses concerns + that the clause made the license non-standard. + `#1109 `_. + +* Fixed a regression introduced in 2.1 that broke binding functions with lvalue + character literal arguments. + `#1128 `_. + +* MSVC: fix for compilation failures under /permissive-, and added the flag to + the appveyor test suite. + `#1155 `_. + +* Fixed ``__qualname__`` generation, and in turn, fixes how class names + (especially nested class names) are shown in generated docstrings. + `#1171 `_. + +* Updated the FAQ with a suggested project citation reference. + `#1189 `_. + +* Added fixes for deprecation warnings when compiled under C++17 with + ``-Wdeprecated`` turned on, and add ``-Wdeprecated`` to the test suite + compilation flags. + `#1191 `_. + +* Fixed outdated PyPI URLs in ``setup.py``. + `#1213 `_. + +* Fixed a refcount leak for arguments that end up in a ``py::args`` argument + for functions with both fixed positional and ``py::args`` arguments. + `#1216 `_. + +* Fixed a potential segfault resulting from possible premature destruction of + ``py::args``/``py::kwargs`` arguments with overloaded functions. + `#1223 `_. + +* Fixed ``del map[item]`` for a ``stl_bind.h`` bound stl map. + `#1229 `_. + +* Fixed a regression from v2.1.x where the aggregate initialization could + unintentionally end up at a constructor taking a templated + ``std::initializer_list`` argument. + `#1249 `_. + +* Fixed an issue where calling a function with a keep_alive policy on the same + nurse/patient pair would cause the internal patient storage to needlessly + grow (unboundedly, if the nurse is long-lived). + `#1251 `_. + +* Various other minor fixes. + +v2.2.1 (September 14, 2017) +----------------------------------------------------- + +* Added ``py::module::reload()`` member function for reloading a module. + `#1040 `_. + +* Fixed a reference leak in the number converter. + `#1078 `_. + +* Fixed compilation with Clang on host GCC < 5 (old libstdc++ which isn't fully + C++11 compliant). `#1062 `_. + +* Fixed a regression where the automatic ``std::vector`` caster would + fail to compile. The same fix also applies to any container which returns + element proxies instead of references. + `#1053 `_. + +* Fixed a regression where the ``py::keep_alive`` policy could not be applied + to constructors. `#1065 `_. + +* Fixed a nullptr dereference when loading a ``py::module_local`` type + that's only registered in an external module. + `#1058 `_. + +* Fixed implicit conversion of accessors to types derived from ``py::object``. + `#1076 `_. + +* The ``name`` in ``PYBIND11_MODULE(name, variable)`` can now be a macro. + `#1082 `_. + +* Relaxed overly strict ``py::pickle()`` check for matching get and set types. + `#1064 `_. + +* Conversion errors now try to be more informative when it's likely that + a missing header is the cause (e.g. forgetting ````). + `#1077 `_. + +v2.2.0 (August 31, 2017) +----------------------------------------------------- + +* Support for embedding the Python interpreter. See the + :doc:`documentation page ` for a + full overview of the new features. + `#774 `_, + `#889 `_, + `#892 `_, + `#920 `_. + + .. code-block:: cpp + + #include + namespace py = pybind11; + + int main() { + py::scoped_interpreter guard{}; // start the interpreter and keep it alive + + py::print("Hello, World!"); // use the Python API + } + +* Support for inheriting from multiple C++ bases in Python. + `#693 `_. + + .. code-block:: python + + from cpp_module import CppBase1, CppBase2 + + class PyDerived(CppBase1, CppBase2): + def __init__(self): + CppBase1.__init__(self) # C++ bases must be initialized explicitly + CppBase2.__init__(self) + +* ``PYBIND11_MODULE`` is now the preferred way to create module entry points. + ``PYBIND11_PLUGIN`` is deprecated. See :ref:`macros` for details. + `#879 `_. + + .. code-block:: cpp + + // new + PYBIND11_MODULE(example, m) { + m.def("add", [](int a, int b) { return a + b; }); + } + + // old + PYBIND11_PLUGIN(example) { + py::module m("example"); + m.def("add", [](int a, int b) { return a + b; }); + return m.ptr(); + } + +* pybind11's headers and build system now more strictly enforce hidden symbol + visibility for extension modules. This should be seamless for most users, + but see the :doc:`upgrade` if you use a custom build system. + `#995 `_. + +* Support for ``py::module_local`` types which allow multiple modules to + export the same C++ types without conflicts. This is useful for opaque + types like ``std::vector``. ``py::bind_vector`` and ``py::bind_map`` + now default to ``py::module_local`` if their elements are builtins or + local types. See :ref:`module_local` for details. + `#949 `_, + `#981 `_, + `#995 `_, + `#997 `_. + +* Custom constructors can now be added very easily using lambdas or factory + functions which return a class instance by value, pointer or holder. This + supersedes the old placement-new ``__init__`` technique. + See :ref:`custom_constructors` for details. + `#805 `_, + `#1014 `_. + + .. code-block:: cpp + + struct Example { + Example(std::string); + }; + + py::class_(m, "Example") + .def(py::init()) // existing constructor + .def(py::init([](int n) { // custom constructor + return std::make_unique(std::to_string(n)); + })); + +* Similarly to custom constructors, pickling support functions are now bound + using the ``py::pickle()`` adaptor which improves type safety. See the + :doc:`upgrade` and :ref:`pickling` for details. + `#1038 `_. + +* Builtin support for converting C++17 standard library types and general + conversion improvements: + + 1. C++17 ``std::variant`` is supported right out of the box. C++11/14 + equivalents (e.g. ``boost::variant``) can also be added with a simple + user-defined specialization. See :ref:`cpp17_container_casters` for details. + `#811 `_, + `#845 `_, + `#989 `_. + + 2. Out-of-the-box support for C++17 ``std::string_view``. + `#906 `_. + + 3. Improved compatibility of the builtin ``optional`` converter. + `#874 `_. + + 4. The ``bool`` converter now accepts ``numpy.bool_`` and types which + define ``__bool__`` (Python 3.x) or ``__nonzero__`` (Python 2.7). + `#925 `_. + + 5. C++-to-Python casters are now more efficient and move elements out + of rvalue containers whenever possible. + `#851 `_, + `#936 `_, + `#938 `_. + + 6. Fixed ``bytes`` to ``std::string/char*`` conversion on Python 3. + `#817 `_. + + 7. Fixed lifetime of temporary C++ objects created in Python-to-C++ conversions. + `#924 `_. + +* Scope guard call policy for RAII types, e.g. ``py::call_guard()``, + ``py::call_guard()``. See :ref:`call_policies` for details. + `#740 `_. + +* Utility for redirecting C++ streams to Python (e.g. ``std::cout`` -> + ``sys.stdout``). Scope guard ``py::scoped_ostream_redirect`` in C++ and + a context manager in Python. See :ref:`ostream_redirect`. + `#1009 `_. + +* Improved handling of types and exceptions across module boundaries. + `#915 `_, + `#951 `_, + `#995 `_. + +* Fixed destruction order of ``py::keep_alive`` nurse/patient objects + in reference cycles. + `#856 `_. + +* Numpy and buffer protocol related improvements: + + 1. Support for negative strides in Python buffer objects/numpy arrays. This + required changing integers from unsigned to signed for the related C++ APIs. + Note: If you have compiler warnings enabled, you may notice some new conversion + warnings after upgrading. These can be resolved with ``static_cast``. + `#782 `_. + + 2. Support ``std::complex`` and arrays inside ``PYBIND11_NUMPY_DTYPE``. + `#831 `_, + `#832 `_. + + 3. Support for constructing ``py::buffer_info`` and ``py::arrays`` using + arbitrary containers or iterators instead of requiring a ``std::vector``. + `#788 `_, + `#822 `_, + `#860 `_. + + 4. Explicitly check numpy version and require >= 1.7.0. + `#819 `_. + +* Support for allowing/prohibiting ``None`` for specific arguments and improved + ``None`` overload resolution order. See :ref:`none_arguments` for details. + `#843 `_. + `#859 `_. + +* Added ``py::exec()`` as a shortcut for ``py::eval()`` + and support for C++11 raw string literals as input. See :ref:`eval`. + `#766 `_, + `#827 `_. + +* ``py::vectorize()`` ignores non-vectorizable arguments and supports + member functions. + `#762 `_. + +* Support for bound methods as callbacks (``pybind11/functional.h``). + `#815 `_. + +* Allow aliasing pybind11 methods: ``cls.attr("foo") = cls.attr("bar")``. + `#802 `_. + +* Don't allow mixed static/non-static overloads. + `#804 `_. + +* Fixed overriding static properties in derived classes. + `#784 `_. + +* Added support for write only properties. + `#1144 `_. + +* Improved deduction of member functions of a derived class when its bases + aren't registered with pybind11. + `#855 `_. + + .. code-block:: cpp + + struct Base { + int foo() { return 42; } + } + + struct Derived : Base {} + + // Now works, but previously required also binding `Base` + py::class_(m, "Derived") + .def("foo", &Derived::foo); // function is actually from `Base` + +* The implementation of ``py::init<>`` now uses C++11 brace initialization + syntax to construct instances, which permits binding implicit constructors of + aggregate types. `#1015 `_. + + .. code-block:: cpp + + struct Aggregate { + int a; + std::string b; + }; + + py::class_(m, "Aggregate") + .def(py::init()); + +* Fixed issues with multiple inheritance with offset base/derived pointers. + `#812 `_, + `#866 `_, + `#960 `_. + +* Fixed reference leak of type objects. + `#1030 `_. + +* Improved support for the ``/std:c++14`` and ``/std:c++latest`` modes + on MSVC 2017. + `#841 `_, + `#999 `_. + +* Fixed detection of private operator new on MSVC. + `#893 `_, + `#918 `_. + +* Intel C++ compiler compatibility fixes. + `#937 `_. + +* Fixed implicit conversion of `py::enum_` to integer types on Python 2.7. + `#821 `_. + +* Added ``py::hash`` to fetch the hash value of Python objects, and + ``.def(hash(py::self))`` to provide the C++ ``std::hash`` as the Python + ``__hash__`` method. + `#1034 `_. + +* Fixed ``__truediv__`` on Python 2 and ``__itruediv__`` on Python 3. + `#867 `_. + +* ``py::capsule`` objects now support the ``name`` attribute. This is useful + for interfacing with ``scipy.LowLevelCallable``. + `#902 `_. + +* Fixed ``py::make_iterator``'s ``__next__()`` for past-the-end calls. + `#897 `_. + +* Added ``error_already_set::matches()`` for checking Python exceptions. + `#772 `_. + +* Deprecated ``py::error_already_set::clear()``. It's no longer needed + following a simplification of the ``py::error_already_set`` class. + `#954 `_. + +* Deprecated ``py::handle::operator==()`` in favor of ``py::handle::is()`` + `#825 `_. + +* Deprecated ``py::object::borrowed``/``py::object::stolen``. + Use ``py::object::borrowed_t{}``/``py::object::stolen_t{}`` instead. + `#771 `_. + +* Changed internal data structure versioning to avoid conflicts between + modules compiled with different revisions of pybind11. + `#1012 `_. + +* Additional compile-time and run-time error checking and more informative messages. + `#786 `_, + `#794 `_, + `#803 `_. + +* Various minor improvements and fixes. + `#764 `_, + `#791 `_, + `#795 `_, + `#840 `_, + `#844 `_, + `#846 `_, + `#849 `_, + `#858 `_, + `#862 `_, + `#871 `_, + `#872 `_, + `#881 `_, + `#888 `_, + `#899 `_, + `#928 `_, + `#931 `_, + `#944 `_, + `#950 `_, + `#952 `_, + `#962 `_, + `#965 `_, + `#970 `_, + `#978 `_, + `#979 `_, + `#986 `_, + `#1020 `_, + `#1027 `_, + `#1037 `_. + +* Testing improvements. + `#798 `_, + `#882 `_, + `#898 `_, + `#900 `_, + `#921 `_, + `#923 `_, + `#963 `_. + +v2.1.1 (April 7, 2017) +----------------------------------------------------- + +* Fixed minimum version requirement for MSVC 2015u3 + `#773 `_. + +v2.1.0 (March 22, 2017) +----------------------------------------------------- + +* pybind11 now performs function overload resolution in two phases. The first + phase only considers exact type matches, while the second allows for implicit + conversions to take place. A special ``noconvert()`` syntax can be used to + completely disable implicit conversions for specific arguments. + `#643 `_, + `#634 `_, + `#650 `_. + +* Fixed a regression where static properties no longer worked with classes + using multiple inheritance. The ``py::metaclass`` attribute is no longer + necessary (and deprecated as of this release) when binding classes with + static properties. + `#679 `_, + +* Classes bound using ``pybind11`` can now use custom metaclasses. + `#679 `_, + +* ``py::args`` and ``py::kwargs`` can now be mixed with other positional + arguments when binding functions using pybind11. + `#611 `_. + +* Improved support for C++11 unicode string and character types; added + extensive documentation regarding pybind11's string conversion behavior. + `#624 `_, + `#636 `_, + `#715 `_. + +* pybind11 can now avoid expensive copies when converting Eigen arrays to NumPy + arrays (and vice versa). `#610 `_. + +* The "fast path" in ``py::vectorize`` now works for any full-size group of C or + F-contiguous arrays. The non-fast path is also faster since it no longer performs + copies of the input arguments (except when type conversions are necessary). + `#610 `_. + +* Added fast, unchecked access to NumPy arrays via a proxy object. + `#746 `_. + +* Transparent support for class-specific ``operator new`` and + ``operator delete`` implementations. + `#755 `_. + +* Slimmer and more efficient STL-compatible iterator interface for sequence types. + `#662 `_. + +* Improved custom holder type support. + `#607 `_. + +* ``nullptr`` to ``None`` conversion fixed in various builtin type casters. + `#732 `_. + +* ``enum_`` now exposes its members via a special ``__members__`` attribute. + `#666 `_. + +* ``std::vector`` bindings created using ``stl_bind.h`` can now optionally + implement the buffer protocol. `#488 `_. + +* Automated C++ reference documentation using doxygen and breathe. + `#598 `_. + +* Added minimum compiler version assertions. + `#727 `_. + +* Improved compatibility with C++1z. + `#677 `_. + +* Improved ``py::capsule`` API. Can be used to implement cleanup + callbacks that are involved at module destruction time. + `#752 `_. + +* Various minor improvements and fixes. + `#595 `_, + `#588 `_, + `#589 `_, + `#603 `_, + `#619 `_, + `#648 `_, + `#695 `_, + `#720 `_, + `#723 `_, + `#729 `_, + `#724 `_, + `#742 `_, + `#753 `_. + +v2.0.1 (Jan 4, 2017) +----------------------------------------------------- + +* Fix pointer to reference error in type_caster on MSVC + `#583 `_. + +* Fixed a segmentation in the test suite due to a typo + `cd7eac `_. + +v2.0.0 (Jan 1, 2017) +----------------------------------------------------- + +* Fixed a reference counting regression affecting types with custom metaclasses + (introduced in v2.0.0-rc1). + `#571 `_. + +* Quenched a CMake policy warning. + `#570 `_. + +v2.0.0-rc1 (Dec 23, 2016) +----------------------------------------------------- + +The pybind11 developers are excited to issue a release candidate of pybind11 +with a subsequent v2.0.0 release planned in early January next year. + +An incredible amount of effort by went into pybind11 over the last ~5 months, +leading to a release that is jam-packed with exciting new features and numerous +usability improvements. The following list links PRs or individual commits +whenever applicable. + +Happy Christmas! + +* Support for binding C++ class hierarchies that make use of multiple + inheritance. `#410 `_. + +* PyPy support: pybind11 now supports nightly builds of PyPy and will + interoperate with the future 5.7 release. No code changes are necessary, + everything "just" works as usual. Note that we only target the Python 2.7 + branch for now; support for 3.x will be added once its ``cpyext`` extension + support catches up. A few minor features remain unsupported for the time + being (notably dynamic attributes in custom types). + `#527 `_. + +* Significant work on the documentation -- in particular, the monolithic + ``advanced.rst`` file was restructured into a easier to read hierarchical + organization. `#448 `_. + +* Many NumPy-related improvements: + + 1. Object-oriented API to access and modify NumPy ``ndarray`` instances, + replicating much of the corresponding NumPy C API functionality. + `#402 `_. + + 2. NumPy array ``dtype`` array descriptors are now first-class citizens and + are exposed via a new class ``py::dtype``. + + 3. Structured dtypes can be registered using the ``PYBIND11_NUMPY_DTYPE()`` + macro. Special ``array`` constructors accepting dtype objects were also + added. + + One potential caveat involving this change: format descriptor strings + should now be accessed via ``format_descriptor::format()`` (however, for + compatibility purposes, the old syntax ``format_descriptor::value`` will + still work for non-structured data types). `#308 + `_. + + 4. Further improvements to support structured dtypes throughout the system. + `#472 `_, + `#474 `_, + `#459 `_, + `#453 `_, + `#452 `_, and + `#505 `_. + + 5. Fast access operators. `#497 `_. + + 6. Constructors for arrays whose storage is owned by another object. + `#440 `_. + + 7. Added constructors for ``array`` and ``array_t`` explicitly accepting shape + and strides; if strides are not provided, they are deduced assuming + C-contiguity. Also added simplified constructors for 1-dimensional case. + + 8. Added buffer/NumPy support for ``char[N]`` and ``std::array`` types. + + 9. Added ``memoryview`` wrapper type which is constructible from ``buffer_info``. + +* Eigen: many additional conversions and support for non-contiguous + arrays/slices. + `#427 `_, + `#315 `_, + `#316 `_, + `#312 `_, and + `#267 `_ + +* Incompatible changes in ``class_<...>::class_()``: + + 1. Declarations of types that provide access via the buffer protocol must + now include the ``py::buffer_protocol()`` annotation as an argument to + the ``class_`` constructor. + + 2. Declarations of types that require a custom metaclass (i.e. all classes + which include static properties via commands such as + ``def_readwrite_static()``) must now include the ``py::metaclass()`` + annotation as an argument to the ``class_`` constructor. + + These two changes were necessary to make type definitions in pybind11 + future-proof, and to support PyPy via its cpyext mechanism. `#527 + `_. + + + 3. This version of pybind11 uses a redesigned mechanism for instantiating + trampoline classes that are used to override virtual methods from within + Python. This led to the following user-visible syntax change: instead of + + .. code-block:: cpp + + py::class_("MyClass") + .alias() + .... + + write + + .. code-block:: cpp + + py::class_("MyClass") + .... + + Importantly, both the original and the trampoline class are now + specified as an arguments (in arbitrary order) to the ``py::class_`` + template, and the ``alias<..>()`` call is gone. The new scheme has zero + overhead in cases when Python doesn't override any functions of the + underlying C++ class. `rev. 86d825 + `_. + +* Added ``eval`` and ``eval_file`` functions for evaluating expressions and + statements from a string or file. `rev. 0d3fc3 + `_. + +* pybind11 can now create types with a modifiable dictionary. + `#437 `_ and + `#444 `_. + +* Support for translation of arbitrary C++ exceptions to Python counterparts. + `#296 `_ and + `#273 `_. + +* Report full backtraces through mixed C++/Python code, better reporting for + import errors, fixed GIL management in exception processing. + `#537 `_, + `#494 `_, + `rev. e72d95 `_, and + `rev. 099d6e `_. + +* Support for bit-level operations, comparisons, and serialization of C++ + enumerations. `#503 `_, + `#508 `_, + `#380 `_, + `#309 `_. + `#311 `_. + +* The ``class_`` constructor now accepts its template arguments in any order. + `#385 `_. + +* Attribute and item accessors now have a more complete interface which makes + it possible to chain attributes as in + ``obj.attr("a")[key].attr("b").attr("method")(1, 2, 3)``. `#425 + `_. + +* Major redesign of the default and conversion constructors in ``pytypes.h``. + `#464 `_. + +* Added built-in support for ``std::shared_ptr`` holder type. It is no longer + necessary to to include a declaration of the form + ``PYBIND11_DECLARE_HOLDER_TYPE(T, std::shared_ptr)`` (though continuing to + do so won't cause an error). + `#454 `_. + +* New ``py::overload_cast`` casting operator to select among multiple possible + overloads of a function. An example: + + .. code-block:: cpp + + py::class_(m, "Pet") + .def("set", py::overload_cast(&Pet::set), "Set the pet's age") + .def("set", py::overload_cast(&Pet::set), "Set the pet's name"); + + This feature only works on C++14-capable compilers. + `#541 `_. + +* C++ types are automatically cast to Python types, e.g. when assigning + them as an attribute. For instance, the following is now legal: + + .. code-block:: cpp + + py::module m = /* ... */ + m.attr("constant") = 123; + + (Previously, a ``py::cast`` call was necessary to avoid a compilation error.) + `#551 `_. + +* Redesigned ``pytest``-based test suite. `#321 `_. + +* Instance tracking to detect reference leaks in test suite. `#324 `_ + +* pybind11 can now distinguish between multiple different instances that are + located at the same memory address, but which have different types. + `#329 `_. + +* Improved logic in ``move`` return value policy. + `#510 `_, + `#297 `_. + +* Generalized unpacking API to permit calling Python functions from C++ using + notation such as ``foo(a1, a2, *args, "ka"_a=1, "kb"_a=2, **kwargs)``. `#372 `_. + +* ``py::print()`` function whose behavior matches that of the native Python + ``print()`` function. `#372 `_. + +* Added ``py::dict`` keyword constructor:``auto d = dict("number"_a=42, + "name"_a="World");``. `#372 `_. + +* Added ``py::str::format()`` method and ``_s`` literal: ``py::str s = "1 + 2 + = {}"_s.format(3);``. `#372 `_. + +* Added ``py::repr()`` function which is equivalent to Python's builtin + ``repr()``. `#333 `_. + +* Improved construction and destruction logic for holder types. It is now + possible to reference instances with smart pointer holder types without + constructing the holder if desired. The ``PYBIND11_DECLARE_HOLDER_TYPE`` + macro now accepts an optional second parameter to indicate whether the holder + type uses intrusive reference counting. + `#533 `_ and + `#561 `_. + +* Mapping a stateless C++ function to Python and back is now "for free" (i.e. + no extra indirections or argument conversion overheads). `rev. 954b79 + `_. + +* Bindings for ``std::valarray``. + `#545 `_. + +* Improved support for C++17 capable compilers. + `#562 `_. + +* Bindings for ``std::optional``. + `#475 `_, + `#476 `_, + `#479 `_, + `#499 `_, and + `#501 `_. + +* ``stl_bind.h``: general improvements and support for ``std::map`` and + ``std::unordered_map``. + `#490 `_, + `#282 `_, + `#235 `_. + +* The ``std::tuple``, ``std::pair``, ``std::list``, and ``std::vector`` type + casters now accept any Python sequence type as input. `rev. 107285 + `_. + +* Improved CMake Python detection on multi-architecture Linux. + `#532 `_. + +* Infrastructure to selectively disable or enable parts of the automatically + generated docstrings. `#486 `_. + +* ``reference`` and ``reference_internal`` are now the default return value + properties for static and non-static properties, respectively. `#473 + `_. (the previous defaults + were ``automatic``). `#473 `_. + +* Support for ``std::unique_ptr`` with non-default deleters or no deleter at + all (``py::nodelete``). `#384 `_. + +* Deprecated ``handle::call()`` method. The new syntax to call Python + functions is simply ``handle()``. It can also be invoked explicitly via + ``handle::operator()``, where ``X`` is an optional return value policy. + +* Print more informative error messages when ``make_tuple()`` or ``cast()`` + fail. `#262 `_. + +* Creation of holder types for classes deriving from + ``std::enable_shared_from_this<>`` now also works for ``const`` values. + `#260 `_. + +* ``make_iterator()`` improvements for better compatibility with various + types (now uses prefix increment operator); it now also accepts iterators + with different begin/end types as long as they are equality comparable. + `#247 `_. + +* ``arg()`` now accepts a wider range of argument types for default values. + `#244 `_. + +* Support ``keep_alive`` where the nurse object may be ``None``. `#341 + `_. + +* Added constructors for ``str`` and ``bytes`` from zero-terminated char + pointers, and from char pointers and length. Added constructors for ``str`` + from ``bytes`` and for ``bytes`` from ``str``, which will perform UTF-8 + decoding/encoding as required. + +* Many other improvements of library internals without user-visible changes + + +1.8.1 (July 12, 2016) +---------------------- +* Fixed a rare but potentially very severe issue when the garbage collector ran + during pybind11 type creation. + +1.8.0 (June 14, 2016) +---------------------- +* Redesigned CMake build system which exports a convenient + ``pybind11_add_module`` function to parent projects. +* ``std::vector<>`` type bindings analogous to Boost.Python's ``indexing_suite`` +* Transparent conversion of sparse and dense Eigen matrices and vectors (``eigen.h``) +* Added an ``ExtraFlags`` template argument to the NumPy ``array_t<>`` wrapper + to disable an enforced cast that may lose precision, e.g. to create overloads + for different precisions and complex vs real-valued matrices. +* Prevent implicit conversion of floating point values to integral types in + function arguments +* Fixed incorrect default return value policy for functions returning a shared + pointer +* Don't allow registering a type via ``class_`` twice +* Don't allow casting a ``None`` value into a C++ lvalue reference +* Fixed a crash in ``enum_::operator==`` that was triggered by the ``help()`` command +* Improved detection of whether or not custom C++ types can be copy/move-constructed +* Extended ``str`` type to also work with ``bytes`` instances +* Added a ``"name"_a`` user defined string literal that is equivalent to ``py::arg("name")``. +* When specifying function arguments via ``py::arg``, the test that verifies + the number of arguments now runs at compile time. +* Added ``[[noreturn]]`` attribute to ``pybind11_fail()`` to quench some + compiler warnings +* List function arguments in exception text when the dispatch code cannot find + a matching overload +* Added ``PYBIND11_OVERLOAD_NAME`` and ``PYBIND11_OVERLOAD_PURE_NAME`` macros which + can be used to override virtual methods whose name differs in C++ and Python + (e.g. ``__call__`` and ``operator()``) +* Various minor ``iterator`` and ``make_iterator()`` improvements +* Transparently support ``__bool__`` on Python 2.x and Python 3.x +* Fixed issue with destructor of unpickled object not being called +* Minor CMake build system improvements on Windows +* New ``pybind11::args`` and ``pybind11::kwargs`` types to create functions which + take an arbitrary number of arguments and keyword arguments +* New syntax to call a Python function from C++ using ``*args`` and ``*kwargs`` +* The functions ``def_property_*`` now correctly process docstring arguments (these + formerly caused a segmentation fault) +* Many ``mkdoc.py`` improvements (enumerations, template arguments, ``DOC()`` + macro accepts more arguments) +* Cygwin support +* Documentation improvements (pickling support, ``keep_alive``, macro usage) + +1.7 (April 30, 2016) +---------------------- +* Added a new ``move`` return value policy that triggers C++11 move semantics. + The automatic return value policy falls back to this case whenever a rvalue + reference is encountered +* Significantly more general GIL state routines that are used instead of + Python's troublesome ``PyGILState_Ensure`` and ``PyGILState_Release`` API +* Redesign of opaque types that drastically simplifies their usage +* Extended ability to pass values of type ``[const] void *`` +* ``keep_alive`` fix: don't fail when there is no patient +* ``functional.h``: acquire the GIL before calling a Python function +* Added Python RAII type wrappers ``none`` and ``iterable`` +* Added ``*args`` and ``*kwargs`` pass-through parameters to + ``pybind11.get_include()`` function +* Iterator improvements and fixes +* Documentation on return value policies and opaque types improved + +1.6 (April 30, 2016) +---------------------- +* Skipped due to upload to PyPI gone wrong and inability to recover + (https://github.com/pypa/packaging-problems/issues/74) + +1.5 (April 21, 2016) +---------------------- +* For polymorphic types, use RTTI to try to return the closest type registered with pybind11 +* Pickling support for serializing and unserializing C++ instances to a byte stream in Python +* Added a convenience routine ``make_iterator()`` which turns a range indicated + by a pair of C++ iterators into a iterable Python object +* Added ``len()`` and a variadic ``make_tuple()`` function +* Addressed a rare issue that could confuse the current virtual function + dispatcher and another that could lead to crashes in multi-threaded + applications +* Added a ``get_include()`` function to the Python module that returns the path + of the directory containing the installed pybind11 header files +* Documentation improvements: import issues, symbol visibility, pickling, limitations +* Added casting support for ``std::reference_wrapper<>`` + +1.4 (April 7, 2016) +-------------------------- +* Transparent type conversion for ``std::wstring`` and ``wchar_t`` +* Allow passing ``nullptr``-valued strings +* Transparent passing of ``void *`` pointers using capsules +* Transparent support for returning values wrapped in ``std::unique_ptr<>`` +* Improved docstring generation for compatibility with Sphinx +* Nicer debug error message when default parameter construction fails +* Support for "opaque" types that bypass the transparent conversion layer for STL containers +* Redesigned type casting interface to avoid ambiguities that could occasionally cause compiler errors +* Redesigned property implementation; fixes crashes due to an unfortunate default return value policy +* Anaconda package generation support + +1.3 (March 8, 2016) +-------------------------- + +* Added support for the Intel C++ compiler (v15+) +* Added support for the STL unordered set/map data structures +* Added support for the STL linked list data structure +* NumPy-style broadcasting support in ``pybind11::vectorize`` +* pybind11 now displays more verbose error messages when ``arg::operator=()`` fails +* pybind11 internal data structures now live in a version-dependent namespace to avoid ABI issues +* Many, many bugfixes involving corner cases and advanced usage + +1.2 (February 7, 2016) +-------------------------- + +* Optional: efficient generation of function signatures at compile time using C++14 +* Switched to a simpler and more general way of dealing with function default + arguments. Unused keyword arguments in function calls are now detected and + cause errors as expected +* New ``keep_alive`` call policy analogous to Boost.Python's ``with_custodian_and_ward`` +* New ``pybind11::base<>`` attribute to indicate a subclass relationship +* Improved interface for RAII type wrappers in ``pytypes.h`` +* Use RAII type wrappers consistently within pybind11 itself. This + fixes various potential refcount leaks when exceptions occur +* Added new ``bytes`` RAII type wrapper (maps to ``string`` in Python 2.7) +* Made handle and related RAII classes const correct, using them more + consistently everywhere now +* Got rid of the ugly ``__pybind11__`` attributes on the Python side---they are + now stored in a C++ hash table that is not visible in Python +* Fixed refcount leaks involving NumPy arrays and bound functions +* Vastly improved handling of shared/smart pointers +* Removed an unnecessary copy operation in ``pybind11::vectorize`` +* Fixed naming clashes when both pybind11 and NumPy headers are included +* Added conversions for additional exception types +* Documentation improvements (using multiple extension modules, smart pointers, + other minor clarifications) +* unified infrastructure for parsing variadic arguments in ``class_`` and cpp_function +* Fixed license text (was: ZLIB, should have been: 3-clause BSD) +* Python 3.2 compatibility +* Fixed remaining issues when accessing types in another plugin module +* Added enum comparison and casting methods +* Improved SFINAE-based detection of whether types are copy-constructible +* Eliminated many warnings about unused variables and the use of ``offsetof()`` +* Support for ``std::array<>`` conversions + +1.1 (December 7, 2015) +-------------------------- + +* Documentation improvements (GIL, wrapping functions, casting, fixed many typos) +* Generalized conversion of integer types +* Improved support for casting function objects +* Improved support for ``std::shared_ptr<>`` conversions +* Initial support for ``std::set<>`` conversions +* Fixed type resolution issue for types defined in a separate plugin module +* Cmake build system improvements +* Factored out generic functionality to non-templated code (smaller code size) +* Added a code size / compile time benchmark vs Boost.Python +* Added an appveyor CI script + +1.0 (October 15, 2015) +------------------------ +* Initial release diff --git a/wrap/python/pybind11/docs/classes.rst b/wrap/python/pybind11/docs/classes.rst new file mode 100644 index 000000000..1deec9b53 --- /dev/null +++ b/wrap/python/pybind11/docs/classes.rst @@ -0,0 +1,521 @@ +.. _classes: + +Object-oriented code +#################### + +Creating bindings for a custom type +=================================== + +Let's now look at a more complex example where we'll create bindings for a +custom C++ data structure named ``Pet``. Its definition is given below: + +.. code-block:: cpp + + struct Pet { + Pet(const std::string &name) : name(name) { } + void setName(const std::string &name_) { name = name_; } + const std::string &getName() const { return name; } + + std::string name; + }; + +The binding code for ``Pet`` looks as follows: + +.. code-block:: cpp + + #include + + namespace py = pybind11; + + PYBIND11_MODULE(example, m) { + py::class_(m, "Pet") + .def(py::init()) + .def("setName", &Pet::setName) + .def("getName", &Pet::getName); + } + +:class:`class_` creates bindings for a C++ *class* or *struct*-style data +structure. :func:`init` is a convenience function that takes the types of a +constructor's parameters as template arguments and wraps the corresponding +constructor (see the :ref:`custom_constructors` section for details). An +interactive Python session demonstrating this example is shown below: + +.. code-block:: pycon + + % python + >>> import example + >>> p = example.Pet('Molly') + >>> print(p) + + >>> p.getName() + u'Molly' + >>> p.setName('Charly') + >>> p.getName() + u'Charly' + +.. seealso:: + + Static member functions can be bound in the same way using + :func:`class_::def_static`. + +Keyword and default arguments +============================= +It is possible to specify keyword and default arguments using the syntax +discussed in the previous chapter. Refer to the sections :ref:`keyword_args` +and :ref:`default_args` for details. + +Binding lambda functions +======================== + +Note how ``print(p)`` produced a rather useless summary of our data structure in the example above: + +.. code-block:: pycon + + >>> print(p) + + +To address this, we could bind an utility function that returns a human-readable +summary to the special method slot named ``__repr__``. Unfortunately, there is no +suitable functionality in the ``Pet`` data structure, and it would be nice if +we did not have to change it. This can easily be accomplished by binding a +Lambda function instead: + +.. code-block:: cpp + + py::class_(m, "Pet") + .def(py::init()) + .def("setName", &Pet::setName) + .def("getName", &Pet::getName) + .def("__repr__", + [](const Pet &a) { + return ""; + } + ); + +Both stateless [#f1]_ and stateful lambda closures are supported by pybind11. +With the above change, the same Python code now produces the following output: + +.. code-block:: pycon + + >>> print(p) + + +.. [#f1] Stateless closures are those with an empty pair of brackets ``[]`` as the capture object. + +.. _properties: + +Instance and static fields +========================== + +We can also directly expose the ``name`` field using the +:func:`class_::def_readwrite` method. A similar :func:`class_::def_readonly` +method also exists for ``const`` fields. + +.. code-block:: cpp + + py::class_(m, "Pet") + .def(py::init()) + .def_readwrite("name", &Pet::name) + // ... remainder ... + +This makes it possible to write + +.. code-block:: pycon + + >>> p = example.Pet('Molly') + >>> p.name + u'Molly' + >>> p.name = 'Charly' + >>> p.name + u'Charly' + +Now suppose that ``Pet::name`` was a private internal variable +that can only be accessed via setters and getters. + +.. code-block:: cpp + + class Pet { + public: + Pet(const std::string &name) : name(name) { } + void setName(const std::string &name_) { name = name_; } + const std::string &getName() const { return name; } + private: + std::string name; + }; + +In this case, the method :func:`class_::def_property` +(:func:`class_::def_property_readonly` for read-only data) can be used to +provide a field-like interface within Python that will transparently call +the setter and getter functions: + +.. code-block:: cpp + + py::class_(m, "Pet") + .def(py::init()) + .def_property("name", &Pet::getName, &Pet::setName) + // ... remainder ... + +Write only properties can be defined by passing ``nullptr`` as the +input for the read function. + +.. seealso:: + + Similar functions :func:`class_::def_readwrite_static`, + :func:`class_::def_readonly_static` :func:`class_::def_property_static`, + and :func:`class_::def_property_readonly_static` are provided for binding + static variables and properties. Please also see the section on + :ref:`static_properties` in the advanced part of the documentation. + +Dynamic attributes +================== + +Native Python classes can pick up new attributes dynamically: + +.. code-block:: pycon + + >>> class Pet: + ... name = 'Molly' + ... + >>> p = Pet() + >>> p.name = 'Charly' # overwrite existing + >>> p.age = 2 # dynamically add a new attribute + +By default, classes exported from C++ do not support this and the only writable +attributes are the ones explicitly defined using :func:`class_::def_readwrite` +or :func:`class_::def_property`. + +.. code-block:: cpp + + py::class_(m, "Pet") + .def(py::init<>()) + .def_readwrite("name", &Pet::name); + +Trying to set any other attribute results in an error: + +.. code-block:: pycon + + >>> p = example.Pet() + >>> p.name = 'Charly' # OK, attribute defined in C++ + >>> p.age = 2 # fail + AttributeError: 'Pet' object has no attribute 'age' + +To enable dynamic attributes for C++ classes, the :class:`py::dynamic_attr` tag +must be added to the :class:`py::class_` constructor: + +.. code-block:: cpp + + py::class_(m, "Pet", py::dynamic_attr()) + .def(py::init<>()) + .def_readwrite("name", &Pet::name); + +Now everything works as expected: + +.. code-block:: pycon + + >>> p = example.Pet() + >>> p.name = 'Charly' # OK, overwrite value in C++ + >>> p.age = 2 # OK, dynamically add a new attribute + >>> p.__dict__ # just like a native Python class + {'age': 2} + +Note that there is a small runtime cost for a class with dynamic attributes. +Not only because of the addition of a ``__dict__``, but also because of more +expensive garbage collection tracking which must be activated to resolve +possible circular references. Native Python classes incur this same cost by +default, so this is not anything to worry about. By default, pybind11 classes +are more efficient than native Python classes. Enabling dynamic attributes +just brings them on par. + +.. _inheritance: + +Inheritance and automatic downcasting +===================================== + +Suppose now that the example consists of two data structures with an +inheritance relationship: + +.. code-block:: cpp + + struct Pet { + Pet(const std::string &name) : name(name) { } + std::string name; + }; + + struct Dog : Pet { + Dog(const std::string &name) : Pet(name) { } + std::string bark() const { return "woof!"; } + }; + +There are two different ways of indicating a hierarchical relationship to +pybind11: the first specifies the C++ base class as an extra template +parameter of the :class:`class_`: + +.. code-block:: cpp + + py::class_(m, "Pet") + .def(py::init()) + .def_readwrite("name", &Pet::name); + + // Method 1: template parameter: + py::class_(m, "Dog") + .def(py::init()) + .def("bark", &Dog::bark); + +Alternatively, we can also assign a name to the previously bound ``Pet`` +:class:`class_` object and reference it when binding the ``Dog`` class: + +.. code-block:: cpp + + py::class_ pet(m, "Pet"); + pet.def(py::init()) + .def_readwrite("name", &Pet::name); + + // Method 2: pass parent class_ object: + py::class_(m, "Dog", pet /* <- specify Python parent type */) + .def(py::init()) + .def("bark", &Dog::bark); + +Functionality-wise, both approaches are equivalent. Afterwards, instances will +expose fields and methods of both types: + +.. code-block:: pycon + + >>> p = example.Dog('Molly') + >>> p.name + u'Molly' + >>> p.bark() + u'woof!' + +The C++ classes defined above are regular non-polymorphic types with an +inheritance relationship. This is reflected in Python: + +.. code-block:: cpp + + // Return a base pointer to a derived instance + m.def("pet_store", []() { return std::unique_ptr(new Dog("Molly")); }); + +.. code-block:: pycon + + >>> p = example.pet_store() + >>> type(p) # `Dog` instance behind `Pet` pointer + Pet # no pointer downcasting for regular non-polymorphic types + >>> p.bark() + AttributeError: 'Pet' object has no attribute 'bark' + +The function returned a ``Dog`` instance, but because it's a non-polymorphic +type behind a base pointer, Python only sees a ``Pet``. In C++, a type is only +considered polymorphic if it has at least one virtual function and pybind11 +will automatically recognize this: + +.. code-block:: cpp + + struct PolymorphicPet { + virtual ~PolymorphicPet() = default; + }; + + struct PolymorphicDog : PolymorphicPet { + std::string bark() const { return "woof!"; } + }; + + // Same binding code + py::class_(m, "PolymorphicPet"); + py::class_(m, "PolymorphicDog") + .def(py::init<>()) + .def("bark", &PolymorphicDog::bark); + + // Again, return a base pointer to a derived instance + m.def("pet_store2", []() { return std::unique_ptr(new PolymorphicDog); }); + +.. code-block:: pycon + + >>> p = example.pet_store2() + >>> type(p) + PolymorphicDog # automatically downcast + >>> p.bark() + u'woof!' + +Given a pointer to a polymorphic base, pybind11 performs automatic downcasting +to the actual derived type. Note that this goes beyond the usual situation in +C++: we don't just get access to the virtual functions of the base, we get the +concrete derived type including functions and attributes that the base type may +not even be aware of. + +.. seealso:: + + For more information about polymorphic behavior see :ref:`overriding_virtuals`. + + +Overloaded methods +================== + +Sometimes there are several overloaded C++ methods with the same name taking +different kinds of input arguments: + +.. code-block:: cpp + + struct Pet { + Pet(const std::string &name, int age) : name(name), age(age) { } + + void set(int age_) { age = age_; } + void set(const std::string &name_) { name = name_; } + + std::string name; + int age; + }; + +Attempting to bind ``Pet::set`` will cause an error since the compiler does not +know which method the user intended to select. We can disambiguate by casting +them to function pointers. Binding multiple functions to the same Python name +automatically creates a chain of function overloads that will be tried in +sequence. + +.. code-block:: cpp + + py::class_(m, "Pet") + .def(py::init()) + .def("set", (void (Pet::*)(int)) &Pet::set, "Set the pet's age") + .def("set", (void (Pet::*)(const std::string &)) &Pet::set, "Set the pet's name"); + +The overload signatures are also visible in the method's docstring: + +.. code-block:: pycon + + >>> help(example.Pet) + + class Pet(__builtin__.object) + | Methods defined here: + | + | __init__(...) + | Signature : (Pet, str, int) -> NoneType + | + | set(...) + | 1. Signature : (Pet, int) -> NoneType + | + | Set the pet's age + | + | 2. Signature : (Pet, str) -> NoneType + | + | Set the pet's name + +If you have a C++14 compatible compiler [#cpp14]_, you can use an alternative +syntax to cast the overloaded function: + +.. code-block:: cpp + + py::class_(m, "Pet") + .def("set", py::overload_cast(&Pet::set), "Set the pet's age") + .def("set", py::overload_cast(&Pet::set), "Set the pet's name"); + +Here, ``py::overload_cast`` only requires the parameter types to be specified. +The return type and class are deduced. This avoids the additional noise of +``void (Pet::*)()`` as seen in the raw cast. If a function is overloaded based +on constness, the ``py::const_`` tag should be used: + +.. code-block:: cpp + + struct Widget { + int foo(int x, float y); + int foo(int x, float y) const; + }; + + py::class_(m, "Widget") + .def("foo_mutable", py::overload_cast(&Widget::foo)) + .def("foo_const", py::overload_cast(&Widget::foo, py::const_)); + + +.. [#cpp14] A compiler which supports the ``-std=c++14`` flag + or Visual Studio 2015 Update 2 and newer. + +.. note:: + + To define multiple overloaded constructors, simply declare one after the + other using the ``.def(py::init<...>())`` syntax. The existing machinery + for specifying keyword and default arguments also works. + +Enumerations and internal types +=============================== + +Let's now suppose that the example class contains an internal enumeration type, +e.g.: + +.. code-block:: cpp + + struct Pet { + enum Kind { + Dog = 0, + Cat + }; + + Pet(const std::string &name, Kind type) : name(name), type(type) { } + + std::string name; + Kind type; + }; + +The binding code for this example looks as follows: + +.. code-block:: cpp + + py::class_ pet(m, "Pet"); + + pet.def(py::init()) + .def_readwrite("name", &Pet::name) + .def_readwrite("type", &Pet::type); + + py::enum_(pet, "Kind") + .value("Dog", Pet::Kind::Dog) + .value("Cat", Pet::Kind::Cat) + .export_values(); + +To ensure that the ``Kind`` type is created within the scope of ``Pet``, the +``pet`` :class:`class_` instance must be supplied to the :class:`enum_`. +constructor. The :func:`enum_::export_values` function exports the enum entries +into the parent scope, which should be skipped for newer C++11-style strongly +typed enums. + +.. code-block:: pycon + + >>> p = Pet('Lucy', Pet.Cat) + >>> p.type + Kind.Cat + >>> int(p.type) + 1L + +The entries defined by the enumeration type are exposed in the ``__members__`` property: + +.. code-block:: pycon + + >>> Pet.Kind.__members__ + {'Dog': Kind.Dog, 'Cat': Kind.Cat} + +The ``name`` property returns the name of the enum value as a unicode string. + +.. note:: + + It is also possible to use ``str(enum)``, however these accomplish different + goals. The following shows how these two approaches differ. + + .. code-block:: pycon + + >>> p = Pet( "Lucy", Pet.Cat ) + >>> pet_type = p.type + >>> pet_type + Pet.Cat + >>> str(pet_type) + 'Pet.Cat' + >>> pet_type.name + 'Cat' + +.. note:: + + When the special tag ``py::arithmetic()`` is specified to the ``enum_`` + constructor, pybind11 creates an enumeration that also supports rudimentary + arithmetic and bit-level operations like comparisons, and, or, xor, negation, + etc. + + .. code-block:: cpp + + py::enum_(pet, "Kind", py::arithmetic()) + ... + + By default, these are omitted to conserve space. diff --git a/wrap/python/pybind11/docs/compiling.rst b/wrap/python/pybind11/docs/compiling.rst new file mode 100644 index 000000000..c50c7d8af --- /dev/null +++ b/wrap/python/pybind11/docs/compiling.rst @@ -0,0 +1,289 @@ +.. _compiling: + +Build systems +############# + +Building with setuptools +======================== + +For projects on PyPI, building with setuptools is the way to go. Sylvain Corlay +has kindly provided an example project which shows how to set up everything, +including automatic generation of documentation using Sphinx. Please refer to +the [python_example]_ repository. + +.. [python_example] https://github.com/pybind/python_example + +Building with cppimport +======================== + +[cppimport]_ is a small Python import hook that determines whether there is a C++ +source file whose name matches the requested module. If there is, the file is +compiled as a Python extension using pybind11 and placed in the same folder as +the C++ source file. Python is then able to find the module and load it. + +.. [cppimport] https://github.com/tbenthompson/cppimport + +.. _cmake: + +Building with CMake +=================== + +For C++ codebases that have an existing CMake-based build system, a Python +extension module can be created with just a few lines of code: + +.. code-block:: cmake + + cmake_minimum_required(VERSION 2.8.12) + project(example) + + add_subdirectory(pybind11) + pybind11_add_module(example example.cpp) + +This assumes that the pybind11 repository is located in a subdirectory named +:file:`pybind11` and that the code is located in a file named :file:`example.cpp`. +The CMake command ``add_subdirectory`` will import the pybind11 project which +provides the ``pybind11_add_module`` function. It will take care of all the +details needed to build a Python extension module on any platform. + +A working sample project, including a way to invoke CMake from :file:`setup.py` for +PyPI integration, can be found in the [cmake_example]_ repository. + +.. [cmake_example] https://github.com/pybind/cmake_example + +pybind11_add_module +------------------- + +To ease the creation of Python extension modules, pybind11 provides a CMake +function with the following signature: + +.. code-block:: cmake + + pybind11_add_module( [MODULE | SHARED] [EXCLUDE_FROM_ALL] + [NO_EXTRAS] [SYSTEM] [THIN_LTO] source1 [source2 ...]) + +This function behaves very much like CMake's builtin ``add_library`` (in fact, +it's a wrapper function around that command). It will add a library target +called ```` to be built from the listed source files. In addition, it +will take care of all the Python-specific compiler and linker flags as well +as the OS- and Python-version-specific file extension. The produced target +```` can be further manipulated with regular CMake commands. + +``MODULE`` or ``SHARED`` may be given to specify the type of library. If no +type is given, ``MODULE`` is used by default which ensures the creation of a +Python-exclusive module. Specifying ``SHARED`` will create a more traditional +dynamic library which can also be linked from elsewhere. ``EXCLUDE_FROM_ALL`` +removes this target from the default build (see CMake docs for details). + +Since pybind11 is a template library, ``pybind11_add_module`` adds compiler +flags to ensure high quality code generation without bloat arising from long +symbol names and duplication of code in different translation units. It +sets default visibility to *hidden*, which is required for some pybind11 +features and functionality when attempting to load multiple pybind11 modules +compiled under different pybind11 versions. It also adds additional flags +enabling LTO (Link Time Optimization) and strip unneeded symbols. See the +:ref:`FAQ entry ` for a more detailed explanation. These +latter optimizations are never applied in ``Debug`` mode. If ``NO_EXTRAS`` is +given, they will always be disabled, even in ``Release`` mode. However, this +will result in code bloat and is generally not recommended. + +By default, pybind11 and Python headers will be included with ``-I``. In order +to include pybind11 as system library, e.g. to avoid warnings in downstream +code with warn-levels outside of pybind11's scope, set the option ``SYSTEM``. + +As stated above, LTO is enabled by default. Some newer compilers also support +different flavors of LTO such as `ThinLTO`_. Setting ``THIN_LTO`` will cause +the function to prefer this flavor if available. The function falls back to +regular LTO if ``-flto=thin`` is not available. + +.. _ThinLTO: http://clang.llvm.org/docs/ThinLTO.html + +Configuration variables +----------------------- + +By default, pybind11 will compile modules with the C++14 standard, if available +on the target compiler, falling back to C++11 if C++14 support is not +available. Note, however, that this default is subject to change: future +pybind11 releases are expected to migrate to newer C++ standards as they become +available. To override this, the standard flag can be given explicitly in +``PYBIND11_CPP_STANDARD``: + +.. code-block:: cmake + + # Use just one of these: + # GCC/clang: + set(PYBIND11_CPP_STANDARD -std=c++11) + set(PYBIND11_CPP_STANDARD -std=c++14) + set(PYBIND11_CPP_STANDARD -std=c++1z) # Experimental C++17 support + # MSVC: + set(PYBIND11_CPP_STANDARD /std:c++14) + set(PYBIND11_CPP_STANDARD /std:c++latest) # Enables some MSVC C++17 features + + add_subdirectory(pybind11) # or find_package(pybind11) + +Note that this and all other configuration variables must be set **before** the +call to ``add_subdirectory`` or ``find_package``. The variables can also be set +when calling CMake from the command line using the ``-D=`` flag. + +The target Python version can be selected by setting ``PYBIND11_PYTHON_VERSION`` +or an exact Python installation can be specified with ``PYTHON_EXECUTABLE``. +For example: + +.. code-block:: bash + + cmake -DPYBIND11_PYTHON_VERSION=3.6 .. + # or + cmake -DPYTHON_EXECUTABLE=path/to/python .. + +find_package vs. add_subdirectory +--------------------------------- + +For CMake-based projects that don't include the pybind11 repository internally, +an external installation can be detected through ``find_package(pybind11)``. +See the `Config file`_ docstring for details of relevant CMake variables. + +.. code-block:: cmake + + cmake_minimum_required(VERSION 2.8.12) + project(example) + + find_package(pybind11 REQUIRED) + pybind11_add_module(example example.cpp) + +Note that ``find_package(pybind11)`` will only work correctly if pybind11 +has been correctly installed on the system, e. g. after downloading or cloning +the pybind11 repository : + +.. code-block:: bash + + cd pybind11 + mkdir build + cd build + cmake .. + make install + +Once detected, the aforementioned ``pybind11_add_module`` can be employed as +before. The function usage and configuration variables are identical no matter +if pybind11 is added as a subdirectory or found as an installed package. You +can refer to the same [cmake_example]_ repository for a full sample project +-- just swap out ``add_subdirectory`` for ``find_package``. + +.. _Config file: https://github.com/pybind/pybind11/blob/master/tools/pybind11Config.cmake.in + +Advanced: interface library target +---------------------------------- + +When using a version of CMake greater than 3.0, pybind11 can additionally +be used as a special *interface library* . The target ``pybind11::module`` +is available with pybind11 headers, Python headers and libraries as needed, +and C++ compile definitions attached. This target is suitable for linking +to an independently constructed (through ``add_library``, not +``pybind11_add_module``) target in the consuming project. + +.. code-block:: cmake + + cmake_minimum_required(VERSION 3.0) + project(example) + + find_package(pybind11 REQUIRED) # or add_subdirectory(pybind11) + + add_library(example MODULE main.cpp) + target_link_libraries(example PRIVATE pybind11::module) + set_target_properties(example PROPERTIES PREFIX "${PYTHON_MODULE_PREFIX}" + SUFFIX "${PYTHON_MODULE_EXTENSION}") + +.. warning:: + + Since pybind11 is a metatemplate library, it is crucial that certain + compiler flags are provided to ensure high quality code generation. In + contrast to the ``pybind11_add_module()`` command, the CMake interface + library only provides the *minimal* set of parameters to ensure that the + code using pybind11 compiles, but it does **not** pass these extra compiler + flags (i.e. this is up to you). + + These include Link Time Optimization (``-flto`` on GCC/Clang/ICPC, ``/GL`` + and ``/LTCG`` on Visual Studio) and .OBJ files with many sections on Visual + Studio (``/bigobj``). The :ref:`FAQ ` contains an + explanation on why these are needed. + +Embedding the Python interpreter +-------------------------------- + +In addition to extension modules, pybind11 also supports embedding Python into +a C++ executable or library. In CMake, simply link with the ``pybind11::embed`` +target. It provides everything needed to get the interpreter running. The Python +headers and libraries are attached to the target. Unlike ``pybind11::module``, +there is no need to manually set any additional properties here. For more +information about usage in C++, see :doc:`/advanced/embedding`. + +.. code-block:: cmake + + cmake_minimum_required(VERSION 3.0) + project(example) + + find_package(pybind11 REQUIRED) # or add_subdirectory(pybind11) + + add_executable(example main.cpp) + target_link_libraries(example PRIVATE pybind11::embed) + +.. _building_manually: + +Building manually +================= + +pybind11 is a header-only library, hence it is not necessary to link against +any special libraries and there are no intermediate (magic) translation steps. + +On Linux, you can compile an example such as the one given in +:ref:`simple_example` using the following command: + +.. code-block:: bash + + $ c++ -O3 -Wall -shared -std=c++11 -fPIC `python3 -m pybind11 --includes` example.cpp -o example`python3-config --extension-suffix` + +The flags given here assume that you're using Python 3. For Python 2, just +change the executable appropriately (to ``python`` or ``python2``). + +The ``python3 -m pybind11 --includes`` command fetches the include paths for +both pybind11 and Python headers. This assumes that pybind11 has been installed +using ``pip`` or ``conda``. If it hasn't, you can also manually specify +``-I /include`` together with the Python includes path +``python3-config --includes``. + +Note that Python 2.7 modules don't use a special suffix, so you should simply +use ``example.so`` instead of ``example`python3-config --extension-suffix```. +Besides, the ``--extension-suffix`` option may or may not be available, depending +on the distribution; in the latter case, the module extension can be manually +set to ``.so``. + +On Mac OS: the build command is almost the same but it also requires passing +the ``-undefined dynamic_lookup`` flag so as to ignore missing symbols when +building the module: + +.. code-block:: bash + + $ c++ -O3 -Wall -shared -std=c++11 -undefined dynamic_lookup `python3 -m pybind11 --includes` example.cpp -o example`python3-config --extension-suffix` + +In general, it is advisable to include several additional build parameters +that can considerably reduce the size of the created binary. Refer to section +:ref:`cmake` for a detailed example of a suitable cross-platform CMake-based +build system that works on all platforms including Windows. + +.. note:: + + On Linux and macOS, it's better to (intentionally) not link against + ``libpython``. The symbols will be resolved when the extension library + is loaded into a Python binary. This is preferable because you might + have several different installations of a given Python version (e.g. the + system-provided Python, and one that ships with a piece of commercial + software). In this way, the plugin will work with both versions, instead + of possibly importing a second Python library into a process that already + contains one (which will lead to a segfault). + +Generating binding code automatically +===================================== + +The ``Binder`` project is a tool for automatic generation of pybind11 binding +code by introspecting existing C++ codebases using LLVM/Clang. See the +[binder]_ documentation for details. + +.. [binder] http://cppbinder.readthedocs.io/en/latest/about.html diff --git a/wrap/python/pybind11/docs/conf.py b/wrap/python/pybind11/docs/conf.py new file mode 100644 index 000000000..d17e4ba30 --- /dev/null +++ b/wrap/python/pybind11/docs/conf.py @@ -0,0 +1,332 @@ +#!/usr/bin/env python3 +# -*- coding: utf-8 -*- +# +# pybind11 documentation build configuration file, created by +# sphinx-quickstart on Sun Oct 11 19:23:48 2015. +# +# This file is execfile()d with the current directory set to its +# containing dir. +# +# Note that not all possible configuration values are present in this +# autogenerated file. +# +# All configuration values have a default; values that are commented out +# serve to show the default. + +import sys +import os +import shlex +import subprocess + +# If extensions (or modules to document with autodoc) are in another directory, +# add these directories to sys.path here. If the directory is relative to the +# documentation root, use os.path.abspath to make it absolute, like shown here. +#sys.path.insert(0, os.path.abspath('.')) + +# -- General configuration ------------------------------------------------ + +# If your documentation needs a minimal Sphinx version, state it here. +#needs_sphinx = '1.0' + +# Add any Sphinx extension module names here, as strings. They can be +# extensions coming with Sphinx (named 'sphinx.ext.*') or your custom +# ones. +extensions = ['breathe'] + +breathe_projects = {'pybind11': '.build/doxygenxml/'} +breathe_default_project = 'pybind11' +breathe_domain_by_extension = {'h': 'cpp'} + +# Add any paths that contain templates here, relative to this directory. +templates_path = ['.templates'] + +# The suffix(es) of source filenames. +# You can specify multiple suffix as a list of string: +# source_suffix = ['.rst', '.md'] +source_suffix = '.rst' + +# The encoding of source files. +#source_encoding = 'utf-8-sig' + +# The master toctree document. +master_doc = 'index' + +# General information about the project. +project = 'pybind11' +copyright = '2017, Wenzel Jakob' +author = 'Wenzel Jakob' + +# The version info for the project you're documenting, acts as replacement for +# |version| and |release|, also used in various other places throughout the +# built documents. +# +# The short X.Y version. +version = '2.3' +# The full version, including alpha/beta/rc tags. +release = '2.3.dev1' + +# The language for content autogenerated by Sphinx. Refer to documentation +# for a list of supported languages. +# +# This is also used if you do content translation via gettext catalogs. +# Usually you set "language" from the command line for these cases. +language = None + +# There are two options for replacing |today|: either, you set today to some +# non-false value, then it is used: +#today = '' +# Else, today_fmt is used as the format for a strftime call. +#today_fmt = '%B %d, %Y' + +# List of patterns, relative to source directory, that match files and +# directories to ignore when looking for source files. +exclude_patterns = ['.build', 'release.rst'] + +# The reST default role (used for this markup: `text`) to use for all +# documents. +default_role = 'any' + +# If true, '()' will be appended to :func: etc. cross-reference text. +#add_function_parentheses = True + +# If true, the current module name will be prepended to all description +# unit titles (such as .. function::). +#add_module_names = True + +# If true, sectionauthor and moduleauthor directives will be shown in the +# output. They are ignored by default. +#show_authors = False + +# The name of the Pygments (syntax highlighting) style to use. +#pygments_style = 'monokai' + +# A list of ignored prefixes for module index sorting. +#modindex_common_prefix = [] + +# If true, keep warnings as "system message" paragraphs in the built documents. +#keep_warnings = False + +# If true, `todo` and `todoList` produce output, else they produce nothing. +todo_include_todos = False + + +# -- Options for HTML output ---------------------------------------------- + +# The theme to use for HTML and HTML Help pages. See the documentation for +# a list of builtin themes. + +on_rtd = os.environ.get('READTHEDOCS', None) == 'True' + +if not on_rtd: # only import and set the theme if we're building docs locally + import sphinx_rtd_theme + html_theme = 'sphinx_rtd_theme' + html_theme_path = [sphinx_rtd_theme.get_html_theme_path()] + + html_context = { + 'css_files': [ + '_static/theme_overrides.css' + ] + } +else: + html_context = { + 'css_files': [ + '//media.readthedocs.org/css/sphinx_rtd_theme.css', + '//media.readthedocs.org/css/readthedocs-doc-embed.css', + '_static/theme_overrides.css' + ] + } + +# Theme options are theme-specific and customize the look and feel of a theme +# further. For a list of options available for each theme, see the +# documentation. +#html_theme_options = {} + +# Add any paths that contain custom themes here, relative to this directory. +#html_theme_path = [] + +# The name for this set of Sphinx documents. If None, it defaults to +# " v documentation". +#html_title = None + +# A shorter title for the navigation bar. Default is the same as html_title. +#html_short_title = None + +# The name of an image file (relative to this directory) to place at the top +# of the sidebar. +#html_logo = None + +# The name of an image file (within the static path) to use as favicon of the +# docs. This file should be a Windows icon file (.ico) being 16x16 or 32x32 +# pixels large. +#html_favicon = None + +# Add any paths that contain custom static files (such as style sheets) here, +# relative to this directory. They are copied after the builtin static files, +# so a file named "default.css" will overwrite the builtin "default.css". +html_static_path = ['_static'] + +# Add any extra paths that contain custom files (such as robots.txt or +# .htaccess) here, relative to this directory. These files are copied +# directly to the root of the documentation. +#html_extra_path = [] + +# If not '', a 'Last updated on:' timestamp is inserted at every page bottom, +# using the given strftime format. +#html_last_updated_fmt = '%b %d, %Y' + +# If true, SmartyPants will be used to convert quotes and dashes to +# typographically correct entities. +#html_use_smartypants = True + +# Custom sidebar templates, maps document names to template names. +#html_sidebars = {} + +# Additional templates that should be rendered to pages, maps page names to +# template names. +#html_additional_pages = {} + +# If false, no module index is generated. +#html_domain_indices = True + +# If false, no index is generated. +#html_use_index = True + +# If true, the index is split into individual pages for each letter. +#html_split_index = False + +# If true, links to the reST sources are added to the pages. +#html_show_sourcelink = True + +# If true, "Created using Sphinx" is shown in the HTML footer. Default is True. +#html_show_sphinx = True + +# If true, "(C) Copyright ..." is shown in the HTML footer. Default is True. +#html_show_copyright = True + +# If true, an OpenSearch description file will be output, and all pages will +# contain a tag referring to it. The value of this option must be the +# base URL from which the finished HTML is served. +#html_use_opensearch = '' + +# This is the file name suffix for HTML files (e.g. ".xhtml"). +#html_file_suffix = None + +# Language to be used for generating the HTML full-text search index. +# Sphinx supports the following languages: +# 'da', 'de', 'en', 'es', 'fi', 'fr', 'h', 'it', 'ja' +# 'nl', 'no', 'pt', 'ro', 'r', 'sv', 'tr' +#html_search_language = 'en' + +# A dictionary with options for the search language support, empty by default. +# Now only 'ja' uses this config value +#html_search_options = {'type': 'default'} + +# The name of a javascript file (relative to the configuration directory) that +# implements a search results scorer. If empty, the default will be used. +#html_search_scorer = 'scorer.js' + +# Output file base name for HTML help builder. +htmlhelp_basename = 'pybind11doc' + +# -- Options for LaTeX output --------------------------------------------- + +latex_elements = { +# The paper size ('letterpaper' or 'a4paper'). +#'papersize': 'letterpaper', + +# The font size ('10pt', '11pt' or '12pt'). +#'pointsize': '10pt', + +# Additional stuff for the LaTeX preamble. +'preamble': '\DeclareUnicodeCharacter{00A0}{}', + +# Latex figure (float) alignment +#'figure_align': 'htbp', +} + +# Grouping the document tree into LaTeX files. List of tuples +# (source start file, target name, title, +# author, documentclass [howto, manual, or own class]). +latex_documents = [ + (master_doc, 'pybind11.tex', 'pybind11 Documentation', + 'Wenzel Jakob', 'manual'), +] + +# The name of an image file (relative to this directory) to place at the top of +# the title page. +# latex_logo = 'pybind11-logo.png' + +# For "manual" documents, if this is true, then toplevel headings are parts, +# not chapters. +#latex_use_parts = False + +# If true, show page references after internal links. +#latex_show_pagerefs = False + +# If true, show URL addresses after external links. +#latex_show_urls = False + +# Documents to append as an appendix to all manuals. +#latex_appendices = [] + +# If false, no module index is generated. +#latex_domain_indices = True + + +# -- Options for manual page output --------------------------------------- + +# One entry per manual page. List of tuples +# (source start file, name, description, authors, manual section). +man_pages = [ + (master_doc, 'pybind11', 'pybind11 Documentation', + [author], 1) +] + +# If true, show URL addresses after external links. +#man_show_urls = False + + +# -- Options for Texinfo output ------------------------------------------- + +# Grouping the document tree into Texinfo files. List of tuples +# (source start file, target name, title, author, +# dir menu entry, description, category) +texinfo_documents = [ + (master_doc, 'pybind11', 'pybind11 Documentation', + author, 'pybind11', 'One line description of project.', + 'Miscellaneous'), +] + +# Documents to append as an appendix to all manuals. +#texinfo_appendices = [] + +# If false, no module index is generated. +#texinfo_domain_indices = True + +# How to display URL addresses: 'footnote', 'no', or 'inline'. +#texinfo_show_urls = 'footnote' + +# If true, do not generate a @detailmenu in the "Top" node's menu. +#texinfo_no_detailmenu = False + +primary_domain = 'cpp' +highlight_language = 'cpp' + + +def generate_doxygen_xml(app): + build_dir = os.path.join(app.confdir, '.build') + if not os.path.exists(build_dir): + os.mkdir(build_dir) + + try: + subprocess.call(['doxygen', '--version']) + retcode = subprocess.call(['doxygen'], cwd=app.confdir) + if retcode < 0: + sys.stderr.write("doxygen error code: {}\n".format(-retcode)) + except OSError as e: + sys.stderr.write("doxygen execution failed: {}\n".format(e)) + + +def setup(app): + """Add hook for building doxygen xml when needed""" + app.connect("builder-inited", generate_doxygen_xml) diff --git a/wrap/python/pybind11/docs/faq.rst b/wrap/python/pybind11/docs/faq.rst new file mode 100644 index 000000000..93ccf10e5 --- /dev/null +++ b/wrap/python/pybind11/docs/faq.rst @@ -0,0 +1,297 @@ +Frequently asked questions +########################## + +"ImportError: dynamic module does not define init function" +=========================================================== + +1. Make sure that the name specified in PYBIND11_MODULE is identical to the +filename of the extension library (without prefixes such as .so) + +2. If the above did not fix the issue, you are likely using an incompatible +version of Python (for instance, the extension library was compiled against +Python 2, while the interpreter is running on top of some version of Python +3, or vice versa). + +"Symbol not found: ``__Py_ZeroStruct`` / ``_PyInstanceMethod_Type``" +======================================================================== + +See the first answer. + +"SystemError: dynamic module not initialized properly" +====================================================== + +See the first answer. + +The Python interpreter immediately crashes when importing my module +=================================================================== + +See the first answer. + +CMake doesn't detect the right Python version +============================================= + +The CMake-based build system will try to automatically detect the installed +version of Python and link against that. When this fails, or when there are +multiple versions of Python and it finds the wrong one, delete +``CMakeCache.txt`` and then invoke CMake as follows: + +.. code-block:: bash + + cmake -DPYTHON_EXECUTABLE:FILEPATH= . + +.. _faq_reference_arguments: + +Limitations involving reference arguments +========================================= + +In C++, it's fairly common to pass arguments using mutable references or +mutable pointers, which allows both read and write access to the value +supplied by the caller. This is sometimes done for efficiency reasons, or to +realize functions that have multiple return values. Here are two very basic +examples: + +.. code-block:: cpp + + void increment(int &i) { i++; } + void increment_ptr(int *i) { (*i)++; } + +In Python, all arguments are passed by reference, so there is no general +issue in binding such code from Python. + +However, certain basic Python types (like ``str``, ``int``, ``bool``, +``float``, etc.) are **immutable**. This means that the following attempt +to port the function to Python doesn't have the same effect on the value +provided by the caller -- in fact, it does nothing at all. + +.. code-block:: python + + def increment(i): + i += 1 # nope.. + +pybind11 is also affected by such language-level conventions, which means that +binding ``increment`` or ``increment_ptr`` will also create Python functions +that don't modify their arguments. + +Although inconvenient, one workaround is to encapsulate the immutable types in +a custom type that does allow modifications. + +An other alternative involves binding a small wrapper lambda function that +returns a tuple with all output arguments (see the remainder of the +documentation for examples on binding lambda functions). An example: + +.. code-block:: cpp + + int foo(int &i) { i++; return 123; } + +and the binding code + +.. code-block:: cpp + + m.def("foo", [](int i) { int rv = foo(i); return std::make_tuple(rv, i); }); + + +How can I reduce the build time? +================================ + +It's good practice to split binding code over multiple files, as in the +following example: + +:file:`example.cpp`: + +.. code-block:: cpp + + void init_ex1(py::module &); + void init_ex2(py::module &); + /* ... */ + + PYBIND11_MODULE(example, m) { + init_ex1(m); + init_ex2(m); + /* ... */ + } + +:file:`ex1.cpp`: + +.. code-block:: cpp + + void init_ex1(py::module &m) { + m.def("add", [](int a, int b) { return a + b; }); + } + +:file:`ex2.cpp`: + +.. code-block:: cpp + + void init_ex2(py::module &m) { + m.def("sub", [](int a, int b) { return a - b; }); + } + +:command:`python`: + +.. code-block:: pycon + + >>> import example + >>> example.add(1, 2) + 3 + >>> example.sub(1, 1) + 0 + +As shown above, the various ``init_ex`` functions should be contained in +separate files that can be compiled independently from one another, and then +linked together into the same final shared object. Following this approach +will: + +1. reduce memory requirements per compilation unit. + +2. enable parallel builds (if desired). + +3. allow for faster incremental builds. For instance, when a single class + definition is changed, only a subset of the binding code will generally need + to be recompiled. + +"recursive template instantiation exceeded maximum depth of 256" +================================================================ + +If you receive an error about excessive recursive template evaluation, try +specifying a larger value, e.g. ``-ftemplate-depth=1024`` on GCC/Clang. The +culprit is generally the generation of function signatures at compile time +using C++14 template metaprogramming. + +.. _`faq:hidden_visibility`: + +"‘SomeClass’ declared with greater visibility than the type of its field ‘SomeClass::member’ [-Wattributes]" +============================================================================================================ + +This error typically indicates that you are compiling without the required +``-fvisibility`` flag. pybind11 code internally forces hidden visibility on +all internal code, but if non-hidden (and thus *exported*) code attempts to +include a pybind type (for example, ``py::object`` or ``py::list``) you can run +into this warning. + +To avoid it, make sure you are specifying ``-fvisibility=hidden`` when +compiling pybind code. + +As to why ``-fvisibility=hidden`` is necessary, because pybind modules could +have been compiled under different versions of pybind itself, it is also +important that the symbols defined in one module do not clash with the +potentially-incompatible symbols defined in another. While Python extension +modules are usually loaded with localized symbols (under POSIX systems +typically using ``dlopen`` with the ``RTLD_LOCAL`` flag), this Python default +can be changed, but even if it isn't it is not always enough to guarantee +complete independence of the symbols involved when not using +``-fvisibility=hidden``. + +Additionally, ``-fvisiblity=hidden`` can deliver considerably binary size +savings. (See the following section for more details). + + +.. _`faq:symhidden`: + +How can I create smaller binaries? +================================== + +To do its job, pybind11 extensively relies on a programming technique known as +*template metaprogramming*, which is a way of performing computation at compile +time using type information. Template metaprogamming usually instantiates code +involving significant numbers of deeply nested types that are either completely +removed or reduced to just a few instructions during the compiler's optimization +phase. However, due to the nested nature of these types, the resulting symbol +names in the compiled extension library can be extremely long. For instance, +the included test suite contains the following symbol: + +.. only:: html + + .. code-block:: none + + _​_​Z​N​8​p​y​b​i​n​d​1​1​1​2​c​p​p​_​f​u​n​c​t​i​o​n​C​1​I​v​8​E​x​a​m​p​l​e​2​J​R​N​S​t​3​_​_​1​6​v​e​c​t​o​r​I​N​S​3​_​1​2​b​a​s​i​c​_​s​t​r​i​n​g​I​w​N​S​3​_​1​1​c​h​a​r​_​t​r​a​i​t​s​I​w​E​E​N​S​3​_​9​a​l​l​o​c​a​t​o​r​I​w​E​E​E​E​N​S​8​_​I​S​A​_​E​E​E​E​E​J​N​S​_​4​n​a​m​e​E​N​S​_​7​s​i​b​l​i​n​g​E​N​S​_​9​i​s​_​m​e​t​h​o​d​E​A​2​8​_​c​E​E​E​M​T​0​_​F​T​_​D​p​T​1​_​E​D​p​R​K​T​2​_ + +.. only:: not html + + .. code-block:: cpp + + __ZN8pybind1112cpp_functionC1Iv8Example2JRNSt3__16vectorINS3_12basic_stringIwNS3_11char_traitsIwEENS3_9allocatorIwEEEENS8_ISA_EEEEEJNS_4nameENS_7siblingENS_9is_methodEA28_cEEEMT0_FT_DpT1_EDpRKT2_ + +which is the mangled form of the following function type: + +.. code-block:: cpp + + pybind11::cpp_function::cpp_function, std::__1::allocator >, std::__1::allocator, std::__1::allocator > > >&, pybind11::name, pybind11::sibling, pybind11::is_method, char [28]>(void (Example2::*)(std::__1::vector, std::__1::allocator >, std::__1::allocator, std::__1::allocator > > >&), pybind11::name const&, pybind11::sibling const&, pybind11::is_method const&, char const (&) [28]) + +The memory needed to store just the mangled name of this function (196 bytes) +is larger than the actual piece of code (111 bytes) it represents! On the other +hand, it's silly to even give this function a name -- after all, it's just a +tiny cog in a bigger piece of machinery that is not exposed to the outside +world. So we'll generally only want to export symbols for those functions which +are actually called from the outside. + +This can be achieved by specifying the parameter ``-fvisibility=hidden`` to GCC +and Clang, which sets the default symbol visibility to *hidden*, which has a +tremendous impact on the final binary size of the resulting extension library. +(On Visual Studio, symbols are already hidden by default, so nothing needs to +be done there.) + +In addition to decreasing binary size, ``-fvisibility=hidden`` also avoids +potential serious issues when loading multiple modules and is required for +proper pybind operation. See the previous FAQ entry for more details. + +Working with ancient Visual Studio 2008 builds on Windows +========================================================= + +The official Windows distributions of Python are compiled using truly +ancient versions of Visual Studio that lack good C++11 support. Some users +implicitly assume that it would be impossible to load a plugin built with +Visual Studio 2015 into a Python distribution that was compiled using Visual +Studio 2008. However, no such issue exists: it's perfectly legitimate to +interface DLLs that are built with different compilers and/or C libraries. +Common gotchas to watch out for involve not ``free()``-ing memory region +that that were ``malloc()``-ed in another shared library, using data +structures with incompatible ABIs, and so on. pybind11 is very careful not +to make these types of mistakes. + +Inconsistent detection of Python version in CMake and pybind11 +============================================================== + +The functions ``find_package(PythonInterp)`` and ``find_package(PythonLibs)`` provided by CMake +for Python version detection are not used by pybind11 due to unreliability and limitations that make +them unsuitable for pybind11's needs. Instead pybind provides its own, more reliable Python detection +CMake code. Conflicts can arise, however, when using pybind11 in a project that *also* uses the CMake +Python detection in a system with several Python versions installed. + +This difference may cause inconsistencies and errors if *both* mechanisms are used in the same project. Consider the following +Cmake code executed in a system with Python 2.7 and 3.x installed: + +.. code-block:: cmake + + find_package(PythonInterp) + find_package(PythonLibs) + find_package(pybind11) + +It will detect Python 2.7 and pybind11 will pick it as well. + +In contrast this code: + +.. code-block:: cmake + + find_package(pybind11) + find_package(PythonInterp) + find_package(PythonLibs) + +will detect Python 3.x for pybind11 and may crash on ``find_package(PythonLibs)`` afterwards. + +It is advised to avoid using ``find_package(PythonInterp)`` and ``find_package(PythonLibs)`` from CMake and rely +on pybind11 in detecting Python version. If this is not possible CMake machinery should be called *before* including pybind11. + +How to cite this project? +========================= + +We suggest the following BibTeX template to cite pybind11 in scientific +discourse: + +.. code-block:: bash + + @misc{pybind11, + author = {Wenzel Jakob and Jason Rhinelander and Dean Moldovan}, + year = {2017}, + note = {https://github.com/pybind/pybind11}, + title = {pybind11 -- Seamless operability between C++11 and Python} + } diff --git a/wrap/python/pybind11/docs/index.rst b/wrap/python/pybind11/docs/index.rst new file mode 100644 index 000000000..d236611b7 --- /dev/null +++ b/wrap/python/pybind11/docs/index.rst @@ -0,0 +1,47 @@ +.. only: not latex + + .. image:: pybind11-logo.png + +pybind11 --- Seamless operability between C++11 and Python +========================================================== + +.. only: not latex + + Contents: + +.. toctree:: + :maxdepth: 1 + + intro + changelog + upgrade + +.. toctree:: + :caption: The Basics + :maxdepth: 2 + + basics + classes + compiling + +.. toctree:: + :caption: Advanced Topics + :maxdepth: 2 + + advanced/functions + advanced/classes + advanced/exceptions + advanced/smart_ptrs + advanced/cast/index + advanced/pycpp/index + advanced/embedding + advanced/misc + +.. toctree:: + :caption: Extra Information + :maxdepth: 1 + + faq + benchmark + limitations + reference diff --git a/wrap/python/pybind11/docs/intro.rst b/wrap/python/pybind11/docs/intro.rst new file mode 100644 index 000000000..10e1799a1 --- /dev/null +++ b/wrap/python/pybind11/docs/intro.rst @@ -0,0 +1,93 @@ +.. image:: pybind11-logo.png + +About this project +================== +**pybind11** is a lightweight header-only library that exposes C++ types in Python +and vice versa, mainly to create Python bindings of existing C++ code. Its +goals and syntax are similar to the excellent `Boost.Python`_ library by David +Abrahams: to minimize boilerplate code in traditional extension modules by +inferring type information using compile-time introspection. + +.. _Boost.Python: http://www.boost.org/doc/libs/release/libs/python/doc/index.html + +The main issue with Boost.Python—and the reason for creating such a similar +project—is Boost. Boost is an enormously large and complex suite of utility +libraries that works with almost every C++ compiler in existence. This +compatibility has its cost: arcane template tricks and workarounds are +necessary to support the oldest and buggiest of compiler specimens. Now that +C++11-compatible compilers are widely available, this heavy machinery has +become an excessively large and unnecessary dependency. +Think of this library as a tiny self-contained version of Boost.Python with +everything stripped away that isn't relevant for binding generation. Without +comments, the core header files only require ~4K lines of code and depend on +Python (2.7 or 3.x, or PyPy2.7 >= 5.7) and the C++ standard library. This +compact implementation was possible thanks to some of the new C++11 language +features (specifically: tuples, lambda functions and variadic templates). Since +its creation, this library has grown beyond Boost.Python in many ways, leading +to dramatically simpler binding code in many common situations. + +Core features +************* +The following core C++ features can be mapped to Python + +- Functions accepting and returning custom data structures per value, reference, or pointer +- Instance methods and static methods +- Overloaded functions +- Instance attributes and static attributes +- Arbitrary exception types +- Enumerations +- Callbacks +- Iterators and ranges +- Custom operators +- Single and multiple inheritance +- STL data structures +- Smart pointers with reference counting like ``std::shared_ptr`` +- Internal references with correct reference counting +- C++ classes with virtual (and pure virtual) methods can be extended in Python + +Goodies +******* +In addition to the core functionality, pybind11 provides some extra goodies: + +- Python 2.7, 3.x, and PyPy (PyPy2.7 >= 5.7) are supported with an + implementation-agnostic interface. + +- It is possible to bind C++11 lambda functions with captured variables. The + lambda capture data is stored inside the resulting Python function object. + +- pybind11 uses C++11 move constructors and move assignment operators whenever + possible to efficiently transfer custom data types. + +- It's easy to expose the internal storage of custom data types through + Pythons' buffer protocols. This is handy e.g. for fast conversion between + C++ matrix classes like Eigen and NumPy without expensive copy operations. + +- pybind11 can automatically vectorize functions so that they are transparently + applied to all entries of one or more NumPy array arguments. + +- Python's slice-based access and assignment operations can be supported with + just a few lines of code. + +- Everything is contained in just a few header files; there is no need to link + against any additional libraries. + +- Binaries are generally smaller by a factor of at least 2 compared to + equivalent bindings generated by Boost.Python. A recent pybind11 conversion + of `PyRosetta`_, an enormous Boost.Python binding project, reported a binary + size reduction of **5.4x** and compile time reduction by **5.8x**. + +- Function signatures are precomputed at compile time (using ``constexpr``), + leading to smaller binaries. + +- With little extra effort, C++ types can be pickled and unpickled similar to + regular Python objects. + +.. _PyRosetta: http://graylab.jhu.edu/RosettaCon2016/PyRosetta-4.pdf + +Supported compilers +******************* + +1. Clang/LLVM (any non-ancient version with C++11 support) +2. GCC 4.8 or newer +3. Microsoft Visual Studio 2015 or newer +4. Intel C++ compiler v17 or newer (v16 with pybind11 v2.0 and v15 with pybind11 v2.0 and a `workaround `_ ) diff --git a/wrap/python/pybind11/docs/limitations.rst b/wrap/python/pybind11/docs/limitations.rst new file mode 100644 index 000000000..a1a4f1aff --- /dev/null +++ b/wrap/python/pybind11/docs/limitations.rst @@ -0,0 +1,20 @@ +Limitations +########### + +pybind11 strives to be a general solution to binding generation, but it also has +certain limitations: + +- pybind11 casts away ``const``-ness in function arguments and return values. + This is in line with the Python language, which has no concept of ``const`` + values. This means that some additional care is needed to avoid bugs that + would be caught by the type checker in a traditional C++ program. + +- The NumPy interface ``pybind11::array`` greatly simplifies accessing + numerical data from C++ (and vice versa), but it's not a full-blown array + class like ``Eigen::Array`` or ``boost.multi_array``. + +These features could be implemented but would lead to a significant increase in +complexity. I've decided to draw the line here to keep this project simple and +compact. Users who absolutely require these features are encouraged to fork +pybind11. + diff --git a/wrap/python/pybind11/docs/pybind11-logo.png b/wrap/python/pybind11/docs/pybind11-logo.png new file mode 100644 index 0000000000000000000000000000000000000000..4cbad54f797d3ced04d4048f282df5e4336d4af4 GIT binary patch literal 58510 zcmeFYWmjC`vNhVcySqEV-5r9v6Wm>b1b2rJf;$QB?ry=|9TGHHaDNxcK4+g_a6jEK zR@2a{mpwIWR@JN`Qdv3t=`0?SPR zkz$xfNPw*PLFJR0QIa5S77(U|Tt6>p=^cpWy_SUxsJaQ%J%Nf)3xY)iv8Y6Z(t#ko zK}J6)C_F(SX&_9gKUxA843((+^uS7`)e5vw@=6Bk!M<~b(b8ffrk!|?!+^Gpc7bB8jJ%^*-3@@}hl>`K0XaPkXWh{@Vsy!2BO!s`>! zEP4NXlNN1y%v}|9=QxSyN9+t5DrrG2P}p$*-8YMNt8B494t;+=p9*)3?zCqCFyVk zrV6=S0;deCYLq&uh78dkK^Jh|aDA!P1pXf&wxFl5c4^kHfwd}vbBGP%EydjUAyWAW zQ)X_g>G9aP8B;Fx_<}K9dHYjkRwyg+LgGU#-3PcZ?EQ8uOoM%5H9U-PiKe49B#>ApB+Va|pOESfzgp?d;D{$O!5FskPG~|iJ za`n`$X!rfNCTy(X+A@q33+V9}%&6WG;{Du|=#k=VG%cUO-`9LspFy9InsHF2IAkoz z;E=(mNE}`^}*9lKs(x&oU8l{(h&nL#sMsBa8P7^%uu4 zX!BGyQH^ius_Vsh>S&ztx?&Z1jjB~D;l&snAJciqgR$Ss6;$LW&Ei|(SlwDz9k{ik zttSyHrc7zgj2=oKq#Qt8c_1Q%VFeFGSkmHU;KJZq;(6d!rOFrL%|_!5sk3mi9;fc7 zp`r6`x5jX{eUKEv6tB*ck<1pUEbL<- zXFqk#__B{XeOu}?QCqZNX-OWhIJ+#nR-NkQR|{d7-BjnhOgBZiecGawOTVZM%rm+j zI)XwD`4(1lecRIHlw|EPnKG3!>EjNr%9En3!VbwcoyS0A(IHtHeHv-Y_z9@2eYIt^ z^&q@3l+X8~THVKa|hoaNe?9LAX+47D>8(tmz4}`wV&+5-fJGBy@B zHk-e%{i$21bK2PM5UR_oQ=qM(YfvXukySyp&{ok_gjUp|n5bBmy!ly646WTewCU=99~ z@Yz|cluRM9(elW0&%%AQ+&r}QWxyf2iJ3SFX4tmwb2*gGJNQPi!UJ_(+C_SpT1#^+ zi>~p=5#HpoY=-fZvAU7f&)k`3Ij<+^z3AIt8VkbYwB8YE?{$>h@YV`Ad#%FnVnH#4 zX+oC^G)Fbk+s`YNooJ<0`gKr$Qm_sD&@&R$(*S0BjGzJkE7bRRZSllFNt;<`v%&Zw zEQ>%0D>AAQa}_5A%YTV>&GQ#QxZ_Ay+S=FplCu65vq_5?i^IK*ciDQ#$)zcKDaZ~; z%PaLro0|0}*Ef=@%qiovt8KxJ;w|601e)8;i-sr0`GwWLt6!-qc)d15_n75cWe|-N~cPm^OS$cSv{Ah1bp=j@XG6XRL@eD(O z+_=~>H%~MpsID5nz;G;$JVes@l6B_s4v7m%BQ|qzhr&t1>*wJu+~zGY65on@jCc7q z%q)pJktGqcjad4hbg2xr^hZ4ty;h|$q3MOAjZaU~t0X9y90EFCvX|<^)+>iWvx$~} zCS$UavV8rR?$?Y~^BcYQO(!;OP#n)%QQfv@BwwTV`P=y?^#3%w{i$93g`w4~m0rbX zXn*8(B=C|rt2ES>*_K|}qHo)B`l+MA+v4_+Ae(z){i?(30{eAgKATr?z2owe2|7bY9Az zl*BH3pMvM3?qj^F)xq9D;?7}DcGeG9nvW+v9%~*%XWuqalz#e<`qREz-Pc^JO%**R z;w2`&LPDfoKAEz=TLtn>Qd1dK1rX>H6$lg%3IeIkcFp_=o~Qlx!gr2TL-qcVcMTrFhO zii{1IM-U{-Z9E<#jQD3r5f>IvwxduKm;-3Teq*0|^3oemLqil5^1mAoL~?onDQwXH zY`wgnwZ;F>7q&@d%E|t_JID!@a^e5%7Uh9OxBWl6NeLk%Iseb;QIUiC@&EVaz%MYO zCP@FiI%-HTX-(MwTpQTkEBgOm{=duj|M}vd&q4mZIwLn?Up>eQ8WkKBG-dYS&K!Un zQ2bJ*rZLacfdAKg8f_k`8cDi=Z?=ml*fe92hZSK6zy`g5`}=ZpOcw_0e)+qrbX7Xx zAE5fbI56QB;)(DF*vp;oe*&v7DP4L0PVNm%67#={{sS|UVJ>V$4CwRb>*LtiSlCdp zw+%WN_&In>o&dXZ!2|pRw$`>b*XKhfP(^9!U~v-M8^nt51hM`DKE_YtJuF}#G&ApM zqt!-xD_dJ}IXSrve+K;6{EiNyHusZSKU-Ll=+aU&8|T09r2ph7`5$CPugL#IwZSJK zn4X?aND@_}tm4Bt&Y z_j{=Z;^gE67BbnQ`JxVZQpbE1(rY6y|7esKshNkQTTY<|=t$zS&=wdlj^ znZfPE?!zc84J*N+chQ$LMz_iK`SZTMq2ZlxKYA=VCcF+*27!h~tSU1qWR3i>9;o{l zdS|G2$?rtcQk=hDoNu$F*}GU6(8>mp=AIgoUXMTs7`ne!3cQv#(B zFj=zsA>FU&L}hW*c_bwT5mZPOEYXIV?W@OUD~As+&z4$RDfiZ2KjrNVs>60qj9n7( zyXQ7EeDwN8ZBX5EF-Q=*jhG7|f^ZEhiaIJndzo8PgVtl@q+`fP9G{`ocU-tf6LA#w z=J^pvxy$(HOf=J0bA-w$35E)iGud8Kb8{haame1#F0Slv&**cRu{q{r&ELmD)(WA3 z+VAp#e|2Rg`JF3^I1eFLG^dJ(Y#qShWXRwg4Fgr42WUIy2kYW zwQ|L*Fbb=U<{HV^d!`<`I!HBlwji5 znv+!VJp;_T6NYNai(Nx4)gi)YE0Oe0B&=8xSTJxg*K$^OeePlXR8m;b-?*Ue!)Uu7 z#*Q6rY-RPsv$E9YYioeE;?9NVf|?Cl5b4Ot%KN=uNYS7F&P%`Sl$^WQ8J(V^?O;-a z3&jg5%DCE)I1&yQM2q$Jd{beGT$vJ`{d)(;UyO&}B9S(x8IwF}h}z${kzZRgub-;g z!T|V%Y1$CrWDDiVUqnpfNF%5Qo3+3EeTI;~ID{Vn+v~;T(V`B!FOa0I$?_D4J3V#4 zcLgpc=ll}H$19+f6C;OL=x`bzp#!!KP~HOr z>%=aw|T5;BF|4x2Nq?28hI+9p)CsoXuZ>Y#W^vU zO%*OE73D8a(fjo21f_eo@@qpCm#)AWdFR1?w_wO2W3_Cu4el+;dv7tVc!zuvOHCE+&y=G%ds1hZA zmn)y`&9YpX^N}Br=fM?tz;fZZurD_yF_6PA4!*_fhNge^W5W_f?N>F@XCxpXKm*A3 zdZ5@Rl{6yspJ{q&Lt9uPIp?F9QbUZ;?Xo?0;5fLs^@b#SB*@W1#K;6L`Y`}X1}L!K z1$9J#^vxSGLI1o#x-N@A5peueNCJwjgVWQ&SniF8g#}I9w6!4M==#RSoel3Z$v2kN z>mbbo*6J6T)&4)^YQtu~WmNe)EbeK58J9v!OI5;*#irt>H`4AODh=AIZ5Nq1xVZ8Q z3ZTZv$ARFcW6F*mNs1j!21KX2y4g>R9$`hGkn0%+fIekg-K9$I;ex8g-lCHPlq1jK zDXB3{8bt?Q*kK6u3hu^xfO-}vnl1|v(q%C6u&H59@T_YuSKhyUA3@Yy8F1$$7{K~e zk{a_7rKMz`+g`VJkHFv1PF28P=r({$DPEO}fd0CbYwp+^X^*Tpaaj^4wy>z!T!AR_ zNg@emUO6FPyWMaIbno@`NrcfrX!IWBu)R_-wlr_Z+Q$5gtX!o1{OY@Ci4p`@hSu|$ zl2?FNi;rw+l29-p6HxwP`ygx7q+*= z*Q!s4V|{%c%ftBXpo5hb{m(7uL4ke*0T8rV%Hq$p%`djot5sjc6b2&fzv=*~wMyU{ z#RGRp3cGK>U*h9AK`IP-mtm0sv4MOo=lqNVU7h&gc=!**;M|!%wf^SgUZQ)w1t?eI zw6SpZ12B(V*M{u%wMEoNT?L^dxxmTjVg8*oqE`YOu%&*l5bQTM>Uu1a->Xyp6;lET z8H87j^cEjfEZ%TruFsgk9{-oPgGm4MHoGTpQA;}}o#_Ql)mo<$-YkTvYs5~^X;;63 z10OW;5+|1x|mG*+Zb^7Tmp*~hy+N2mEU{o36nUs+9s zIO?Chm%{2Gp(DlL-~}l<)lipfYdIeYj@So@8+HgfXUx>NF{2inHQ5kC{B~9Jah!jg zzNDk%Z>aC(`rn6Fkp<`&9g5IOOb@H)1^vblG{IX@X7dpL*9i2%s_6*Q#ekcTMzA3W ziKh(}u;5fus{|OQa`8-tG|~q>Q)M!+@)#DEGz-%GHTTz7$@>48yXFmsZ|2s4cipz3 zC2?E* z+}2lmH5Df<;QRxK=>GsDqMg)ry8z`61T6~2N-5k;^g)+9h`;zX6YSqJ2>)AD)O(nM zyfIV$u~4wwwzjtXU|Aq1QWm1F*TDFVGvz=2knJFi=N}Wbn)u}{6<2w|(faG{z%6;1 z=<~~MX{kAP;EPAOPX6eH$A7uVK0 zbYQZCjiA~9h}6j&!#AO$@nsJPIF!p1!0y9^@`kM8AW-B#Mb=fUJILRoc{30y8xE6S z7m0{h#+0T;wXifv7?{8ZV-g0{NM9gxR~dsuIRrCd56FGl6tht$X?hX_9fTI1O0mBJ zNLIDQ=nwijqo2A*3&2(-?os>AMI=@^#raQ4YQV##>fs0dP<5AQxsJO21oY!SQcHhV zhtSfPZ=}*r)yp*>VO;#_F!yTD-f@b`kyMW%V#&Kmc7%LyPxa}(xwQ11hR`ctE?jhh z+3;iDTdI`UUyS676F}!J5$D1m zPy~dG8Jsj1OoyFfd8{`5y&MeHk2$orNHoc zwC?~C!R?-aKkbUbT9qlU3ExBSbpPHBw+{af!fXPedXu7OcgOiTnc#d%`m`^-L2GLv zBjY^L(r=>u;)vMV<$w?}oAV`706}!>b+m4a7n^Z3z&1FRXZF2C6PVeOfY<@&^(;D2cu&|i@Xt>6! zadB979q-Wu)hq_nDy>a7DRqsL@1trT7DEhc2Dy8cLVu+MZzBh5KsYo3-8BSH%Q5k25JXwZ>33HsD*@*j={+O1sG! zj@_HW&%TsQSs}Des9x9tlR^8qu&pwEHHf%jV5Sc-T9sG0@n94(%>$BJ9h7->0f}PFD zi&yf#bm4E)zi{md9QkL zH9!Enj}2#`2ZDo5kgspoeB21m%81Q}1npg?8jE8MPMux}sbbH|bx}M0{UCA#-hmh& z-UV(mzm*QiHb7b2y9H|v%ecN2qBKQmpO zKl$)7DYT{f!_HhG4A{%PM4B>fh!IP~-rioOsL_T>Coyj7>n~XR=d=Kku0#UOdGq74 z+AhE8J>LB#Ci6#$D4#BS1UL?Wl7TFC&}VFH*ks>SN;y`7JVNSQgao;c&L_TAFuS4_ zt4CbqBU{&FAMkP2csNs3Y4V5xlR-Yg@CZ|4f|FJ!48sso^9Xq}CV~Cb1BqXjrt06d zzioz`iTolQHqdyMHc_xpES z&bwCY4ArP_fZ!j87~&BZzePdviijy0xbuZ<6x~x4G+GP76|eR(d$hdRQR43|2uI8d zGtYgM-$pv{h;Dw}<9vJZ`0SvQ!%P_auvsHFXODe9=5Iz8O2$LzGgb4t{&g|iSA048 z84~+TZc^ff#kOsBqg`>*_%E~ZhtQ^Uu3WOZROdw`hJAb6CPvIBe88`fvztTe;XSdy zzWg9dligi9Od~bp3v_(v@%cdA)!4TWXOJ*k6i~XXtgS_9F~#KMM!$3}ijW2<(|%3b zA&wtHiel0NvBBhfdKbnc1Stj{Eq51YN)U2T`_{ zH6MM@{XrfdIEn%IBbdBG(YUB&2$0!@JDldHxs%{$rE7r>4m)CohcSH|z`k^gVmH{~ z2j-yJVB-_iex8pHq|fvlq;@a}w%m{}l3$UVs zf&tVppppfY!a$&g-iOCr%}uJ3R4&jy6ItCpF@hT#F}^fM+=)3q_@1kTW8K@rb?Vo( znTjI!E_rX>X?)zu(NWsln;#G~0WsjMFielWiQqU%-K~6#BjT6kq8gx@Mx!)D^dE2vuhj5?Y*c-h(%3eV+mTq@V$CS zDzAren>hkCKEeYL0RfZJNjt{t8!y)e(SpLNfu7a`-Ha9Z6z$*)u}}Rkg!B9M^G||K zZ4G1iWNP3^;yj+^*B%%ByV5;zITGo{-K?R}O0KMYtg&T_57jl(@g5sp5fIYMsmxnS z?1&hu8V&Qtres{Rg{EQLN@0M(4hV4jLYP2z0{PT)GK7?Y!L-#|I^(xAIjXf`_*xUr z+LEF`{>KSoNs`}9Mq)rCQP{HDM5QiD1Q>5>%LDJy#LWbM_B|FxB&E7WD5cYRt7L=# z!uvVMhS5H_%r+K>r}apcrvxI~=)|$m>v1sxMvq_V>FHAo3tiV&jjYj8w|vdq%P-xi_iY z4#)UwcT%I*&BtLHyrJp9%JI0^pmQEO^f$r?!{tmObZx?PO(MkW1u_DH`NogZVe=oK zb}Kwc(_|?sN|iN4G*SvxnBx_8vP^?LU*}N8xIY9=u6J$N5Vi#yrz-k_xn^o(kjQOy zZ1A+k8}`54GH=ZX@1yZ^gF}CUPX5tD<*aOm%#;vJd8EUcsi~M8ACOWN=p2eZA+S{2 z>Aq2(o>xQnU6mdeT3hXGaPXtwn%g-1nv1<)*iaEFzi?C?&LAtFQ0$=@{Fm{evmdvy?FBw%TYzCWg+F1C;4VVDt{g|oD zzPRN1bfGg0v5KHwG_3D=vlO9TqpY^j)9L5Rra2%MOR*1h63knd$A^@$L2GRBc?l&! zP;qL{b#*qlVQ?&nvv6vWPGQ#-F~_{}{~&bwU1@yJxOGC@6DF$B6_>&{$py&mSVDr{ zV}Q&O0K(ft8*r&%(<3ZTmu#OZPsgwfLpzU3*Qv8+lp_z%;9l4jUtF{`K^{FwQ*3v* zVeF$Lq!X8qVSaQTYD`C%+}HZ%c!QkE?G1z`&xgYzAPm{Hc(1tJLxKBV5&59^=-V#C z=gsTqUV`VIYv-TVofzOLbwWtbb>B}2fCo+P4@4!|IvtvkXeWb}F>N#zIvOD|Jh5p* zf2KqxSa|5JK`bnsJs%-=J-?#@((193O}G=>kuUkBHu}Q!ODG`VJJZ}O@R5rnnSU#q zb_;68bKOIXq4CV`Nz59VIv8&bCe);IGnSbq!d74dy~GHS9J(>FeBueD5e*nQ=Q!hra#h+g}OpTxfaZyt+ilmJ1tFnSnq4lrf0k* z4FKsm`dwy7sfjbxAYxnF=qxNUw?brj7n>1l2MwC{xX3Eb)e^gPyIA_X(Vn9tGeMvQ z;4`sOXn@4pkD;W!Z<33s7|3W&x(FVvQVv8uZ|^qKIzj|8Ttxh1H$dl3krEtdk*_N) zwZ9x+wqZJPYlb`dJia5oe4q6*>Womr5pGaJGMe+NPF;KAFe+CF_KP**AvGVK`sM-B;2sT$^AYWp&QW4lhP|}Lj#yRRbehI)143T z9OP4RS%v6x6yID`v7~_kh!c#YotWE9C#X0FR6s-|*cDLia?J-2)m**iTtljAG1)U_ z!I<+_`Ncy_He3yO*JDDN3dxTNdSl$eKC-@EZRMHLDE`KB$Wb<#f?0Md&WDRNAb;4h zkj+^lk8|Zt2}>I?4V`RhueAZv7N1NiWIS6aHIe$*YK?YvJcPlp+)zFVu__ zjKh>qy)_ht)nHXT3CqcO{^)z|Dfro3huMEbsTeF^-gbdB?Vb_uxN zh<{N6omb$d#?4PE-0UQpwyOWFdW2(luxHV4!fH!57)K9_ZjWU1L%;bvR|(}u z4wvDv$LX3*!X-=Hg5gU$bum?k}zyJ8H*a?t0tl56KqJPEH`T3bG#tR3Vhf#-9 zXRZCCVCT$3+h;1cFSG%>UM%Iwf=1Y2T#hRdRsO#`(2h^UNw-f%S7APn$uQsUZv*RqgOY7Zb`a=74M)DHw|sHlpuIh5b4x>HByRrztcXKF^BqRtaRDCnZzM&QPBmx{tJ7Y=~ZImp5^g; z1CO%>rQFppYyn}sgbBD|MZL(%CoRLxHC(Wr-FV>-(}6%$E<%Yuj0Ic&MO*DcG?ro@ zT_4Pg%DiD*vha#(NZ*bkFAVO;w$7Qz&c;TJ1OH=rUcJI`y_cP`b&*gK;njy$5Tu62 z31b4PN?cE8;>~3T$blp2`^vgMnmP~V!cu*LUP@6*by_`qu@^jHa$+tbmw`cimG7>t zGA52b6J8K)fax-?oQ;nV^J(iYHX+{?G4Lr<3gUZUumGGVPH*ZPHI5#a0fNRkmRoI7 zlG^h(T)dp1e3&JHp`##Z_Nw?%9FjFqyc~;v$sCOYUi3(J0b@KFhkfzD#jN-zh7zLy z$;ZdLburHICS=pG@dOQa4zAEmiOC+SKcA__+jYjiW|;SP3HSt7+9Ga^ZQ)WEeOY?V zcD57XAwJEL@iiSu@R<(m;v=>ri!FP#)WR#TpCjeJN7A;}%zlnS)}RYWka)aFO6W9_3zj0>i1 zCR>RIm=#x!5F$Dtq0zC!bK!7(E4?RK_bv6eYgDf5BsP5bgY3EH;JF45tV=#^(0+^8 zK=OD7m&r-G29LiVC?@+?PjyU!f|}L)iS6ufGVw@O8~l z>7g5ulrDEa*L4=ZOQp)1%LX`$*23F;`O$NN&XS$F5YkG;bF}tFXI8%iLt*nf0g?T9 z>3jJCr>!NZtNxvHZ;3t(8FU_lrwp{0KX@B{O%Z_hc+=$%1}7*Uwad!M8QE29ttR9; z(736OYmrwt^Mn!w3(0rY-CKgXrtd%D> zGeG;0_7htuTRZ|M4p%?^?kjeoBWW9=&1{&)-4jk%ghrX>Aq_9xXLC5QY;$>!buWew ztB+i&!;~}DAL$g=m>i&iTJ~-UQy>cTehj&?1?owXt=!&ew{@^Q_VQOyUSFWvuQy2NIJT0#PVVdzW}yg9BxsV& zd)PwF*}Sm89B&ZuC%w>&Gq_9}p(BA9K2JTD3K0lY`E}DJBr7HOSYFTMuG^ve+b%GE zHQHl7Gvi~ScKZ{hNI%9!Tg;iO)oe{cPNE5&iNVs?KK2=PBW_=BxrjhB{GszCQaVQ@L7b^AME)etX z>~Fok&ju_G*qSqt!@QpxGg=0h)dX!NdT{H8M&F>vA@!ATrYwFYN07nylZ^Hz|?T*wb$2u_3m*5nu~0c_>Q;U(OKnwN#JwL@$2!n}dA8U8Zo#aFFM- zld#lK(bjE*uF*SdX`NAW%e#3esITQ_&8H&)_lJ$>#O6e!0@ayYP#|rM{oc^KpI-<+ zZhU@+`M}^-iAQkxE~8S^pbra>e2G&)I#YvjT%i zMWpP8HDDE%r=R)XIyybwy?@%VoHQ}pg7nM|?XE$+OY;{P5}6W=Zzdm_xvaV!A47xk zO*E~W6-`0Y8xI{Pm;hK_nZ<~l5cwO>($Dmo3moD3Sg}k9o2bohyAIbYs_+u!mpBjs{V#=QT-@0_hYi>GI9uNEqFA zBr<)-$^=7)2;RT2Ba06qSXKFDggi5utyV;xi>$P`5ayq`+$ig?60< z*2|V{S2z~K(bfg+d2>?Q9~zykicgOI(n8t(%WT+vZMIz z&yozaHk8#koY-)1ly{@>b%r12sp*g-0Hyi7C37x(jY+L?Y%{YX}?Ru1R} zdK!;}}b#J*Q5KvXG8c3;VK=7J>6l;%>P+aOTx^rLZ)vR49VQ*&%1 zus^*ZcqBL3i=S&esk932iA3&7H?|jLs$!_|B&*E)aPff zJFg<9ySf~6i}{s}(41hxe=C*8G#~j;*X>I$=hG+9mtoAALpRY-<-R@&Tq1(WdmT{4 z*paZnh5t@x{4+B6M+Qz|w8(IiuVt`r)rG zc;CxYeVoM4wTj>FSBJl_X4b46;lrcT7QHN=_nCfJ;O;W^al9;yy)!vJ>(juQlN4TH zDcoZZGDH(Y0=2tWZ+bG)9W?T?G;zv|K}G>3x~3tl7!5FQ_(-l#_f|D_oD1lmb~6*l zn_5}Ht~NQ+)VSp-T00B^5+%I_(*&!qo)Ozff!)v(pklKw9MUtN*fk!0WTUP>LH2Pp zCpcK8wZb!30)8L#E{FbGi)bSvjFtjQ42^{IxZO_SqlD}?XRih>C}| zS6jcl$P*7E(KzOYX`!ibe~g3p;b&3J_K}ff6z7iw4O5G^wL72@Mvy9qLbBw#ww-ZR!9brWD$6NT@YRgMs0&I}a3 zB7YoDqF{BZ9j1l`s{ls~h4e-^=^q~7JpsiW-jr+hv_BZ2=F6Lmi?vJUygXwleJ0+j zNf$tSH>GEd)XIKD3z_>&J(W755io$j8Ib(_O>1e7G7@qw8)yg9bpSf*X^*B>b|XAC zE2y^Gq!rjSGn9p@2fT^B9Vouw#7zWWXw@^d*$p*gKk9e9ZangMA3zoB@{Q+vdcErG z*6a+pn)WrOv@Ky%T5x3&5fL@QiT{#i!R-ec5jEbor(-EA%AJEAb_Y->Kt3sS&< zWr9pd|BL{j@BzcTeHcmt3HPc?6UUEivta8C!)Lc@jiz~tnv?B7)?{u9E3!&1i$b@= z>`U;LRX58&RO#PpQ!en>v;DGV%1o6t)~@Jl}%L%{H9Eyo-Oy#qxh#?~)#+ zAr7L2-MZc!PCY*gwC^F=3N@5;YToy4@AMGPhlw{bF{!OaO56+|&*0u^)Js3F2|t@W zt_x{g4^5=;cHaBJV3c;4FW`=iDLa!6Tk98#vOdIQ(YdA?G_H>$Pu-_kW8p%Nr19?Q zsp73WUxRF-IIPW{V+!1fui12@!u9MQ&A#)vTPW?Gj%6fUIG z5?1bWcp1M_l*MfHNJGrgpJpunaO?W>*c@l{RI;=2fP!T|Y>sJ@w(SS3(b~+u8P0pZbtoqc#j?VON_C-XzX~QpGbtHa zi4Cah_NJFr4y|(=B1k&-96R@&-S(W__8x!S?ekc-cxf1fPqi2XT6`;=LXMgWVKBt7 z+unlSJq6);wemgqTedKh1Uj4olkzmwb5*LJwbuqa>gq563jv#ffkEgQbb2}}d?>IH z;#31e^4m2-#0+{hgAT6So&pX+H|_ddhU0r8b^4J~-*jB3XHe=`%u8`?l`W9@YKVXa z-nhv)a+vYTNIwc4&IwDBFz#@^rSOt|%$H;T=PJ*tGs@5CDq30y$>z#!mBd<{<&cw?K(QRP1Ela_oBN@Q z$AOE-VL&G%D*vMj(%0j{`Am)7%TMRmRZk8dx|)C_j+V2G)z=vIupT~4e8ZK2H3^t; zFks29Yk%NAa(lm0#TeWVOkV>X0bp)eTdglTzpae`n4$DMDgi2@$LX1wASa&R5pB;v z)6D{ye>YCulPnC?y27o4X{b;dfYaY>hft-Fme3_srch!V~q}TSW~6=nMxBeG^HhJO?+dwv_9O;-f4qB#i)ss?ZS^UUt$U5+!du)xhTNuDPhBV6do=N&3Sfw^FfGJMh~a7fVr%1Eacvo|40&;f9q z=5=_?6hsxwo=bt#yD5dG$3gx*R(!hId#nk8yOpz72gMr4iF@Y(zD)cBuqtq6&bmXN z!FgbYg`Bm*T-aHFos+ZV1q&(?0V8?<6*+v|qiH|(S^l!OeGgLJ)`nf)+z7 z%qEZdX?;UMud+Lgp$c-yHC2|axT36YWeb|3+r16z&R16|c8_@{Z1h(U?O5ss_6|S0 zfI!e@=MDC0=OuQtKAUIuUj0qp0!k>jH!BTCw{sb+8o$ZAgJ@}1nA!9tm}o!>?5v#@GYI{ z{g+hPyvIAqa=pVqy*;vM!Y_1Kug_@|dn9cm6ZL#y#xcXUXPw1KpE^A(@N@isqg30N z3mzTWY+ulRmYC-86P%5Iy=;387#wUUu7Ky&9G85SPV#_d=lRDv z?aKr7f{GQvCS5RrEIe+wjcxlQZ>wa z%`A6yzneDxI}iefu+4g0{QKbob3GbpT5ON7j|I%2-e&qWLt|kdaCM+bwXm@8#rFju z16Oy2rqa@JbB-aCG_LhJ%gNf!aR;EDK+u!>64xLmC<4d!>AUvQQfOtV)G9BK)1RNiUo24vcb$PKG0t82 zDQ~@AZ|oskXV)^xUijs17ibwPo^fB!;=_0?FuM2X!egxb`s5huqS2Bx&4P#_id@q! zlKhL$HqO^RpK&+U#Q6OO9haD%m78&4$@7N{r}4d2r(JuGo%G|T?)^)0)bqSXu7I~{ z1?W|gZcU=wERl!ci(CS-4av})8+wU4pDo3*#{;9#bxV~c9A^}{@o0Ejp3>7rzp1xJ zk>=B=zv9cX3oIvS>SBL*Y4Szyh@IqK_D^Y{cNz*}ptTuhh2bLxB1*j3^Ak`jku@KG zR@HcRWpp4qi!>OF3P2zn#icPHMh_4Bt;*RJOuy?s2eg&}Vi*`Ca0sQ1LWO+CA7!qs zE!Pc5>n~S&{t*Z`Og$%>G0y53=eF6>QQ+?}Ek?F+jYjuk3!XCNLTkhsILe?wL0Sf} z>h!U0V5Ub6!OvmJ6f(`)VtLdNY%Dm);eE|VrDZPmKfS?x)HX>u%Su-YOKmLkGN?2( zb|20fN=xw}&uJ}cUEX|uh}gUQyGg9%memZzXO|^d=&_#v$JJj)RrS4JpfG)C5b2bZ zPU&utmhJ{=kVYB-X#wdJMY=l=B^@H&aTG+l8}8!s{k`uP_x`109Ea!Zz1Du#eCC|b z+|MYMasU&Y{f~?QSe~#WCzqGA9VoHk=L=mt5P=)6xRg{!oA-@^L`kW=mi7#`wzeVM zG@Ore9;{!)|7=oTNeG9>a{iD%RRzk{IH}4H`FC&oknbA`$ zTRh&sj(vJ;$;G%}W3O_$niv(bh5tG`JLg(UmAV`q%XTDvYkzA&6{+Lw4ur2F&pZxs1OSqN`u#$ex8!_#TYp`N&*lVF!p_5 z7_=Gd1%|>Tlv%>#dZR6iSzeB0E&0QXGmmfX@HcVX{zJ{3B zx@nfkS%6Or1mj6RxzW|=m)@sM`cIX{k6av9&Q(#-5QzANA~-Y|*-4V@$=l2H%DUkXatK?rCMz2S&v4(rRbCaq4beZK5_JJ$Tr>fn03Y3^L6xy~VI~Om>E)y$+b5LrMK|(pduO8*eSjxa zmfUm%e!8QlL9xR|G35M(17)-T9z1TBzj=QDm;iuGH7I9FgRAk4zl4gk{n>jL^0uWR zQFF_jl~CH3B)zfLizr_yXu2o^7%rtUJFYF`)2* zQh`$R#rk84ztJD2Sph|SMvv~{Gxxrb!wS-{d#R;jGSEH9BVU*zX`=uP`N|C7^i=(| zcEG*3?YtpRex8i$Ly0gEwk_BzlByp{n*g9XcZSs3j{DVJ+9R)=$Cv&;cy3c+d#2uC zkN*9JA{->Oa`3JW7QAJ8y8jZIe6G)(!E2zS@{lz4a~^;7FG*K)Fs9<~7ii=%CL`tM z3mMW`_qpYk6p=A!wZBS~K8|O;%i9m_%QGgF2HbXOLD@ zR5Y#yG@NO;XDEXaJH3|c8G%WD=Hzp;A^Y7>hSUh9>(#TaMO;U({YCAhH(lUsr$sg-;)1O5~vi)U%}<<*JeVx7Nq^X*Yfw9XT>Mv-7LOKp6eV|r$^Cn zYu5Mgg7q}xfh#yJjFT{%?K?LkPu^pW+U7a`Y6jDxr1^k5M_+hM8kdMrbWYGoGxaoF z*ZCzK$W@6c5qCET16KF#4`*{c6OY#!d1MQ`_xFf?3$M+k#=2o?Mdcfh1L@#KnL%p&ck=6otTb>@!V*29zuD%FW6npY(U8Bp2v1u27tzV)<394r7$f4ER zZ9Q`|$bWB(iG{TgcscV+KClBPhgAm2jGL&Dwk~2coMXREK8{>GC`sP&0koo%l!3IuN6r=w?4dblf+t4<6S1VTA3+7x3TS zFn!Zzt2Qa6mEbUH{{RJ(7OrRWXfTJlh=uZL_?XAJuB$_KPG?Qi>XqG;esCdZd`3H)5=L$bu zJ-m%q@~-{d*<*E=OnKNR-dlta@!+Q5-L4yZ%?Nr-LrcGzfNiocDMmzDb*R#rjXT zvj4{h5`)SDAB^^@37>8pH%g}5+lWU>W!WxF9*W_(9Do(MA7{x{h%ttp=RhqyKn#T0 z7WL=vUe8L$`x4I~ISBN zZ+f9Md`&EQU87DWT3BlD9wig|X=SRM6d482A=RAQY1Mx}RDAE9VzbW4K zb#Oz+@PWnE#ud|+Bi7P`Cdz}%tdh%v?s$lQ#?Khtcm2*}40-2^Up)NI*&_O?EYCuO=`A?-+LK$)& z>B}etcjW1eEVg}YLK?>TytcU5+9KwEP}EY~r+e461q#c_Bt+Wheb9GD`ZyzNmhh9D z$NPkIWo1M-q(nt5EDNQUSGkl&Bn|tv6Ic@X4Xmi~*4@D&Yui8OC~xr|pwNc|RM9)T z>2f_}ptWLTO2ATmn~fKPjPW3fX4F<_ye-JMF+;9HgtOg@>ZxsV{48T;ot^<91&6_))u3OyzE|Gix zu9bev%O1>UJM*E}yiD-G()tBLKRhwIN=aPA$f%KzZpj?ZiSSUCdVH0qq;N&qRETBF zO+p{(Ky7}@5o==C;gA2iHNQ!zv7oDnN|MR-s`6Xx!O+*LeO22ZH?DH^S*$GerVU}`WZLR?!?2&W#C(p zZ6A@H57#h!_YGHp*vd-w)3n85Muk1rA2zGMbR{Dv__>M3-K7nf*NTB4;J~S;>du*L zJhdC#CA9w2cRopf_dXEH8{_87Z<6?NCUTFdD0SvfmrvePbU_BHp4?UsNl=*%q+Py^ z|5b_wdp1{6LYj}G^*)6oO*HcdAcB%q_aAssyPNaCV9(QYbK4vXKjoiM1zyD-FKdSJ z%d?k>GxmOeRp|vd%5XZn?gob0(T9!wJRelkhx@8t=sQF!E|^-c)NesBAQeBduL0w< z;JFuQ{VSfT{9Sp|^dfjMd%qCh)itZ$nvaMwfvm#xA*W!g@9}DU4R#Ypw(iyjc#8Ya zZ1CkJNX)(7&_`*^-J+sn1i(5)K?`1JQ03R8d(uM7V);(=vwVd+xL><1A6WcXg_h+C zag~LIg)54xL^W*Oe_k*=tn1MxC75miR~*6cG{U3h@h-r2OAF>&Bsn`=QKIe zn+6`TJfhHkg=I+a2>Oxau?)!7uhO@JQYDbfPl7n1WBlX+Ob|IibA6q|@UuD-%dgyt5w2axlH~#{dOJQpyJSA+8P|9f&Gh zgixyn5Ub{}nl?j$it2+MD|@#q9Kgp?7V&5LCB^3yonJ4W{T$9yKFho&B=-Z7$>*Q(xlY_h9k${AkC-}sh;nyUI_LjThq&5YqG?Z$yPb2whmg&R>q=L zB(G+zWMwLl#P5Rv+m)Zgxir}1hK&PCGXT~qwXgrSWOqcT*_LKxl8D(U7tuH;czUh4!#xbf^c!n`9zLX9JVx=a z`B6kMjcKLBGWxELVxvqmELi1k*91}HEp3tKTCVQ4#lk*&cdVu|7PC2U?o4g>KdmU_x9ef;TRnAcK~d0$i#3`=1+$r9 zzpDTf;E)Dh8rL=gg(Rfh?K9R2lDeJFDcj?TiM!=1!zncXn9#mGiOIeLZYKQdJuck=#0z!Jxb_tx7eyWY@w z1WDFewuh>5H4JAph#<1yy{nxSx~@?T;qI(ST;e1exJSek6upH?Zh)azH+RAS= zijOFubN?rAfPq1D5xo_?`DMzWF}z|0V;J$h=gBd9KKt6H=>bCg9a@NWOOTc} zuT5vA{8x=7S?%W?e-`5jDF5nKtVL10hqPS+)E>nfLsi|c`W4sR9L~q#5&mg>1X{rE zl4zqgS4RBzFkC6SKcg<~lLFlrG_rKpPfY)kIJvn~b%BVc7I;TZK0k-d?uKFq{J>T- zvVs}u`W{RXm1_q-8g@mCv3%A~Ti272kNnYH+V4eHMg35sSwmp@m{`WI9u0n)V?e1< zL_7|4s##-H$mS&6qSk$}!-(XMvpP6>_l@IfCQ(okaH{6QgfxO#N7V62fYfhNMP`x! zp=?4(Q;J}WUKhYFmu-0;uoege-wc&m4}`ogFWkl@j-$BO{`PI7F2C(9m)`2ZXi8jx z&o4ycGNQI*N57AVHGX-ix79wycSn6nj)}70!fH5sxysF3KE8+|Nz}0?_N){W`K^51 zd-SuB_lIWBwb=j%RQCa~5jZ2}F83n``;YHVC)QJR?W+Ut{fz3&5i5v01i?92w_Ixkjf>|^h9aCT4ap)Wb zjMJAYw^+>*6D9V_NAr+~`8Sj8>bR|6?`c*$L#+`HnmrLsR=n{$ia5+x{uyK+@<%BC zlyv%u(px6iQ^8*`CywD@)mvVEx#8Wo7A-9r;Pcq0;kf#a1z$D-7%VmFgPfZXnjZ9$ z=srqq6+2gKPKl&;-v9QF9Y_j27~&d0j;BY%3jw%NnsM#SM;d?dtb^Y0Bi|_B6DDLA zN8&QN*%udZA{aqK|Z2AILuCIe8#ZLP}j@gGQ7sH5!gXDe}>w zvQ*xw3oAiBf|cIwxM%6=Af|{@m{cOHg zYt&VEZ)0qofiRPrQZ~0a`iy|NNXnYGcZD0*F?PZzw)+St@Jtg)WC|CV2q_nFpw?`D zkGs0f1xh%FS=rM~8?a@HCA86NSZ6QgZ35BwZ7UY@=jyy7Yt}r#5@7<`jzbmDj0}!? zXW5Ygw;?<_#Se`33j*a#U;9N;pG33wYx6E5YO%ua>Oi6#mwf)bs@+OT5OBwu+tzD* z&jChzr&n4mIJ->hUY|ew(OY|;^VjZ;6=xF`V~d`2fkenIGxF_p(6td^Sxe23nGYJo zv2&~EshId|up)&Z+FIejvFrw1P4^leFQ_?oYgwS$+mk2JbyX-F`C45CpxfUqLIYeV z_#Y@=uFI#8C=*oH8g+<$e03;kFt%3jyMAJ&y3xlzTEvkprkUP-l$d+zcCg1a$c>@# zyBni5$~peRQ2(&ENZhULT1hg}!-MRsoHW6(pQ6baQ6KNcM-hQ|lRhbvB4fXdF zlADAHpyd6a*V-0`sCcC8pozwJ)8O@!pUr~Zu_uJgOquZHLcA+p+gIUo&$(T^7k%UKtvq;X# z{VuN526G0$VE_x@HRuSA_4}(ltWDooVEb|Oe{-<2t8oh8&x6y3H{qoZ9}OR&`S}vq zg_ecqW$H7RvimZBVCli6vZ`8+c5g2%=>ky-x*VQzF&>TJcUGuc2@R`EV=##1){h5| z{D5MLx9YRqH~QYpEy8}GPUHMBWfz5;DtTjL-USREM{Hm%mj}HkSBn45b0)V`^DLsK)6dpVaT>s1}`sS6BUhUWc~0OTQrHFLx|>lc>-mtH%s90 zE@OW`UjH01VdPXvblW^>Ta%RP+%WL8G5&%f1{*E^WH;}qapNMXMOCdjTuSi9ChrRG zc3;oXXeM|@*@T%lfSh0$F;bW!;U?0Qe*}S}Y_bX@W&9D@U^64)AEc>~N8dXPIJFX?=Lq;-TwOQi5AiET=)iQO*adNdZ}y+C_-R%c zLo3UxbiS=G6c%yTltLwuo&A+pEL6D z@j;sKct9vp>%eHrW*2%+BOSLEmv?{C6x1ZtNA=&M*_u5jpj0L&vcy6j_IWlRM{5rKRlB*R5oEdfus19EhSer%iZ=bVvSbpSs|cju!?BIGECM!j z@w=WU4o=CM-Em>iTW9^mtbEREWr#fuiwDf?L#Z1^_)A}h+I=-f4Cy*C)uUj{{C7Gr zd(Ie1yoP3>@u|gCAL#}-U1HxuvOem(Z%fwGybI>7tOV@r6PW+S0+n>xn@_TmvTD95 zO%VvVcvA?`>XyZN8!`aBxv|vK(2dExjNe!RWMNC4EvH)xPRR}v-S^~AAU%Peq}*va zx=fd$X4{FDr?pIr%0PQ2UGVwu`PI%xKBeauYezw#92TroY!+CZFcNX+)pI7HwRb7w6;STTC*S*}bi; zI@YjH?CBRnzOh!U8>^DHAOpu!61<@yY=B4no`l`FGj=46!`$NxPrwGRc927nK_&v6 z&^+Q5)A)9lbKItO`s`20fkkIJ)LM{}HD<}B4UMYvR@zLTP(0|tnq26FQiPIUMpAf7 zKZ%Z9)T>7^uLGlt4^Ds|ci?=kJfc7$qNZMn@WqG$S`I7P&5m06PWnH8*|>-|CIax9 zIx5B$5S-Pv!oL$1Hr5?Dw+Y$(6(ye!40}V&Umc(2pS>GXUYHspuCS!PJepw;)v)BW%P_jmo zDvE1IL4uvP2x`$!EZ@=u6)rx*r_dwEE zC4gO6alQMLRUnt8)M!w%XOz@IXKdR*3`ucpggma#-y4Fd_LIRlAr$0KMmpt*TykBV;d|@$2;OdY&}REL{cQ!dKrF2 zoCpE0GZBTb##8kgC``=ERs|`+@b7oycDZ;{J}Au&=iG@Q!$Zjc#JCGYHmSlmV9m?i ztc6^31hkW)9JPx{xE}-RU&7cJ3&6w|s9;#tWjiD9_`3b=Ex+lHf7&cuyg4#XDsXnZ zIhw3Y&-!JpJw!qh0=|)GYARNR*vCNfpYUP^X!x&-OyjQ!WYa9!H0-qqt>9(tif!DX9VSnh%|*c|zeAeJDs4o1O>K9J+pQ$>SanQR#6BC|g}v4%Qk;!T@|Yx3^G< zGYwfQ>e@}*@Ukmp-HJ_+3j5UoKqi~dUrp_XO_b`+Ph?joBCTz}_alRIVJ2(LW~CTP zhraGZ8A}ak#eXqC)j}1RN0i1s@GRzB&`#r{H6{7K$Tc>%Q0h4(@hX4Nkz%UP|uDuSepRk%yKyS@CNYRLX!G#y4)oZM4 z$bX_bUP|r0(ZlxyqxA3WX^NFIl^EX$STB=MwU?9(rLulvJ}$Fk-I#xZ;V3u7eR?H* zx0-lMuR(t16Nq~Kw6~fJd%&?kc|SiU;CCk?;*93p^o?q=A_I+s@BNGC?G7S(8jFe}{`eZHHWG_=2tMw{XHAVQa(* z1RN$`UvTkjZ>E^<+N^E_@_xZX83h}#FeLB#yM(3XS2hxQy4g`YSR3;z#6G>X{njDL z|9Zq}4iKgQPlCzubS1O4knVG_?8D2=p2BD4`r3%Z3lzZkZ)u5^y+=`A8vJiu*g5xq z$j=zM5*asFF5h(+zP23(yr4>{AU<)3=>zz;1i)N^PB%@LD!PF?LzDvAU z*D)F&4mz=yX;hVm^RH*K`4YDOP-+6i1e!pab=^JeUts1$P*R-@{wvg zyD?b57ioUq%iOHFnng-IMbxje@4U(o)_{3i3S~$M6|&#dSrJp_^hsYX2S-ZJZB%$; zlbWU(`FxMvQf5NjDb+K4?J6&>DkXF6m`h>CPF`^)sP|*5N3PmZ*Gr?pT6K{+7#>{U z@7C8Kbg4E%^Kk*gdKN#@&DJWwQhJ<9uc;Mf8zrLpBHF;U96bVF%kwypx7e|8a=yiJ zwSMx-qF>@F49CJu4+ZPo^To~bg=JsXRSX03E-dQ6ZedQL6tP*ulO;mvitP$swR=^{!G~! zclV|^2HY7AcJFp#cP*=l{~ufwj@Y*t*-x;3+9hSurhoQD&98(#K68gQV8N4j764RZ zHI`iz2*vgcTXfuRc5iK|Hg=z|pfo+UEJH#7U92$A|N64LMWpjQ>?q!F96cC%7T{N( zzWpf1RKBKk6(`=Zi?v`HCUYp!fN5fBdp92Pq-gOoFg*W+^eoyi0{C%(v-QcQX@Ybo zc6BcXj4RDnBn4ezf0~g;^0>(b-%T?o352BU2Xoem%?F$A3&zfrAt)4SSF=V_YT8uM zvs&7yRF;!UjO+n6Hqwe2OL9iUflw2@VY^ARIS^(~_dV%qXJU=7bNt=EwPMXbY1*0v zt+xt=RSR)(7t8Z?NNZd#FF;b{DQi@V=zs_}e z*;7&Zvl0YCgn+kF7IQva+2CHRVp@7#u(&)kE%;N6v}jQobw0Yy*e@mdM4bS=4nCkP zg02{xf+O_3yT?yd!R~n%Ok@3B3kWqE(=3LskEMW^xYEK=LV`oO7x;u&M_#1-8qU{h zxZ?U@lNQCcO+!8|GH5kp<;sHhYvqQ`s+Rd|gk4#=o6Qd3!rF}}>YKXsL0%|^H@i~&-Y z&gG3Et~PYPnn^!?Z;gqGNuBbVHi!LSnoJ2z%LSPwPSRcd@#x;r^&W+!$N~(3`U5NK z(@{tIPZ#`wWp956bV2oKe0#X{!8ZAvX3jny9MwJ)+W<|ss7&>`L86@l!4zJtG`lcL znRqbhVQHD%`lxzbH3>H8*O%kHhwk7TH|C7xV-MZh7foz-hQP43;GO+uN@wHGnw8(W zup_?G>EK0BJ_=emdpXB494gihU)I>zU6P>C<07zlj=!l^`@IbI;TX$vQ1vakGe)Xx zE} z#$XnyVqd_Do@x$ElV>?NR-p9qh$FJfRa_s}-Kv{zhq0o$JNu-5jL&GP_DXFoVdVa0 zH#3OGd?p>Gn6fzm-edcQQLEE3taSw$x}U^G^rhtLgui$Mk7=EL1i|(=i}qAe?G)QbuRt z^%wH;P&~$6dUMLBRpG|muh_|M|DIv z`EJG(__BRg7U=KSgq;0@?D2w(#xg(bM-QIQ&IExZQ7 z&crb-+DPtg^hk3beNM;bx@y1-;G7z+MKm7RR0Z%wtu`$pYD<2=Lf@1M`uyde~ z#|}rW*3B#2__81vMi6n4o+jJ(6H6J&PwvQHcG{QaLytJnt6}PP_hO;R3P<;49_8&5dYulO}IAJL&1m+=-r8%IUOn6Q~bMgE(Olc zyHT>Q);ZZtT7x}=DuNoWU}4x)Zr@DD%Hy=5Lsrc}uEc5V34|gMxsRUsiF2#60Xg6t z!%Q#?l~1hRY2_8<7m1$&=E1>Y)A@fq9`0RjmlR5ZxYF zqD@@R^BQ=g=!DI8{^WsG7`%bVwX8j`)b;b`b+3_iLH6wkTQt;((d1=)UI_NN#aJn+ z$K{z+c(lixADJxnHDb+pWoMeR*ym^FZ+#G?X<^OeRFQMEma-M{x8%{^Fx0pMkIOO+ zlJPy%;!_HX6(u*hU4HM-F_Kz_8^KEOYebf&zijpNFV`tmmnJ1Yz)i({0pLXIU0bSq zHB}+tq<|u3Y6s%029a$6oK~)8ik6b(;N(k{nA<(H@L)A3mo!p=pOGR_LJ*G{>cbZR zBxkLCU!i4T5zb_FH2)V1xnb4jo^%2RMc}?zeDNbIAHiTMghOESS+k zEUDXMT*+ey8YmSC;PeUe88ZhryhdDyXfhkidwC{0c*}57%`}BvbgD4xs7UVDA|sT#wWfo;#m~2udjUNxz8Y$CqsTkK&HT9 z??j!4%1vZqwvXPUm8Rys!(!pI`@KcCrIUG!EC3L5gf&lgwWi89)uyWs0{^>oPIPV} z%65TJM9~4a6Ay8JXMQPfV@TCN%Bd~R`5CpBJ+3ru^3i)^)GGp`_ypaNbzZ{IaPHJb zlO}XyV~&mP1QE;-FqNLUrYI@zbxH2|P9kMy?&bT2(aeW#^D7bV`PeVqa6jnHZ+n}9 z&Fk^LSiZc`(A`Cua09|sXqRNF&tNTT8fzDQ44@(hli&a;U!$-6DTLnda3iC0G)H?% zTmU>82op6ttI}|d&aHU-j-7asemAbwML0=x68JtJX>jy^g_EYGp9?-5o0{-EIJel$ zfc;!+A+tQQXDcBkV?vDBhpk5SG{}p~T%hWJhzCov9Zy1)3kgI4x2v-wY=sN=3xM4Z zh_iaG=v+jBXJ3}$ls^)ghDk#m(^`1ZhM6gnoI-s1Y+-Zr-4*3| zK`O3o^hQFf2|HGJ7R<=;mKc1*V%bjYd(B?j+PuyW%J*TtJ|(-HjYd!%B7U2^V9(3_ zxy}BHxT^(>Lo@3zs%WJTbZD-M2z2^S{5u^8$PC-ocNK~J&Ze7b+GvNirGV;dHPb%r zNt{(>2o#{McYEcQb4|_$k>_z(SJzbqM?O|QE9{Ky&%po0I^iF`wiiHEqe&FIrWE_N zaG9USdrKH8R_yasIID?|}q^0bxfnw|x7vfr=Cmr|_U>v%}Kf#z0 z02W-QV^ICu0b^38It+a;Dee1-C_6BgsM?VcCcwi;o;3LNdp}|VO)qGXFI#X?8H>@H z-73XRJc*Xi<1m_>m<6LsO6>}dwNMWQ2BD35Q z0V%=s>Wtz)Uc0Y%+p~Myy?fiO`)it56b%lz)*8%ml(C!1&KPPD+UDQmrM~BJU-k44 zBN^Xjh>Hx2U+arq{*81!-eg3|4cFzD^J2j>s!b(1o5*n?7UyU=QYL{27vkeH3(AVY zW$~nD`#JIhbH$Dme#KA0w~WsLey^<|D2eEx1%BAnPk_q`dEg%7YO|!W06wO}Ki@xtowFIv~2Q~7pmN2AhJW#(hmZh%mlFPJ}E)UK?e=3t@1 zjmBF+(NIX3KQFLsJ(|)j24B)oI9>+!}Z6 zq5eclDy#ibvn6|GiHc!0ll>9P>}V79PRx4i9!#c*eZ-Q$75G@7Lr8x_9tcvyW)+zFYYtIKCW%t{Acfy-5IK2!tX))k4;Gd%D&Y z8j!U5rK&xr7TW{6VOv~)J-1>G_Yg8xw;4;^!z-qS6fKRNwV;2ERb2P2I8$0e8NVK( z>NrFp7nsHXzP8#-2_8-7S3HEG3ol*RY=}tsF28F36nRG0m35dc5m3=oJW(r7I>q1F zb=8L-cs6PRyDf-?vY+CGzHt_yovCirs;Mb?{sDEsrSpuH73S#8tX=Z4p(1M$PMRQB z&~7)I-hCtVmJ#(txFnr7`=-j{lU}m8+-#Ts0@X_kL;=4||J4j!=cW()IBOqZFK@qC z#cEnVOWXW9gQre{Au0CK(OQ8)Q=#yepPb5r{n&=1yZK8F^#1o`?E(n0lOk_@Oo&Y8 zuLJzRj*WBJ{kg>d7S$l5#+EWHm5;+-!-TPHtLuwN`|&thxxr3k!N(r~sh*wy7sS?= zT3m9hbdT+Od|g0|7{GP)x$Je}@UjO(;3WHpps{`*|i zYCF53{4iyYOM5&-44A87tKA3lk?A1m;tr*}W_{F_U4$>Siv=1$RHi$N|5&FMUQcCwe2h|J`TjdU5{FXO%+_6hqiz`6}U4%k@br6VI;6x65ay5Ba zJhOIWn`o6os6V|OWEedB)_$AN*C?1jm5)wd?Vf>=2X_47(m;)QfV9Q};%*q$)eFAh z$r?q}P%^}@Ua(SsQfjRF|Gbmbwmq>snQ;ibI5pjv<47COC@C$KDf|oYgn?+ zHrz(^F8aa#q^Td}PN|QTYr;pqcoxkA2$75$*7~*u$!?i|rw6lkC7x+M7yqdFC^hZ<9bdQ7hQ4*>#0^Gi8lL)O{IA_M-}WR{QCXZ03YD6k<0xhwSQBW z_lT}`7YXg_eoMq|Ldske4&pFH12;u{;(1lwhA-<+o{*>5dy*-?g>>Gw{<^EtOhC3Z z=vMWxKm|kZSGbNuo-l}yNTvb|m`sibGe0t&$OfeXVv{FVO(nkq;oq?|Jtkh821uDy z9QdLcp+OA`_y0Ovr;?LCX+1uCaeH5g>tHcc-LL6O0#tjBkv8xA2Nt%cD+{$8mzlqv zb;}mvMa>&1ME~yNbjB16O_5 z?t%g{H@z>`x&EJGWZ4E_(ag#WJ@Pfa8B!5>(ngZjbz~T$zg=@hWjNOLh>zd|p0pn8 zeR6fPf3u&D_0s8g&I@&cJAtz;yvA@CKL|QAN_5E5Jot&S?}!MeDwgQXwC%`qHmV3+ zb5UCI^7Pd1%{CquLl3=E9nNu@4jKnOXatC(zYjS_=Q{-!6}KoojolE|m?K6!5lXf) z8?FUJ?^Q3X&br-{QjFqC=W?L4UwG&B&5rG=lO1(|bB-QEfez%=^-s9nS&3U|zzx)a z4JtArh3E4hMs&UEnEKPmD8pmP;q?#Upml#SG@KL;7nyQuis{?8S6B7u)v@LR*)Duj zpHIu~$76q?kSd);n}`E! z_KC$eW8M527(@)r04tr;I}l8CZ{dx1yzZRT9rgm16ybJ|eelpq@e+HC-beo*R4|{r z7y+f6@d*d@0~`boMF6^E)c`V7?RI-+M1(L|6ue54JzfVOM44*;vG55jOv&|@a@t8z zN;L0)zXtVz8|PCn~2)|@qX3zuxoyvuHA$LG#aG$#C}!s5li%ToAeWQHcQGI z?wf5v(1EA493Ab3x+Fdx@NSpN-wlPI`@bjJQ#|pJM|wNp;;ilF-txw?#Sohgg@#U6 zen#8AyN^==5+>;IqMS}8EL7kTy<~GB?D{{4fe&Az3rGQ;c4EB1v9GDDjt)orHCYhx z;&l%zdNTnNhx-PRso;kO-DxTOR~-39@&)22i8jlDr!&NP3QrOOz(+?+NAC&9#U~G^ zgYC!fZNa66e<^qz1az6}#j^E1s*C3=ngI)0^l+u!gh=yYu1fQt{<6vThG*N5h;=t5 z5cqxaGL6-qgjYn@HB~z;pEiw1bvJw;NQk44 zz7c-u2dQ>esnB`&EM4(LB%fR*17iI4VBtf``9sFnt}rZODmCH(hhAK^n5^dn3_?%|oCLcXv#QCVxPcoFi^)a2WZQ^(loH5i_FKAZP3}5c@ zDQ-0On%e;|5LZL)E}PNXyy`}Hzm@f|21umFjP@(gAe!Lktq;Dp9rg@!L<#~|6McjD z72_iqJ{@iu%Kdt1FxIWYP}V;hcIo^>IMM>l2&zxjiM~VMfIM0Zm%43aygv433_mWj zrlpcbE~sK#dQI#vU*-#rbXQ6YA<#vPG-Fs%&TD`ydaaMzKwnF7bp)S2*i*WJ<-DwfLf-!=iQ&5dg2w=hlz*xoY z>U4dz5>ZF`h~V-$Q(q~++@G!yau$-`$Tw-D= zr?-UA{4Rtb_H19*$4HO}K01B1LQI+aq>_Rw({(iYClm@l<+l4DcIM{+LcR!@Z`&Q9 zOZ7~P0cZNNX0x7lH4P6eO32F$dY=j{jqZ8zH)x+vFZuZ-|F2DAgQHl<*$y_Q$`&+O z+)w@4+=vYtJ-xP8lz(`g>+?PZr3j@)^y)yO@#uJ9Qb#j=3ai+>9Dj%C zd)Lv%#}sBiDs$hIY=*o9%>(v%l7y3w!|?p^!{~1N@?Mvf}m;Y4X%&@|@nn2e^-Zz1{?~^fm1~e(f7L8^Wy!b!GHyb{R z*B5*KJgzPw)uib=Atk9j3%0b&T$NV!vC)c#jrZ+wA(R}_Kl5-jbp1^3@5SJO}DS39`wzG^HBDi{`E>6 z5Lg;G(umvDySBLygt!em##+csBy5Z4z2PMhW z5dNE;SJUt-U!@ra$-f1I8qc@U55wy)6?aSFflpTj`Fn-Av7m$Hp zK`QnQ{^Zg$Rvj}~5HKPjnV(1jd3$>zs0}PFeU9z_fC@4wH3{$zd_=i3!Q^4!l?OYY zOUX*u53k_b23tq#jnnU(ZRl^cia@70y zye5Q|DxdqbEW}wt(CR_t8nA+08{TR_vyj9WKt+IniL2iNk`4jY@SePsr&SO(_b&t( z*>EW_5q{z~<0ewC^T@81695Oc_wYwqXKWg2k@@F`DLunIZlYXEBW={||(f(e~%~KE9o+S*g)0x4(#g8X>!a(?FZvtQ7tK7oI;)+ZR)>uBDnFcbii* zMTR*=PN*WsPqW;{y|_s2ku1g6jWbQ6g#Zm_EeO#7>WU*b@cfgE;1D3~KG4WO{p7+%*9l!3TTQShV z3PPPuvwI3tQqIMcW7T%_ZLgy;#IJ@%|MQ%bmU?NOELzM_=#I#BZmMR~t$H?$RQ1!T zV+uOWEBQE7_M zc#-|4(-&^N^wT6rZmUPb!hF*)AFmby-WFdGxkg zHi)~qFjCp;B76&fg0Y3d2w>K=!YX=j$EKV8&1D9f*(^ndDTTt53Ch7A6G5JE4mxv$ z9u}$@#-PLSvdRszTG}c<4BAR=+Ehz1C&~bx1f9)265CjMhWVEB2w5$%qWd>8@S1{$BNboU88`#NPZQh2hFy0D zYZK%%Z2v>Tzkn+5L!!l8(T|vQ(3;e8lJT=A%va7GZWf zh`CWyvFbB+SUY0dI_{~RZC#Z69;ZnE^}81>Hz5d~D5LPq9a6^&53RL_6AfPi$y7Su zp8o#Cb1^V{Ke<@|*jB&Cz=GU~pfv-npuRsjW$}CCn&%35yEko^3wT(RwLn?>V>idl zPt=%$PDB`cZyEJEA8enlYZs#5-nHM}N4{}XD0w^yjz2Il>l(LZ$9y}$#1gHgbv-q& zhmZqZP9TMXsR+y_8XZR)EY9ctO(O3!$Eg5~`|XV#W`Z)%1ZPEb2;InA3z16eVwc!+ zeSxXNokj~BcNg+%fbGL`mX$K@`j0Qz9mr{u0WBMQf@VGIrapronr&zG{YDnxV~{&` zMx?(A_?@s?DfUDga8Pz0Mr4c60SW8zxFaog`)Q1z=7c+x-G)b#*?r@+iD9GDl1?-p zC{|{AP8CK;Mb-QUP3F!tE=}zfZ z0RidmMnbwvx*i1=|o1oY~vskCb0_EXAQbJXt{LQ-A4jz>ElRu21LuNKa^lFqPIB< zace4(j4XFC^EcHhlWGzyn})sFnVIDC>J-@SpYn3PJ|~8MPTycq706IhV+ro%-nTAu z|9q-U|2HT+!?h+LDnCs|M`&BQykUz^>ptMsi`e5W)noG$vM(SsAJPq`vj?ww`^$)9 zw==oWzQJO4mfB0Zxh8|)ZWWHOot^OkRB5RKZcv9r#>EjKKi_ehxy?KiCsY{1!dU66 zaRwcB&TokXv(F@nOhm-o;%e7p9XV5~QRjR!)+UF7$?nI!A-12jhbj8&7=5ZPy^FCX z_sWJlUZP(elTY~@5|R1TVWD{5WYOX7?lrlsY)Et;y@d%G>iya2rWOe7d?&*?af$%M z$m$MC8I#cyo3a1MeNoD`~jr388HzY3#gWNU4&=yiQm7P4fPJiwV#x|GCEi z@e}>n7C~CavpOB-v+v_0Vv-1v!l63R>Xra^^F?gWa+hIbwHn<1Szr81Rj3aAIvMr;^L`m z0EZj~Ar7~WM`c_N8JReBTrG4Wwx}{&N9ejfVI(uYTpS%W>et=ZU@|+W+$rA70=rr0 zPw!~(UlV>LcYQj%%|USa!DJGsIu(5RP@uMLH#?*vfBoM=MuIwU1qpfI zYqJC8X(mS{ifyB%5FoNKUv&oZ8tyrZr5(h8cA&Z5$sG@DN41@jsZHJjY!3iL$G5r# zsC37-_*a4{t)WzZCzajd@kbK=Wjk#;r;OYfAiPg+2{qw}a%!kw8@X&zW%uE(;<@^% zLNeCN1=a%Kg^_$R(e=t?1@7ODa#*=VGhV$Y(dk%+5#GXOnYO=GWi}r_oh+T?@I};P zg^qG|4;-1!kx#9h*F_T#>rx2n_R{*Ot*HwHbfPVh1rJy|^O4nVI5WRgTzHQb4&oS_ z5=`D8Ul$l3Nn=zq237(iMRWac{2!B1UJk%`fACwax{5ptUk}OORhTIP3(+v{Q@~0Y z2pUdn{Kn~N07$QyzGp68XAh)o!t6-?TVT-vP^Q5T&J9VtkEe>n= zcsx1$Pbpufo(oEE z)Tu=eW24ERCzYBBViL`*-{Z`~P|Yd86?GANr0jno&5+K*P?UF?c$AcRSomeIqM{%w zN?{e0>VerSVEa%Rn~%kOMmbweWO5*7&Q=R6k%>mXW^;l!dbK0S5X^f4()i-~u}SJCQojC`TV+?fX#MHNkY#z;2nfe;rW^eA~v?i06p4-;2&ZdmD_*QSse zLv8E;wzZAIE@NN{EeUa;bq4!kTwDJXL5!de+axY`3`2)OFfa0!Pu`%LVL{rC1aGL* zD9PY^IP4ou>B12cWlsrlm}$$4NW6Ze3CjL*w+^B&+T7D`smoeY$X9JfWQfy@YqhE> z`}-~nGFXKSu`k%-f|N+^EXOLpDY6umQkvm18_3`WTbX%L)_)%s)R*|eAN&o+Cq2M5 z`Av*7O4rjz5Cf~zF%c}HW&W9AAX&@)9-{ga>6}}1>++5BAQ=T{_f?gAANT-2vDbFy z21I6(&3L)yW~4!XjX?;iTs?~@EHG7O2SrLb(CG=^-2VV(j`)=#KOP(@00**a=l8}6 zJBTTJb`(&2Mg;JzN!R?DT&I4--pCAndy99c9jM z8_8>NfBa4GPy(RrOn#*Bu7bjZdwRv>K?^m-X_10>cka>>=(WG$_fdw?h5}VN9$dfT z;?jeddBh|5d>7MAD1e7wv*?gX>6VaENR2i*n!x3>na7(XFWuTIUnnz#`Klsma@V48 zsWEhoiMB?x3Z2da=2_c`j7uDL>{1PkEN4CchkSPCfP!vn*lkni>;xJjj91b61u7^oAS8P`WG2-M-uK0Z_=3E8SxconyD^0d`H?wo_tuj$2n> zSP#|%xZ|)ozTJ#A6gL%Jo2O~ebUw|{xT2Q5h*kzwB_ysViCoN)7@1o-_n&?RmcWA1 zw3g;L_L4wGQ;i&Eul=tM`zBuptHU~z$9<7RWn9g%G>qFTQqU>+#v?AH)4|7k?{12< z-f@tiNNR8F<^&G{6V7j~m>+tSHf_C&V#Y^-91I)41qvyzaZ&$nfV?Ww`gCPHamTL_*mOWL&k?f{k*Fwq|vE6DGbK zf&hFNtQ}iXC??<`kh$;wtNygs`X4&w!O$L;vXR-v(V{~?vZLr6{Mbp*)7BAW!-lyg z=P@lC-}TLa$Dzf#=vdfeXXUQ!&p zazTn#Sc7*i$REDSnPWEm^oazhCk5#7sM&lPoN}Fy08_SNZRLnr60AF6!kiF=m9rVy zV-KV!f?%_jS{D3M{Va~XvnMN`Hm~d#puMkO0bGoD^EZSI-oIAHuj_psk}^r+?9qxUY-+Vh%gH4czu}47G8O^4UJ!OI} z_W>h-9T}0}R}ZU8h6nLe*@mXiCv|^OU}6>l?-eEGHJRc|E*9PJ)JGK=*s&p8U||g3 zm@&kU3i*snHUDRIYxP+?Uou$oD`-id6KQx#F*i}b zs1IejSf9G~p}z{=UJfeMB# zFALba!4QL$9$0E7YD*_hgnII$A_q=d%N0SVE+Jgm-FA9*2R!&JQxzN4|4#whWq~}7 zScS6R7ff>1#L_%3;Xn0!OLbG}iC#=3KpcNMkyu54po3h2-E1zAg>JS;V^9M@5sSs; z?HACz4*I*gd|-otR!`K_QqVN~qYZO4@K(FZcX8`<6=rn+1V}zp-i=jtPr1X{sa%O0 zc-20%C-0|JoFD?^^aDL}RUUS>8F(KlMH;cVed-c~@+f6lpQITEq_-a=lv}P@kqP`M z8-x=&rC)3OR#XON9$({8za97Bkt9aXq zu8*%A}R-<+n1dD!=txI)()BpiCbyg(HM)*~Dp8i&Y_zwcew z2wS~o+%nR-^;NI0F-Dj{!IsR3g$ zZfFvP6sU0cn|zYCNGr4RJ!a(u76Vurr5)o&+JT)x<=>O+jEVBP{KX8~8e;A2?CP5D zX<|cbzWoS(8{>Thr}JW z?Cxn#lANB6DI}Uax5KG*;n%R>vdVmCkhb?9j5wv#hWV3 z4yG%hlVkUr0iex4?EetS_z$XB%K_*UWT^{-sij><-X~Rj3&YeUg??zzI%E3JB#?SM z$}vfjfy|Iq7uhS{mKt(fsXj0I=hM~GO>`*d0@TADD*8~0kscICs`oR zGou3779tJ(H|dD^G5zJkBR-sh{FmmLb9W()Iu~xpaxkf__+xV2AH^PjRaJY8tU}r6 z)17O^?vMKb(s(##yj&A`yxbaWpQyrs3L;T8rNNc!{lyFZxsD0}kdDX$G^7GleVKP& zl%+b2@Om+6Q%m!J&~v8$X1QK!D>HXf5#@h3owNEZ&CH9 zI5>Kzqg1{C5aS9M4d>F%6`4Koemb~O-3DCrhKU-F&Eynrk=MSzC_(R|TVRN*9Ji~l zy7JcuM0YHIQ3%lbaRchoQFSQH(7YPFfE0>1pW*hoe4ACoG1>MGoe~3MQg}hAuO$7i zChwni+|Sbo3)SvRxKYv{hYR<&w?*mj`jT?Z5w8`0cGE!FKC-3nZoSCPOY2sPkKkT+ z{jdnMOtoVb&7w@(Y+;*QtLb%1kq;3}Uwc(1=>;NwfWkd6F$4sy%e5MB8Fn{A6FtK< z*uq8rux_`xusf+FyR7~kDish&aHEg07~c!iK9@_0Q_J4G(B{cnYxN~}oo|3UqTK6Q za20}AYayvP<_u%iHB4b+J%0C-rN((M_!?qIk7^t^P=iE($2R8f0P z=A*pmaG?Wqu7Pi>BWs6rMvFirL-@q~Yi91{#+-Df#@~KMt`Y@mOw+Z%#IwE>rmRNe8 zjaYhR@O7RqC4)ldhK-}>IySzp0Mk5RR}G>xu+DSCtJh%(g~v)*+r+o>+b<@0D|WfA z(d9Xjv@^-82cu1nG@ZW#52Ht@$??(?V*ejKeA~-ML`@%O1d;gdNTrntXt%^+IIR9R z-ncpD=kcIe|Es7vv0X)ZXVR?#W43uo-p^U-Yp2mpLbUi*1Sxue$YL?+O?hGA0S}_5 z;hx9X`1of~0%`ZTZ{|c+TD@bIl(e8w%hy2Y+wOZ+KCi}5f$T@^B62ZpoXpA%&)3E_ z@C-7W$j>OSb+b4<9SZ(xk1iH{RUX~%qtBfrFr&MD%5rVFWNyguN~2v*>zyN3>9253 zj;AX45ez}EdD%YWJL??_qDLFs-!hZJp3BI_2Ca4GmIcru02&Ks|A6p@&6O>kPy@Mr zyvmg+Zxslp6sjUzd#1c8(#-5=I3BpEH}Gvxk|~qdz+*r2=pMiv1ap)v#IExx&K&r# z&5$)`ZR$|afFkr)8nhWK%uZa*8tZrb=e85D#s~aYfdO?6*f?Pf)>w031n#w9RXYov zdmmnWFvj;U*+omml3NB~QpHE98wWa{{H2rhpW?9Iv=9JeX87-H@&_ud44wwR3H{B#2@mF5 z@19xr8IDo>KrI_AC$)Q% zGqm@AXk}vlM}A$+1Pma-=Di{@Qm+XKe5Um4!R=&}u9IC-nF_Fz%G|c;Y=?b+mibbV<+w`Chpxs9N?8Z{4_Mf<`nbV_!iWc-=iz>O6aSbJ3 zE`Q}r7A>AD z>2cIt#GUlP^fLA8IDHC;yF3Y?MNX-*td6jMu%0sbPeD1-hCAJFLCXXAl$R@qp$TWFWjOYJ4#Oa#miB7v^!*~LZ5)a9#e z)YHcEOHz6xZ>(Kw&wib~TQJ1~?(T=vqyzx^tpERql3;|FXGnT@Kog_FTpu zis=f%6ZKnM#0*|jGn3O38HzSmpKFfp?(Pb+K?dM31KYrTA-?R+{9KZC$&f%1&E?@O z5%hWP>@t4R&Y%9>ts?tr64J2ti05BSadK8PIek&bo?~%k@146k43ke;_KdQ&$DV-( z=;yZtO~>OmluuhdXRj7J=^jFPIEMhv9|2AdIDZ4hSH}d*EYsQjkw?=_3tFQXZI-rV zOi_sYe2v4`HwYFv@$^Y>ev_Ywja9-qUQr9o6_5-D9VE4GBxvRqTBR8h<(ly0hJ70d zWaPZy+ykC5jhf$3xLPX@^3Iz{If1)3YjmiTm)c)K(D`#lrt6A}rCy2XFqDSR^BtzY<{M*I22 z3HJFuYJ&0kCqg2z3s6*nmI9Va;rz%+WtSz7AdtcR8hw$?>w#bWpm~ROW2%edx?g#r zl|JS1Gi=+qbx! z!`e#R+L{sEZ1VW0nW!dmf~v?ypV`a7?O)-^`IP>n-Ag@zqha&qR~+lt0s^uOlP18D zMRTuFDvc*$M_e*lXU`K@(Hcu$!Ef1cA8DqM?JH;L!^))@1aAP1E&=+iy@SE+nP2rO*oMci{=l5OIbh^YWn(B4C$~C z_m#o=*PBGu*Je=>lgW;Wpj%+M+ejp@0xA9O?~g$6zi`H9;9p8h_s~{#C-4Ix;2Q^ z?AzLajY@^XWLc+V#%DQ65KkMyY;R;pP=@3~k&q0e6j|G@UWyatq8`X~%qq>LnXxos zXI@PsxaFO?ds*E=m)$9t67|J2_of~?>3nftvT%FwpNrN!)evf)b)%r9=mFCMqLusM4{n2}6YcJr;L65o2jglC1= zsDj9-BB`P`s%K4;M!~Gg)@R=dT)PtgciPF{%E0tM5H>+5`}pk-_fgI3J~lZ!GYnuR zl~qzQs7d}4eW%-phJtst@x$b05XgoBQxl4)dI>kCmedtdohg+@?;Te#c2wXQRC33k z>w}f^a=S;A0?c~QMF370%G2)htqE70hFcFhmOmGAPx3?98}) z3A~}*R~#4{#MrQ;FN-v{k8Zv6#>+JP!J4O=-ZOWV1O&D^$OYl!!<=Tm$o1}+FW+v(J59m>G9k#st(|S{9VNn3Rbh+mQ zatlODvT`ctsER;VEVEib?`HT-YxOP^~k_Bt!Q z#pGMk>ttZPRlN5e_<_X!u57^q@Z9`e9r|AZ&CzBFdRm_IB^rYwuQn3&A)U<*$noYw zAQ*Ww*=6T~reyfRNMv#P5pLH?5FjBy7Y*z_Roy#8D#)$8YFy%~wEBBpWvxE7Jl}@> z^=Gw%WMv@%yLR-M;qYP{-;zkBfpk9@D8TxSKi z9IEx$sE`vw`~W%wBMyK4mgDdf=R_2RvEZIXstWMRf%cAzF&rlRtnAc z0hZLYS+zw&aJq#|9hr{CJ>xvUpwp#kOs6V5IP&`|P)bB^B!cTqy3gGkrg! zBLv#_ro73n2m8|$D&nDr(-=89;S#b8eG3=77SV6h7kT*A5wK^1 z20tujIuRh7f;$Fp1<#F*NKv=s@(fQ3dH59Ob{BeQ#>%G}@ZybzI}(->9(6dpiDqyP zP<#{wnAra|T!Tg3bo~tb&7ogIC5_NnG{yh5&VFw3ggf(Qekv-HP?BfCP2z9xp^&Qk z%~%s*S=`M}{h-y$hU3R7*R2zWG}DYWUuX66g_8aXX6+Vo%8E3EPyVL3rHG;R!EO8R zO$gvQq1ef6=mKV;(DwvpynaHQWYpBL)a^h+la~7P=NBC7_L1qoPjHqJn7V4$B|hx! z7g;?P9Db-{(#(J9ymxu;b?0!NZR^}@r#^AJ?Via?pg?7q0%b^Bm?3TlKAH3NZnQbE zbQC^kZ@1Xr*79^3+vJ{*y~tzX+1uNzFoXuTD0^(f2l~sW^88q;VJFQKk^d?xiFx^F z9Agqfm)z!^QZlB(^F4rDyUwYmt&m93?>sv@T7&pLwdzoY3@7p$0qtIP- zv_V@;aQCy&o@Z?GoW?XN42p3Kbj6mq;jA^n4SO%EGW0b=9NTBd$tX@DI@j`q@CQk5 zR0>3z>anJDPW6a_qhHkuMnp#snPf?aN_rj(@eFn%T0tgCgp4hrsYR!yWZnK*d??*QfW;Q^1P55#xr$TF{D)Qr_Ir} zAJ$JhrJ0LqPbqGgJ}9d{E~E4%i69&dDP&MwS0M=7Hlf5DPK&mCI8}G(ia!b}bO(oZ ze5>;WS?9@(?y)K=?4Md25LMEDiM*-0e6DyK><&Y@4)S6a}wfrejC8oA&Lpn@jS=3 zuoVt;qcKE5{Ysf zMA_FPU_cYhK4Ex6MBlq2`5=vTc@5OF};EsWHmJj-j{knHZ&)D(%?Ar zb1*1Wh+@Pj+g3Z)u#128uHLI9Kj<1oRh-t;*5>5obo`{|8PeotVi6oTdgRkPnzXMo zx4UK6fEo-Y>Fi&q>s(EI6rk?K<&qD~E9{+RGHPuPi&?ybYuak&rM4wGe#vRwL_uzw zh^DKY#efUgl!tYs!?!a-rB47U#r)3#L1NuuWNcOS_9A(T4u)ns*&zy&*<5cYZsY1+=c zkd?m!l5|8Qf6W0ZQ2&s^=x{uuR8R=7TD3Rz=7ZfA^J;$*Ncq6x@ZY^9;V6Yg51*{f z<)^3UcPUSQ6SFyEP)|>(%W6-3$(RD+$#_CQiR~k*S>ixo&ziK1Ibp_IZ8!#k|ZmVf|CM=^#gbY`({iCWS2Ias=)fH|iB9ruS0BUX<(wY&=PSxUJ&L5juf8nuL@T z64t=Bh$1IN4-Wz1PiLA%|gggzsW|B>066c%ux37Qh9G{?bf@+LgU}+%;2Q`I29@b>AR;`z=qMsG~ zaYm9YBYcSSPsz^gjE>IwZO?^E`hoK19zCRdztS3~uV13=C=htBJl?h|q-_--?=tll z8aYNjQdQV>OIT4U>gx~ti)P-BD`c6;6XdHam{8GZUugEaVcy)#$ozWUmh{^v@qA3> z>x|lvzk7cI^K`i(^qVjb7G6QJA1qJ@8Z^hvzYeatuS5yt-ezWLa$SPEyK2!l`qSZl zd^?)=Xu$vgE~=*#->)REWlk4Xi5H1&`l|U*zYE}Td&x(^Gh_BJ0Bq-@TBYF zTs3!p5uT?65^F@_NkX0vp(6byzNhSW*BetfF*FyW0hx_5Q2riJ(2I!$T=GFbFr{euSHC^dUy-imm zU;*HuA%lX^{^||+qMKvP>751dWH~*pndsPX*XGTcKV)yJP1F5Hrl`CsfiLWK%!i}S z%W(hlu`!0&n0#d%;vdVNEY%e-%`efTQ-rQ|kZo7#b`u1CoUvwLT{zI$AIjiHNTqmS z*3zCUw{Isyyn~5}xiwSN>mcJv`P03_W^?m{Zk-wpHND*47e>=epb8^ETxl|h8gozG z9T;u0{B-&&PZG`m#Rjr$?faO0s&{K6`${L+qy2KJxeP8OI!KA*^22BG>nF%w&mWi| zieD%@lB<}L)KtKdgkcyi#Cm*&TR}}Ea7pmQQ!=M{hWuJ8Se37JtBO^`R=B%t^Z02% zx~>rPrXAco47wn@qUE)fL#f z{gGlYNLMJG>49gY*S=}2p1FVaOIo2lDa2;J9_Po8AId!aX3$_vjYgM`ON~{p6`?=r zBxYqy*Z8*)zScmug-Oy8MJe%IgMZ3td^T#tnbF#O6p_`O3DBeoH{bq2CUJDcs7o8?lp>O2M3 zfTbe|x^34y4-)soMJ;vQ2a3&MWfB`0v zWdFs5vBL^Gjl%g;&z)7ICqeN4PrBk}D!PKi&o{R&Mrx1Ef5tV8XO=ehOv zzOmi9tjXv2m%m?r2@;Z7tTuzVM5XxNJ`l{8ThVVO$n^|TKD-D=JFW2UVIh0%g^`Gd zpYuj3+Y-%5KG1L**xuPUf-=q4ZJq@L74Ul;;lnwW3^cKH7`lP<{n%2B&L=$IGnX2V zAP?t!OB3ILTd)Npp;X^PZ+BNwPjAt+!9e@( zw9bMn8at;o?FRR&y>vDW=tU|-S-8q<=Lfoy#+R78CaM525iemZ9ZP=_htK^gtlE{> zQTa4)lFVAcJyxz^S@gKVbTr$+TxD!1<-2SxcLrXt+iG_w*CmR0NR-#$R>iX}1xH`J zCki$*AI12BYPkIxPt~6*eE5UlDQ+5{1KNojd>;RqIJC@mE==IC37vQG?AIwgw`}RN z6x(YOH4a5iqxhfC^5=f6*oinFWQmM`+C-L>va7Fu3A1jlJn@sd>TjTlSB-_Fe|?L# z?|ut`oFU&jVHV~YL46>6mCu&cv23h-NQEMH z5A+WAp0@ILr;)hOWJkO($&)sT)RVAbFC6U*ABqP*EbG=AsWf5lr@^JvtazeyMCI1w zSKb$W3Ju6oO43~C^b4avM(eLil@MlMr9m0FaCwie6&VfT;BO#oI40a7Z6c;ka5HaUoQU;#{McEJeba9_To_vSr8A{87 zS;%kn#q+Z>7v|+5zXV!(Rc7)_)i=5jHLZji>Yke<$M%7rbO?vfw<3C0I|$9oyCKt3 z=+k^sIy@g|KaY-%7VFV7ID6^AGTho}w@DUlb8LTik#9x)ap*Vsw#%I0M(_QYC5%Zn zjW|`pM%y~{2!f#l-ARwg08;v|`vIn!(^ahw)9IJLLU1n^uY$Il@QZ?;rz{F+AFTg0 z^D+jeoTKr)%cYO^-c4ouB;a;XLC_C{ld-=tNs#3Z8?^_Rrnr>nQF>mIx4{w-0keKk zUs;(5Yn+*x1H?2FU;o#NZ|BzCLyP3gR*&2dVe8?jwu!-ivGg6|pI-OH` z%K`ZlmBpVRuK7#8mkX}B-@m_LjKIq0uv9D4TUfH9v1aaP82r=W@{HfW%weUyHH3-9 z%i%_ENdN3rjQWo^{a=gA%6fJuij?&9d={&xdMUosGcxWSUFl#o{`NE#S&DPGUHtU_ zq^c42D57HG1-Mu1m!hip1u1B%s#I@{3FjexZcNDi9p#+XX>h#_Zn_5%n|G;??Kg>| z96~wy%ySEii~cASvyr5BH)I*bJ_LJ*H?7mxo3^i>iQ{#dm|=IXS83$w(#-^1tGa;oCOtIMzS54?d}LHM!F{u@PCkTsoDJsI4;l1)(71Z-ZFkZlB#B{ao;a)>Y3yse|sshz^ z`qko-p|q&1B7qbi4vGu7?USRPR&9rvySQuh)zpwW(s&ftBrSEV_SI%PN<@gwk|9b? zna|Wa9nZmdjam~NGkk>}@Wj&R{D;2B>f485%lTM>kL*J4fh=PN!6D{d} z6|S9(R7XD+Y9%iB+V2-De8k(lwO=dzu_d%(q06}_JRVv9)9|n<-o6n7)XsQTI zNv!oV3zqP~wTtfS>vJIfg85QZ8I(wcg@rB3@;AtqlM1ma7hxEZ<0f;$MxuDB8y=c!l_U*=UR^C$-^3HwGyo$5L!Vkrr=g_H9M=NqN(s zg9=gn4^&7Xn(aL{nk3nFtl-~wGVHIML=R9z61dtr`+0NY0c!zBd2Ktx@fkt3jt1qY z1MwNW3pNO}-Pf-E5P9uSR8@xInCoii3+jYpiutqh9E{zLl=3yJ9Uu_zyRJPe|B0ZO zP~2WEeBam#Tt96V8t?%$*v?!xze<+h!`P;$tQ@$zyNixw@nNcQFXSo&G2eGEL+Cc= zl9hlk;|#&OwtqUB9NwUuxp8i!viRquWjfZ~kH4~iCULs*85oorD)CYh(g-+^XSiVn zjDoE@;-EZv!NNh>0FPFJD!*Fhk5!6a#f{{3ycFeqQ0K9z+>oKHqAK(G3)9{^FE5~Y?^ez^>Lpvx!O=P()K`YPZ4{kfwY@eSg~8-N+|ypxqx($Y$C zD5m%cx{LA2$(-6+0#L;TB8|Wagz7~Zn!Tpw6go=rTbMP|RP$43i!1YH>c_3$s=8^a zPeIBdE+#(jD$RRSzh;*JU^^OWuT$-%V8iV%`0gr2qCf6-E3BCG8;IidThVVXC|kAz z7s5T)IUuHk=aVuW<_=O*JCLDtu0MD02^+@p45L2Jm2_-y<1pZ@q!NdK_Q8w=PcQgh zy^~}zoA@#Cz|QAfS;uuS9vcx3;4X*07Mywb1Z`{1&=F^%;HQcGesc!_bEa(@Fcd~b zD)_})Y($5Vto0Pu#W3^Cx|o_2bWEZ2Nv7J)?_@7Z$s=Af_xdTj|6O91xc{YEJM z1nxE|x!6)I!m_t54<3+$dKngZAD{sI^ZNl8LCCOHL(UBSYJPOO?*V>;q+cO|8N7TL z-+O#Kbn*sL0Y6DbKP{?1eK(xX%)G7Ec3n$4Yt%1GAseUe4qN1P#;3*;q0&Z4?A|2v zES{!p5>r{0R(3q{pWfcA!+EvwdOFX&f2D{3iDkJXPhAdp$L4@E(Y-E^-1NH?UUA}; zy>c+R$^02+i_J`>X?1HK%dJ}=iCjBIN;@*)v$K{O%}QUbUok9wK@XAy5ycx*!fSlG zC;}SF$#)1QyL>{+xSzo;C2`LV4&uOVp#nu_&n}TJub6jnxRBLv@6u?`fCHIlP81nN z$=sxnc{s=vGi!%)qC5hG%x+h-OZ@@gaTCbmI{&WZD#XwBx&FOI$C43!aq)isA!f;b zC{eENJI=-2Cx}9xtq2f?bC{`=y*=ThjPhle390%sLwt@eBIcXUC6Mz zdzmky(tjxZyqdb^q&H^iv#Bg0)>Y^5!yxlj@32qU-xzP~a3+b^4U=OfvQNx;>U9TT z9}R-NBmOegz)H5%NPTX2nTnh4jYv20jbO>sWZ#LOYhA)Pf08Kktw$8{OgW}Ad~{g$ zwtB1$&GUY=65!y-m;WRvc6jJhB;w$pc$0+M`3x1v%V;Dt2VXuByxWe`_+>=zqznCH z+%rbG8Wt1GteM}@YjAZ#UME5H;@eeSUBX%z^Ki~xE@kyC=VwFw!Irh5#n+!$STlAp zPIID=$;ig3IkBNF;*wmyqQ`2y4_6&hLg{2fl`TfJQ)VaeP<`rBPUp|mOMf9f~E|qe97c3RvkKAu+NNBea6Zy`)|?Z0{AF0C$dhkEOG2VxuyV)GW=fo6VLo+sNdgO(kJn{sb2%pWZQ-9( zDgHgJFt+#r?q*Qf%LQ8Pgc^*o@)~Yc;)4o~7(gpg2ra)Cy-~_P-lp=omSR5m5nj7f zyUl|o8{vPTOn?(bBcR0OJ!)V!l3=QS3L?+%J6d@3cy;HqRG#=%zrh5D;(qXm4H)xg z6{X$px9d~SFB($fnNX7)RJ8OYQ2p~Wq!207XvFF15b=pbTOanzEA*pUR#E1J_hH3=ww=kMW$%&9+Y-V|eT7*;t3S^|sG{1{avw6f zl#`$v6>R8jWxN?FYrmH-@_JuXK7475+$p{alv~7_++VFqV!D!4CH_5jrM!1$@|IS) z^&@d7Z6|q8uXMtNx)9-2=%bTc5IZ%5X0>vsuP(xU*fp>RoU2w}qYIC$yQF;Yi%vk8w^H!#qt5AJzXN!5o(6SUmKmWD26Na& z-RsG8vF)L`dY$SQ3j4A!l8^t>24R- zi-*J!%gQ$J|J~}u)Ake-Ol%p$5z!YZKpd&#iH9m(H;<2Pc5sRnUrlis#z z%gneJGI<-!)c?g4^=ndJUqzyn&v{Myj)+>nt+d2;KK>hYhDFWmA4;ueeDhDGDBSYa zz$aK%XV+NXUs+62i}-I)=uAZe@>f5jR>iSWv>Pf;mx&Pt8MveZ3g0N23RKamnp}ya z1tQme^nNNom~W6`W>t_*VvhjH7yDEGBmi4fOKlL?e4Zu&G3|zruLxL@=8lYgJyuxV z4$c>|jJ~7C|4(%5HDtgeVv+wCn&W5uY7XbPU__NTg+WaDMWb0%QePzT9TIE$K^IgN zYbCSwniV`#0Nrb`4D~uwlZo-FdNxe4mwq!tQNA|;RUTs&Y5}k9mmxkCJ7UF6ckl4l zx5Q#itE;PXe*Hp?x!c4VI^`m?@_3#6KktdAT#$jhrWLfL|F{8fyAVSnE~^MvMe1`J z150E!R-|@nboMJ;XR8T~97Hk5#i78LhiWYs_J%L(T+Mys2fkOMONKWurOJ!5k)EQA zf`+>X>!91l7sFG}7p~+0kj-@E8h3Pf8ya$l9G~lIK>sH^2m2jgc7pGD5~ac3Fm!oiX;1rLkn+$r6P;p+{w3vsOyhjO>((_hz2=o;C@bsU1Nu%X+v*1my{(VPb1z)NFEp??~f@yf$AV`ymnw$49$%KNCl@CP2nV z_!Af`O1&;$zF+TyyRon>&$4a0H4MYyQJP=rmABUi34!^|7K-UPZUZaZvz#U~p z(O0CZ@nrqpc`VaKj4U{pC8%kF5FT5lk^^CS6iFDA^11$JTeB@(Yv-q|GT-+}BB?5n zGV8h~{2%;1rS%|$o&_K_$S#v30YtqoxKxj~|6sjuFqmD~z$9f8muX4LKCo0YC5XG1 zfIMwmpdxF*V){BYzTcQ*Ttl+rmgr5{-!M6woTi9 z9hBIGAgg$<@Kn^P!nxj)e3yp3It*-DOn}ss^VN9mE=MojGK8}Mkvix@YFmeg7hV4{ z9t7%o$&2R8KHA%j{i};(&K3!Oz|bZ-C->NtKK?_F+3o^|P#!=sqpe#qcO+;PMaIv! zZw7;!U+C6S4;eVcj!2L0eII-@QC(?wSac(#k+M^>axO-l>bkY`$9oTkj{ze1X08`Y z#aB4@n!CT?Jnnr7ED#=1nd>LXp;8a=p?eUD(*1?_m3_R4G z)?7;y;;b+OJKJ(i8c&>Ngi}{<^z`9D;a;r!Ooy<5!hUaWg$N_;2PtV6u$Q3EhMF9a z#F#1Dnm2V^PaTfCW43-qp85j(h0FH|J+Jk82Ag8m!^(38D)D6*q8@1?z^@01fgI{o^c!$zmJ^49|y)l)4Y$(w_Igw$V+0LmZFct|9??4<1nP)hH-DVYw z32#t0d({%NNjXGOyQRnnh$4ED!ek^`nZhiy;3h9rOOM74QPDWjew6O$GEri#7`#*~ zxDoyl!T^R@Yh(-B`i zw^q-HVD{@iP1qh>-hOv#Tj^7_CVQ%Urln-yB>-iy>!kvxC8<)NXnb0!Y;Ao~BUc`;ps;n7&DUjDb z8os$i>+f#VV2i$Xb;A204G3_Bqm%4f@2b^P5$&q<8jS@$CwWa$*n(!hcpnR>7SCmV zV9&m^On;w-$M#c5pJkPmIrF;P+xZ5|xHAQ8)EuI9XV6pxb(Z!Ma#;2H8!fzVo%4zn zV?h-(v|iNWd2I>%>930{!1u&7*;=~sEsl$$Qi01l!P4x=3t(XN2}PK`H17DK@Nn&z z`Pw32Y$?aiP4lbMt-$2&{>YQkxHCBP&);c zU{;Q0hjs<11AB@{>10Wr;kAg88^W{;W90*hWz^%*9UrbC&6}5#qFk7FTyfG7BW>3Z%AG~ialB!6+pPJ)x^8v$`0Y5m~ithrk!m~x=xhfBr zNkWlSNoZ?O=9SoadWTPpSNM(8?x%!GdsceAj=E^GF&Q{h^6w-x2ll&gM{0A8;^=zh z@1mz0u8~$*dEIsK{Ay|7T-UGA3hPnZj^bl~oL20gSP(GoI@gww68*H4dcpa;_%Jp;K0Fe+@gfo-0m}w3MdJ zTpfqFINfl<_@RwaDV_H*Jx>BNHN~I=&%{A^ZgBx#p-wyZ`Yw2064Kv8)0Qji4m8BykOs z4eq4;TuK2YOS#uprFtd;gh-W+r%Ehu)5Gfg{_^`3-BdfcoHdjCFZe>`QF3ch8?v4% zK`VNfS%-Ft)iP*8QdP8v3p>PUbXfA7(gMsP>vTq-qwJU`3ONmqhmyF;8jH+XVHlRd z)PNH&svzeK*NUd5*v^hicTu{q=f*5>p%KJJ1nWS#<9Hn{!^@^AV5p73p)^FWTzP7Z zzMu{-OIb{n7gr7rQDs-2D>Vy+HG3!LIO~ZNuzz}EzPQD&k_9{@K-E`6_V^&yF zQB`(bEri1#6)o5gRMgTi!!=EqFaCjyfM=(p1CoU(E z-9X`a$Gr+~&ldSVWcwnVuw+{AT(HnRSo_h(odIeYE*!7sixTdqgjz<|-3$j2dK2kH z6bf3R4pEbJRU2Uc&j zJ^IvX+xV2w8gutpOv@3M@(a1DEG#y>lJ5K2RiJ^S=qGcCU|nwkLp z9_RBSh7IjjSr#2HpdsN-vpgIrg`H0Cm@zJzfGKlPyNUBbrh?z~+IQRgelu}<2q-1m zT3-9ta1C$Z8>&+yFkd^}6CoGe>#2mMQe(#4W(9*JQ8dw?#DP1Gg?Rpif!Lzd2A5U2 z)cJvStRiJLbrHKCCIfx~VK2DzpsfSZXisY`-cN}+nIGlS?Z?;C zP8s_WP26C*q69vM$5Eskr`?mex_^XfKaFzG4tI_?u2$u?@MZ(I)8}Cloh*Gg7)-Um zAR+m$9(+xkiIW$t)<<$DPn;!LjyvpB*C)u~&r+l{Wb#qzHH|w=fE5tlTF2R8%pwJK znM)V3GmWzD{$`O%8B7!uk=cC&=G;ngDwL%w_S?-@mi^x!?dJldXFODc5+CI!*zj*3 z%9{HaFFG>8lxp96zf8%zRVmN$UEOZPCsG#lMqDj@XTY5ai~YV49McrN!f}u@@3?#B zZ!aw2a|de_0_r&YB)2t8#xrl}*ZrM7Bts$LDdO$YcFVUWq_B;55cpWxu>?qUJRyq7 zlhC6Vls+TVMkHy*(+QYi6dhVUDb!Q&noOSAtiCpn=A~IspJVcb>Q`13R{mbwjp5tm zlu_+u0%YY;;{<-H zR4o(1RyDENxKZg*ZK|r1bw|@#ywq)?#31ArjoWh5+L@9Oe03$ACLfhu+xZRiH^VjZ z7*mn<7CI~KaByc0&MxIkKp&%m{t5m4X2*i%?*5j;DNi6X1wyA4iC-!(0K*`AcN=7w zLjgI35DtuMm7hL$FMzFAQSKWv&2;MORufOM%Vags9>e)fb$s`u&zg*N8>MD?9wSHj z6?!UzBr!&q{KUvL=T{TSf65zv{^Vo)cac#%th7FkF}vmYOsDsaVoS&q5eD{$0(K)#bFmA3J=9S&9=xOAb8;>F93@6j3X4zT z9=1UOH_*+JqkYa~%R+?t0{co(8PY88YfkL2=#G4h9W7)U{-pn1)l8q)qkSOWZc0$r zJh#KtlaT;9mC_#{M4d0)%l&m;?%5YZ2ew$)>`@;6`S05biYpAeyH>}1+jKdxXEVpT z^=4pznM*Rj_=X5*L(&!FP9P5Ri{+-H05zFBcR}qY{tO0y>Xw~bZ`kM*`R9JPY^@5_ zqzHn47jXJyR7wAL~yOK5@dL7o;|Ct-l+H`Ek9o z3aGSrJNc1~6A)3Fe)z-<^xT?sm}*u~fbLBENy(t=Q(u7oK_C7NDDf(`P?8OfQzDPwXIVg3c^m#I zFww^k>m4WTA94chFVPJ}L7`MtZxLU_3wt*%fBQ`x#EN4zXOhK|QCrpU zgxSkJ`bPb!V!I?Pw5v% z+Vw4+*q_BrvXAM*3&`}ZM~5FjMT=o`@BXbuAd}lVpWc-*`XZ{9*iGCETyaq#su8z3 z9gW-lGKrdWLWuvym0BV)2O%v&Q&UrML4kqsjNxY`5dPa2N(3|6pE2q+eA!gWb95G=j()kE$JV(bGl z{kk3q5Iob{pw9OL`{!(IMjp{+K8cJJSDnhHK4G@Z5`}b-NwQ(gu3qkeFs=|2%^RpO z4XXX*nI86QaWQ0~xMF;m)%5FylZc1{7e-9LBV}nS2<^JAyW??PWprq0>l$?MwBvg` zwW)e)m@0+`r8TX)lj1yh-ER!Ox3{NK_%lGfR^ZeRSUyY+{WFoq05v%MtZD1mtj>)s z2ahPx_((pc8}gVu(YYsQpgYlq{YUr{!0pLNWkyNbBCx-caiK8CVgm-bSy~Pf6jNfE zXAOodHdt}h^o=!zg@p}FlhKf{i7I+A3puL{g(Vkhm){#w5Mzl74*sjFf!ZT2a`(== z?FsuT+ocV}sy3AIs3NM}1k%jIg{5pee#kE@jKTe!fMIZUNyd3;kGhfIGJn*fXhsv$ zHdAWZPvETIYt7M*De<|kVmX|P$8T^$gQr-cI8hsY(EdrRVXelqi(_ivABbI0&)A1y z1dsGL5CgcOlx*;!nZywJx#Q-p-RWu(FP0CwJye6;8$BZy(C9YzNPbRJiL5S!>uJGgmd;cdW`{ zh1cYvc!k!#it)1jU%zVps4mI)E0hW5@ec2sE1wG@POP=s-N9kzCfGc&t$M+dl9K&} zE|rPhim2`i*|%1|4B^+PvV(ea^wVe?2p}FWv?dE%_>>U?WaE8n9Tlo{QAzo@MG|S^ z>-hM%Pd2w@k(KAeNIrI^2*1tsbxq|jua6B3Kar<}CU-(f`4dcc0L=vvtXfv78z_=%><*6pqQ`ExIN9HgbChlIRNz~OO^86Lw?`HvqzPW4b7 zh3Q&sG|%7P&h6cdYMUXkV1!!Drk`be3k(+x?Pxc2zBZ&v+-gJd{#3^HI2 zOtGU{?gw=z>@-JI{LCoRgEZ4RzK?T7A?u59gHW=WvjQZ<8igzoT%KY=7H5@I#UBVu0g;qTwA9v{7!)?Ebw6*zNRnLo&;443eWC3+3 z(@`Oy1g}gp`TkZGVl|tzLvlx>dA+(^H3h;HF|yI^X)B+1K5}9Oc^tIAeEIV3u06qt zizT7W0kK;8EeKmXhFImFAnVu#hk<7%M4o?{5l-~I0Vhv{x7|DtyrKMTdQK$`l)OFfye`zlj3_)H@^-=cpGc#o__MVwe-wk=hKr$@xWFu2=&R!5 zMeLNF2`Kv6$-QYOdOwJ>(JyX2!Y|Y9<$sx94*|LF;4$?}wR@x(&kU(c*sK*V~?**#Z zAU>K&JCrM`-<|54b^BIIcXu}->DSs3jLxDOracR~_hx{@;Ic4u#|lmUslySIaVvI< zA48`8#yHskd!PUF9K;dRZr$d2<@HYT?wdJ2Xsu~#`8tk=Zux!Ws9F07*z&%uj33?k z18BnpQs%4|fZo6wAJ^B{heG1B8D^@YkPshJ#FK+60mjLs@TRQ;Xf$q@jscI`9`o1S zhoKh<5Fg6_V2^L>>9~>379-C#F zNO#euu(2aqjYu5hzK^(NF_xVs8^Jd$rX8uOw z^pl~G7~42eho*;lasvvT1l<*Nh9=t*)sV2e;Er^>W@17hUSyuDcJtr-H8dd+Y-K?` z$r-*op|^jq7zK)I#I3hhuJfTA8yjUWd*@{7NilpF_mg2I+RQi3tQOWYzraPnk{x2X z@2=Fk%ue_z8U#o~(2D=AmqVwl#YQny9^JkOX+k5&*;@{sk0`P9mM;eM0G!9LvRSx7 z>sOp4v>uqLG7hiN`nj;+MEzTE_P~GN&fT5V-y%_3vXJVO8So&%Ke#7Q;xb|BMI9dR9`RfeKd zw>4x*9Vr~Pb9zIQ)Yp+Dnk!w-oGBpj$`7*{Z>e+-5qa6j2W)zxUB<8RxN!<@lw5BO__`hpZ&H00JK1lc37 zm8Ph$qm!oyYvXFUoDw8QNY)xXVHzAqU&g*DHh;69*0bt)=h6d#{!%-z&JA38$$OO z!il>w@G8#60%)JV(Wz|c7h}sM4!*XkV_WbsX6Sd`^aHS0DGAZ-LC|`1J3FObPM2Fr z`PRz+u!F>++KZuayHSp~^E!`q)hZYpM`HR8_}ii&XWA3IZEHiar>_>NUPab32}vU6 zK_)H4^mShH=5nY9&HBEVY2T-)$Vl3mc15#r$;Fn_M_+ zd+Tp((O70Gf2KxHEiJ7i=86et>+DV+{$T&qo^-?|yAb~|h>uGi_3{Y#&P0Uw-; z=Vy0&5tgd*_3eSC`;$Z{+apeiUQH)9f70TNomBdR-Fr;4PNKR`0E1$n@@3eG`jk;yP%KBKuTxMpoGH;V8~Z**Q)~v zYqal%e)+UWC4S=a)>^Gl*?EbxvkVL=Ck9XhLKW=L53dr!E8F=N>Mv1%V#<|U4;96^YQ zJGa9KY?b9B!F5gdq{!Vj%ZuU7xB26U0a=@x?k|V|pQg$SUFH`8=JwakRJ&=yWy8LV zj@G(XDh~`#F9hbys9vIVmmLkf*WL_e%G}er2NpUU$8;^OdX~67dvws2Q%6L+j<|U$ zJfuNuG{-j_`)N98?%{_Kx=W&oZ7|hiP^|pIV|1DC;;=Mg^<`7V&W0U#>*g2csEhX@ z-J9zBcA$oA20P!1O`(JM`T3oM4<0<*B$JubbTW(&V2#ZH!R?1bZ@h`!6(@Dhy&~nm zjIRz_)(&S56AkJ2gIB%!_8P3(qYBRGc|nfh`0X_j1R_;3z1+y+1#-5kDQRtU$m9Mc zNEdaWdW9OjD9CV{jWD;kSPV0*=6dSu=f|wFf&Xo=VOZ#sP^qAbnMip5!aoFulMyKB zvQmv_g=5Q#@p&=rg-^0_cU@*VzfnE0PuYU1#W|XV>q}xdqyt}-m6Zu@g@1g0qbL6b z&W-=(;PvoD#q-~^PXVy7V4P&_Q*_0+irP@pFe+|g^Z~9y3?hy7* z%`8}WS!BC6jvk((btSEr?W)PXB}%J$nTJD57%_3R|1_EWO&=F%HT6wcn{&{oct%yL zos-ZU*O*XAvhd&fp5zzz-U!*c?kzoPSv40c|I6#QGh-3HWw6}IzJmR9fFL7zcqsvH zpKvxzIFs(tFuQ$X$aoV#vR+dG0$0A3{>}^weHCJ{k@D8@n>}a~>EV`l>guYOC+cJW zx!0gZ5T4k7;BHNpH;Uuq;;Ph4>TvbpBd$0qT&sQ7Z48~j!t=yI@6e(#6=C7lMENyE zR2AVF&JSNzKm~l=ImVp##>HQ8wIYA}6o!|+;u~&7v-B!b`|3S_Z8vv(F|EnBZYoVL z{H!jKaH|-I51d#i@EyLJXY`TaYx1E0M*?lpo4jFse+MjN7rP^(x ze$TPiD=iWwtEWm z6_&mU`8GYw1vWWRp>-M!gW41u7hG5`cU z8NYccT-N>+BCAb%X=g#Tn~s6}EgZ)|euUevT>g#gF3C@P2;b(*Fm>oJZC93L43HM7!wUDoV zSKIaU^q4B1E&CoGCg_Sr2f6&EOovMj`r4WJ`nLcpmK-N{MG6XKVTw3V{#`%VeE06% z0G4nn3sfn8iIGBzt%dDz6XX(iiIFLIW&zqa)Rj;Qf*uoiH;w)D)lMHir!$x|`o+*%=iVHf=n?NKTV9L| zga_?*0erwE0~>%$c3CkUPa0giyAt=(=`XAD)#FX2sM`-72*#Zsq)uj>WCnGO=N-$s zGp?}EFI$evskqL6*|*J82Iwz5bwulH6J+vb%QLO9z8PZi>L9RBhL!&0p7Qu@bK0^b z-Mm^0;IT)z(EQ~^%hol`)^o_{ssuyP#2C@SEVClm6Z8H-A79_l7N4;%*UbMm6w#)e zygVxl4I!fsxQxv>V8M3o^4Yv)0 zS2bA&h0mx0+K|yZ1sR{a>GCFWR~A$KMgRFgsr|uOO@W5<$bGs-o%1hyz4_a!7`7G) z2;g}UVO4p6kSEZQbuQRl?N>p*>@@)Jv;_A9IXl)~I=Pb*`ISUC`aAUuI*>K$qc!R} z&E(4{nO=%>hhrxST%<9=`i=zr;Ns$94S!nzed7vZmAcI{lM@>TczVV0 z!K8)iDi96N@S9@L`1H=cL;TFHF4C8cKIYbk`-Q}S;%0sagcVxlq|P?qy8-R*s@+WR z087bdJf7^!QO}L@4klHNSyu&FYzK#i0$$9hl5sfc+NBm|VYhWnl8S>`E-}DPQ$WWA zIi81`@Z=*Bp-{RTOsg+T4IqC#WQk-QvuD)_Y#5z~%xcAt?I`dDu-^=rmqmDz-oEx{ zn~;exor?qP`8eD*d4GT3FaM`aoIF`0evKa*L2VQxR%sz#tPYWUtJswTi-t*oTbx$y zu7mCY_M`!In)ka$w4i{>K{2P)1gq>`S4uPvNmr5NcZw(9#Ou1E@ zM2lw+LL^!FVwP}c6OxgKa2;@C7G%kej z6Vkago{baK1GjP+#ZOp!ev^gc`sr0ol0I~BB%5xF+=Ruczp6~V2WUPDC9Aiu?05;X zwFF8D&z4PAe^4ede&$K4ah?t|c@8QUK1khH#Lz;Du+clQ0bLfMhH?Vo8^>hWu_mx~ zDxeJ*z-;4ocRFH_h*Eydi~|aJSy))8fx>%(Arjp(0payLa`eb#V)F)2DPt-Y1KGBk zYMB~QP#~;!kZY}YW!B{Nm10PS1ikO+=IY}9R~JQCE}&dt%Qk?Efyn#F zwU%ltV@Wgl7Vu5td5u=9>)u^w6bo^<=WOSbDrBwS&tXHxHuKwk#+J(n+BPw}T8}Fd zZVOI6%eo}a7R_}0`2C{mHJisS-|E%0a&U0yFS%Y5&w))6TlEYlb}aDNm1}0(dD_a!Vj;whv451uU>Hg^m{+NV%EKiv|~~~`sdaEzyI!i z^>;S)(=>n0dNZUKUl8m+8tr1qvF!5>kkcY!}(HOU@^HXLILG^YNowPhhwq zT4H?sP~^ElkGK^Fq9 zP|zu#xz~#IjKb|}VRWL~39V`KH+-{6oTxfsHu@FnV~EsHzP11$n$>zsZeJ8lbQdSj z2(-VY3{HT0@@dIiY7wN96VT0H&ZuU6%eqXb*yhP}K{PRs4y+iZy#rlEF}Hf+(H`H} zM2Of7-*vo8e-r3--~Bc18gx>a?f|`^hys{;)HY8=#!@tcIn{3YM9*JQ>IR9QW*>sm zK59YaB7{10amBP4Ul3ujHx^+b4S~-pqYi0MjqmHHKp3-tNaxizk=fBb}g$P#)B@Bni( zI4Y#P%lyKPY^7n~(9G((la&(dVDdG{cd98|wtoG~rIB3qHvdhHp4g8Qo=A%ixn9G{ zM#axgTgv$IIob87MLPQ@o-xXd6s0Bfe)@2C1ldOiKp+@qfb0B+=@iMc=H}*j(vBx2 z_~YSCR%{{6RGu+G7A{tz7HXW#WG(a zEqbjq&GoIy?ijgWzdq&yEo&wey0Sh?0SVk4$E#A3spc(8`e1DF7;FTPgIJ+|ughh2 z;lxktv>6W~A6r_bWD&*9Qa(E>X#2;rn1#>avnVqiaJ{^-a{13!O7zAfxzRlo*?nXr zh#mSmFfe{K8F3ML`_|U#_cb6f=_6LXKzk9M(?q^kY4ZdzN&q~90ECV#T0s59k4j}0 zApUB;=@5I3?>-ZP$4;CLr_d^Owf|nvwMb`iRL1StYxj!3gLSZYOL?d{aAj!)`OBF`}%Kd#9ig;W@@9xriuvNo0#k)T{t!qM^!GNwL3wOk2J zR7Ct$XQQ)Sl8F&!={<6D$`P#YME@L~ln${EI%yQerhbixS1VY(AK z@z=ZSH_LQ_*9ITZiAuApfzK=gk<@Pts{p%EamD<1r zn6k2bZk`i$?2UB}6Xyg=)m=Ui#H2w*Jw^#UQ_8$T#eMuO)I%A1^?;h-4jQu}0QKnL z2|_?-#TiQ6Re*8TH89Xy3z;BoXu1dW1blvQCij!o&K)Qs;mg;GCn&q=Uk?h}^^u7Y z!UPMr3mW~ho+P^#5|*-19XtUN$3s<Ow9BUWk!&#FfE&KLRlo^;d3g?$6B3%mkROkx^G%$-;29 zBE0uBko}A0MRRdO_titp4>t)k0V#OZWt2)@-~7mx3oe{TCWg1HnVy6PpcGPm(E^G|(jv@+Y*7N^D3nblMt)NLolVTmW zy_JrvB`OS%i7%@1Wzsx{#6 z;)!01TYu`Q64R~O`4!Ub%+zHeq|$4U6_RHG#6yAk1qw2?u?ga}91)e2J)9iShXah7 z1cY~ffVXn$)Z)uNg4`Bo3lx2JaZhPZQ*X^^DXEp&k6JZ2wkH4B7WwiWQABDmUqEj3 z38siR`8#jr?|A+zm@QDMItj-pt>rbYELJ|I7|-yi`wCOM{rX>hk!SlE2I4;G6H#%GHeJ&QVa3lUsg|yHkWe;Jp9b%ky4a zj;!v6*vpEqM#B>aA3m8Nk%@7Aa+$^K4*Uf%%x*>*Z(1LJugg(o z>^Z?^V)cx~PrA2%u7^9ydHT(tC|8HtLr zQ&|DI>_!_UE7po4lJ9wfLOub$@QHrIwIAztrl1&jZH2kQc%90KY>T4?6MPZn(!8oPM1adm?ygro0GM*^}9*6ix%a8gf}oY zmV+1JG*Nx!|G*8DxB~T(jnY$IPyoLBc&!7BqBVWWUOUk{PJw3@!2R*NK5I?W9etRH zl;;KV^pBnT2|(UA!Oy{I9{e|JAO%su_1I6Qb>VP#P-l4Wb0BymdE$Q16P^4hk0y>< zH198xzvBeHiG0{}cfVftnw*Tg(>JeF8Ui}k|5R+wA=!=q&isdT z#66@uEEst9f!TKj52Q($$yYQ>DF8$1(Mr#mpDBt?E{EF#{2Myd-;Oj=5T%(ZKq4(b z+pE)a0{x9$<~3z!autB7h628({?*PXdjae>f41d30D2a19$wzUz@VT~Dh#L~Bb8um z8E~yWcx%^G{603aHr+UnbX1)gzS!lNerjOY8^9+;!0PiTjEbI$60uVr-?$t&=s*NN z=A;kDfn5F9dS662aXWC>psQ|h!BJ8i;F;9b)wi7pnHjK6DFD`Pf8;7Vhf-`!-Urdu zYf4Q`ZDN4H#^QbdwJ8+TdGlFM++o88eUm}cAnNngpr9a5Ov#@O0ltraFWG7$=SFN~KJwhT<|5$H$&LJF{Q3$r9VI`WUl!%GLYrLazo(w@;}i$d z0;{?T&{s{32GtD-%>snfbB5dr=5psFh z_TM^m8F7)$l7H$*PDu5S$2C`v`iAJSuLRIgE_=9ICM*{yqy1#YB3 z*#XM9V(mwl1_uO^H}g1UV~fE||2*hCaikqJ!df{60o%R(^|;3E$gKH}v)2XVCT8h_ zik5SCyOlBap-RnOItviwMgn+QSfx zJMRr5=^Av1Xe_NBFx)7r@Yf`#@{;N&uTIuqhy{X4@?A5{Qfs`+O_?MOmc|(O(eBsyAJH&*N=*sEB1`>yX^sMh3CaQ|gxYidwd#@~|`%9JAU=;bv4$SH)5(o|1d zhAoZ1e6ltnml<-zpP8a1=($+45$Z_|<;&k)Gl^qwO3Q(63g5CH^$W~QlF|-cy(%m@g<%edz${B zL^@=5z{Y(M=D~nDcPY>NFi1=}QhCY7(GM;}o<&-4p z#bE0RuV3fyl8cv4F`IY^A#xg@hODG_e7{qGqnqp)y0__CVBu0n3`nt%+_(wENC>`l z>-zQU@84WHqC4TyrqIe3wiO|&qxLKjc+J-DlnwO{-Sa(TkP-FS1jMkDa@ut*Ik_hk zmRmRd+{Au2D6#}PU-x|Lh3N)Hksa`XhgUZH%C!h1OgFxJj9e-BN(K_M7G|(BLxb!C zg)-jY#B71CetmEZ{eoeFoFLb#i`*|ykP*ghcLM<;!#FR@wE84Rj5IX{^xMUz;sgka zp8@UtI&h^?X8X^lXMiSsd4fz(YP|w;iRtM!Szr^w%y zGC+6~@+RTY+l2V|c!oQKOs&N%x}6(>bhia<8Y1e$Iqk)6Qvmg>TY# zTEX|3bl4R61H#~a z+qC03VII|yLMfNEZK^+52hn0O>Pe)HOU5X4tb7}z9iuJs2j~ki?J=(t2+8sekMX{5 zaoReS-VU9&pc{g}z-=;be$f6#w5d$f1Q2dAot#1yJVR}BKO|TiX6RNyr+*wFSLGPd~4N7hdFiW`L8q5 zqvSn%UWa|YD5Ux&K@y1+*2%T@PX0%@UP6OoY!#rr4kyry8UMKP8-m}zw5c&v2<(;X zo9xOWjiV=@T?n~36Vcon7C|ErtR6D$6d&Whe@{&(L1Av@)AQ%g@2#u=HpJx6=^iI< z$*9c%f0nm0_FEf@Lf)#vm9SzpK>P$)FY3hx9tCWm!0U~FW1>ggEB2k_KM=gKP?TEBqQKiOwZqUK+SB577 zzAdhL+g>v$bI`ST&j6B*X%7Ss2FA&j1H)qav%&DYBtU^~y$$j9UNeSQabSQArrk50 zj<0R&W#ld=rnsKeMjfQUmJDJ)6xEgQ^7v&p@_XCAP)5*0AjbqS=h<<>vqSl6I-lCk zQ71kFa*y-vur5XDJs!VzuOElX+o^B3f|`J`c^df)lO@iZv+RTsva$MjZF59&7ZW)Y{0%IUx@Et`EP7E?pUai2!8u;@2Ocy7y}bV=}R| zCLvl|Bk(jLXa4SRtR^e}(LtZ)jEoE-gdqknLp>N_xLFiMPXM#P%kZI$i?0QkKxc=w zsU^4$5BoMLo{-{M(5BiAR#1ckfKEY||6vMlLlZf1`CtAi#fY06p~sfShR|tF#4LxI z+!8_L=>CggO~tg+!iOfSWhnLWvIxsO9Lw06+;9X?3cHnuVc&S52EKFV4E9&kYj5>+ zBxXbbra{5}CxL`VU8#5ou0a||0rl=#Mj0zFZMl-5cM9@l#c7Y;qh0&7Ezu4cU4BM) zRS`K7t$)Op^Y?$@imySO?kmQ%Y&nCv%REpS+c!jGh}ol3f&S&+40=QnMC!disMgsc z9D6%nhSjVE@YnxujDz8^nSOq8aol!&LnqK#N)}c_Of2pIc%wN%PAd5M{g6`uSKQxC zYTNOD_|gAEaRne}dXk?;x19fBytp3Vp?3{-04ak2Rdy(kOu`0BLQ?uVrv|)B_UnS{807;fO3z! zQ4|XO1Cs%kKQEd%&!|of0I!Dx4Z$o&;n^q0V1S@<=-Yta{O9_=R&iVV%cDMbtbXqx z0!K*RrbxggQht$ABawW4k@j%U_)(%CQKq zL3uhhHVT%eFZ|2x5Wy4HYOf#iV1N#5p!+lchl(5iON9MDAzZeH-jGacD3hoK=~Bld zk*5wvT+LI8`i_2JXH^dcLNL&3v<~|FkTc4@70QYJNZ}e|V`FgW5=_eHy5-?!DYk+$ z76tgt(Zi>zCk+Z69Q2k^N*x>9q2xL@w@mELsDT0Z;CBj*j6x!`28J0C?@oicgOY_z zQji2soEx+p{69A8EZ8VI52wSS05I7fqFkGW!O{uZ8#ds@$cG>QH~S?ZDS{{k6PhvT zM)4j%T-16IIn=;(`TtH2&8_*TWF{BmoO)wL^JytA4YbH}dUP+M%x!FV7w6}%(LyB) z<8##|jOwiLIs_jRfg+OP?!ZRb4y6)tHfu1E2jR@!xTr@=Svu6oLKjt;4n$9;ic+Ga z{Z1KA6!P66&jbSUXk();hb~1X7(a0L6XbojElSOIN7}AaFKo+*JSIzLNTOiqjO0*R45DB%hg{IjfruAu&fk+WR(ZRfHpc z&uyF7?w;*Ydt}Nb5#spuF%n59Z|9%~Qh=TGla~}&$iBvFW~PzUE4z`G2heJSD(sapxaOXcs!`u1l2NnflF2mc~IbvC9F`|ELAtcvl3@ zkS_o*hMegBH`_a95T8~_hJ|rPx)Ks;(M{pbH~;TsOv#u<{K@u8zrxCftp7UcDX6sH zx2RG`x$NG<4aQO7mn8h-zdS|z$&##no5y5t{TkFfr!SE8(eSoJ;-}vr-;nI_hgws9 z&avgamBpKFLz$70OtgoMAU|h|XPXK$=5TNP!B4|L1)w3B1x!|h=Y5BEM_VvM`;%wE1NIT=aK0hFxNp`p{g(t|?tSqscj#3FJd0iU2`}He6Z2h{H zIY-H5)&E)91ai|PMQip@y$AGccH*$L)Lh z`fQqCDhXMCo2^KD`^JsQc|(!E-wpto;oq`@co9prJf#|H64rblfFO0AsW6EV*!DW; z>bc$>+f$;IVDPpkki+8?t;g2$a#o#yd-v8jsbjg5H#awBpz9z-5cDjE*u<uy0Ea58%aiwJ_+`0c#zy#m`rXVrRf%ooA;gLz2mA zw@SdO`M?yA1cP`yL=cj_Jw0-#`IxdK5H)~fHtP{ze9n;^OqdB{xXHSj2x)6ZVLu!H zud*j))t8o*j$&Rz&#OyL9}3Uh{~0UgzniOoQ?0uK7$!tCxsv|w`%Wn1>VcpZrTQWD zQl7VXQ*@!XPKt3}#Hcz#Ai-V&kwxX< z<>Vv=CfYq*Yb!uHq03cOfA-*iRaIegAB&c@=E}JyFir8FKAV^PQ)Ins9ow!R&w6e@ z0XG=g9*EkDjT~jpHbx2nXGb2BOT!gpJ< zvS8hTciVYhnXpz*E5tBKiXJ=@(L9BQ@lj27v;b>6g|%61_(FLUTcor(`FK9x*Z%(S zt0lHo{@{q%pM0VmDYB~a`hKg;GaifvP?-+QLAwi7qdL#a>E8?R2mN|+A>P85(o5O9 zdtV;*z^C)3n(n6kh1dfNf7O7-unZ>q>TJ#=3c(g@q%JsJLYozH}U+uH6Qg`N)x{TSHe+@0p+LJUfsQRctDZXgBimL3qAvU z;n|LBFCaSsH$Axt@&N~ZxDcY>ob4Gvg}Em^NrV?v?icitNZ~Z!7VkrcU>$E`3RHj9 z+jc>p{nf?a&)Y~pqw9KsZK{tRrnYPq$ zus^Nj2@d?t1W#nCIkd*QQd~k47X|ErF&$**6c`Ll&kWjncXfgjA$(57iw^&k6mAHz zk40c2bHneVG=a^{1-%#o#ZxWcC9G*{TrQJ=yn%h+>Dm56Dj>P2v~f}Ynn_hhWxyuu zUYO3k0_Tx*UXK*vEvdc*toIrm&|$P1*g__B?2+*!bwPf#jjexQH)hAK>Cc{ofKQ$sd@k14YI1) zsWfFVv_eYoBm8DWyM1Zx=e64B@KiUdHzLLcmbaBWRuC*)kGc|ssaek(VEH-S(hYTBZmZKo+ zgaNQ{YyfLk$(8Obn!$} z{IIHG-Ctg2QJ-Iao8G|C=NoSDWqV0KwWC5j;o$iqT1F1sw_;VO5_1&|`WuYSEbSCi z>NbleL{dZ=>ISx@xvhFhenIoEla@I3d-)sL96BTDE~dkpFu?5ju&h$UFwJfz*-fZ+is}*K>|}@5>rNr=i(;ha2tsxf1c%gxW`|9MAG+)WU7iD@FjPP`~N3 zc?ombGd`Sr+?A#xm})3u4T9qm%~3E;1=khh^_+iu0g$2?@IhpxTi~YmBju-_?%;&+ zZBTMKVHQ`fj^lg?h?d(Q9@5Z>utb%`$(P<%NYR*yH$YYc9Pi7fp9fwpF0i`N};CnbWyedu?F&`3IYrcIUDIV_>Ja%BDXxS*(w26+1;x zIC*dA-RqEv5VGq-mE4UOL->j&i5=~lNDNr?Y(pUGeD2@BCnX_qH#*0;?LWUXi~Fl2 zL4yfCZ=;?O%3o)oAAJ=ZomReKGYXXXj|Fq&0FFNk5;gL~AXBz#_V2sEI_*!B4Nh#y zyAHn(7#N0+9gD~IcX6gmG$l#pcW^{Eqy=soh3+MPOC+12_HzP!B5 zC?Fu9j^lC}a|8lY9bsGNag zm%tE}IW}ib9PJAHIK3 z&$?TD9s9}A1-f|gqPBDK2BsfaYT!VmU@gK6($-rnN9y}FKbN*?y4#mqOnvmBE;yZ~ zpZn_7t25C#KCQ`vGnDx5xKk#Z^!#}VwOy>f|pS=c?Vd*(7$t&-HLl4jWjn9t{+!~L^FgV+H1X!i0faLB+ z?;*NO{`~p#j>gC}G@0i8__aUl-ufDrNCc)oksB|?19ci-T}YIn`i#jsqIcrKX`!33 zfNR&hnCy){R5>C)-e|l#0u=9{59Ga?Soy5d!a|KP>mVwO{10Vlg1nF;Ud{7uVyzbS z@9s`F-oy3yA=-*X?2kS>2SV?8y z=qFLUE0b8w^|tPqS;VB|bkehD{3jmYq=cIGl0V3JIcK~pVa=r&?`MOapm|Rn128cO z94Z%s(OIDzo?d)?l|%I^cI@i4Yu9)lPu0pDC(`K2%@OJ%V@n(r)U=K_gYaXRiNBqb zELf!Gzl2AJI_G?(mEv~j!ndZL%9JPTpp63^$MHHEic4It{XvQiRgvd{C>taq^Jr;p zcZ?KD)}I{RS|ggcfHI>`-t#;V1_zf@POl@bya&U>dlxQ5g&ONeTY&QzqUtr9JCeb|A1jlvR7?FiaLC%(jt>t9vg_*WxA+V{)PGe8`lCf)rlmu%>nBHriCB%ymChSQx2=Q;_eFB1 zGK6M~!Mhx5O$L5EliLd1>{wRpvAd1ZL7+I8ycwu(whnR-j8cSBF5l7e$dmsuLlb2R z?)H5A_fI!7d#e>ktMEb;^)dD&wHxYoaRx0g{*~(u<9Qu6c|J8F&wu&*)TLqI%5Xbk znAgYS!y%zSX>0nib!GQP$`|32$Atcq;Ve;NWkW?> zMxXY%*E5NDkEy0+a2PWJb0BRRixAEMNiMy_17S(T$ww*t%42NTHDNm+4 zVdRd>z8%m$8r;O?9j2TXBH+y2?D0tcM^NMC$ueH?BHj$2D#Gf-U_E^eY%l4 z=WvyKIseR$qO?*qgYXw%QN3vS0%)z?-fB6mccL~3ObNU(KLxiGpPoy<$x zno3hUa(pgDLrd4z@|pvdKTPuMWj>XuClTUv=AI%EZ_j`Ukm!=XW77`TauqDTfp(YL z|LAY|<#p#HXQCw^NH=Q|7j^GoW;7nSHu_G=Pa0>RP_wgtYYDT2)nLr&dx(+TN&$~m z2694l$R`zkh$LPB(&jbKwv&jEOCl_{Gl^aA2FgG3cOd(~arlN0pZJ>n8=r&2hn4UVsk793wh56oK&(bzIMMhscni&AH` zg_w+gnXw|0%jOm&k4pq_a4&%W-{ng^seVWK125+zMexBei+tQ1Np;DMEblO0x8tcRD!MKF~6=n0lAV^c0`+@3_BQ0v;G*FXr`?z9i4( z2g)dpv?aU4ZbMdb9zu^_#-7O;rO&A#<5Ed50gZ}d(x(ZaGH{^rS#`w&_rY^L2$8{Bimxivm=eKo4IBqil&fucul zIJH)%GWsQ*5cV2>`ku$=%GAKXKIgKLEyAB|xxz}Ahc^>e|B$!9go+63aEQw{1dVy8 zUWfX(&@z(iF|il~bggtbCmfz)s+=3I_VHW1J5w=U&2R0ddn%pD84e|JIJdVON6Yrb>W0Yjcy%@p?Rt5<;?Fz!N@ z?Jh!j)SOiAtsz?F)92mX>1b2yyhS}=9!jPUPkU|V*=E_S4f9iVc5G0~g_jh3)p;dn z{({s|6Xw6PIa6u2%lQCBoxZ~~DV5Ey(zGW(sa55$^M!qf>|syLyhD`)iA~pMrg;&{ zp4a$Y#|(yWyBYsedFGw`gNLhGK~ zULK1RcgI5^LuD0}tm97riE)}#$&8GBH_Gy2CQe=h^yYJ(ZHgtQ-X%@$ukidIe7$!d z)qndxe(aJxvO-akJu)&IRv{7DE3=N7-LWeqBMmbYl|mHZ$j*+OB>UKM5{~WQ7{BXy z-}m=>-=E*__c?#P-&yDNIy^c1T{NMTJB%X^W9o~mG_#p17^>PwmiID?xi`bmkq)YoZOiUU+~#H zAgTp(6KcK%_(~+_d2yKI+nQ4ruh+BJ?^Bi2%X@|@hnJQA5zT%`=SbXGIE5CqbAgsa zqR%QO?libpDPFK^8X9^UO7n3#L|bN0-^V3?A1FTF(3Z*^Wlx1){Bsz#?B#Th!gJs3 zJUOdRh1UdncoEJ$h<81oM`qhLVoO~;G_|=`U+n$RN7>^pf#{QM`+($W7?u;WsAc8{|3zNyt@HLEH8PPTV$rccB^l@J*{I>|IV{yeYs z+%wznAvQE@x9{%U3L@~gj}*1U*9%2F+CI04u*x~?CA&l^(Utw1k4R(vNxgdtdl~(x ztazgDoo$S$MV~o#o*dgRZ%eLVREJ1W+?VRdkDRB+N4Aev4oKop&&;BW7fy}~S$(yl z*f|lfV~t+ysTahsv$M~oLuOdKG;S)YO0(s)xMlhMp11mzG)$BcTA7-$dY3O>MzU$n z#Yu}?HE~U*h(=v`mg>voVUeMC4Wuf+AydZ>J)17`$+|(xe_mQ>`$;p7gd5FP zCJ^c~ye>~0`o^brVMeIydfU$J zm^1RX#^1SDb?xWs+?Fa^Ng66XhWA zFt;5#GeKdgV21R>IG1MJVdv0ni37d1|9BC4iYciUWDuWU68;E(5^og0d%K3=R2M52 zaw_C0GNuwP#fDFWG^$Mf(j2p}EMHskp|(`0uA=4{93?+{q4;a`Z*;e&S8hw)+X{X3 z?Vf<~zV0kC>^-<@^P=wyz6LLpcUAjmQqZbt7z|QDJYd*Vy2bsxxJS@;!H{G8hu7D# zZfDh>n%AD{BM-39BRpa)@M>SZTv?t-2+XRi9Jcg+xazelT9bFLVnQN3m@9x;U@Xt4 zBCN&Tvae?jZ8&?{+qOsdk6L_nPuR~YDS!F?#rJ4R)Jk~!DtLJaw2e#1z9HV0)Pgu^ z)91;_lf=;C@}Ybv=8j@gj6VoNwR>)xHIhgGcU(>h)I2`@i%Fi|2_@l?w21 zS=nLo@Li|2y17e%b@juwtzm=<35>74i=vOvR1gApPNOF+d%SZ$*|sbDixru1qHq1I zn#v003zG<_Qjq9o^dXF;p>|MfwmpBiux#^$@mj`^Q<%Cr99BGtK;ZlN?1)3B5cPgU z*d1ZaDQLo%FKcvv`?0Fl!IWoh;XsZ3c|}9$h3RbFZNF?G{q)Z@=RYCDa`r>A2rco# zeUq`FstK05N37Xjze4J}+bVe>eZ~@WeWQJfn%UQsq!z8b=H4$hoLWqoQ7b1ydbMw3 zB6ulO7PIcAj_OMJPyV%bZ;qcVdb4AFJncug#2^G0{7cvKhm;F)#`-Atwmj2 zC)Fj>6|1x=M*N)0V{PyDRp#Aei=LOS?8QASA=~$ouq=0@u^tTW1_j%DaNb7u4FNXS zDY<=nin!;7T)>4_a5)r~ZR~*wwkM#DX#Jr#EgYI+mYzI=?89JV|1lJ6<&^{$5_=7`1Ji4mzIspllQhq53`19k!n}>1)VKfqZ|4-rE^;QC0Bv zDtkS|MSDHS-)R0IxOY+_spb@i=ZPnOkh3Cc<;piEp5W5z_Z#BVQRpOBFXV#&ZRN&c zW*37x#;vHc&A}gU4@2%o{uR2>e5s=nR_GK+MMEq?pqz!RJK#iDsrcktj43!BzJXpz z({QaH;-?z5rLE4eK>Pp3p0n#nqn8a6W!1Wmq`-rxdO~^8_KFw_ls)#79%Z!qpcnl> z!^Yjvw$!E|ZLtBgk8$La9LRxk#*OAK#w#CvXzoZeG*-cZ?EE;y5&ovYZgA8$o*QSd zj;|CqGRPEMkW8$v%;al~kK&Ih5ZSeUx%&0jNv!MEhkGgkR(;(jzll#Phh@DjZYH*N{fxVIV_%e9h@)egXy}q;gM@eSRC??_4hB=%74lkg{+;Y=h`7k zoxE2R07qq|CCe{YYCJI^$LOjV18w1Oh>}gy(^oh6)EYb{36iXmJ{$MA!6T+Yc=wPp zaZynsx@?2Vq0{fZasDbzqOZ~jAnk)KsjCnsl>l&Un5c2JQ80+b1AYda3t>J(PJ&0s zYP7XSn9B^tj$n^`4BE1MTk}Ohc~r(FgcyFh{r>0Rt(8_UK_`LxNn4IzO9O7s1_(t) z)N##aj;*DgbKfoFI>qPl=%m-f+b$FD)hFNnO&-?@?O*rVQ}27~$tm-r`!>P^1Nfz8^T+nmCGRJ(CR7-Pm zaYL+#fxbkn!wo#foEQPpZZuhmoAvU-PnFmzVQU z+0^xxJ{8O#Pb@BX9bqPRD<_IlIZvx?yjrq3nPNH7cg=KC>jiPRr%HBXmw2wWO38)2 zj{lD+|9ZIRM6DVx`ld^jdwmiP;NW{+rZ+>uz&_V*Su+*AVHWd*upWLe9HT zgL|_EfCY=wH9lfIH~o0{-to4+-d_68qcfD@aJ;s{P_(4t3d=Yh5*9+z5AZU&W@zor z$Cc{?^6zCE-?y23+@?{C1=>*IW~W!I+QR!cYoqzMZLKCz$E=a|3R4@0y8_rHW|a^M zlSFo_i)hvgy|n`Lg{DLA-XcZMcs18{wSHLLW%uIs*j{I_lKwas!Rq54@Hh^dkIvv8vR*)WFwMVbi?88K5+d7 zWqq8OI2V@-4xx2IO2i9!g`^2(-ieAG2`lB0e5*L8nqw_@#2l4!}db zYohlU5NaH6I{a41rDCp1#@)EP9^YtH`_Usc|ixCM;?wM=1w)rAzX-v;l;~a_+JzkgRsL)M&_LHBeE21{Xu{a8o z!98}5p&etptN1CC4V9qL2UX)sg5$>Hk17*`&9M)XYBvJ-l20rwb82?mnI?+iX?3Ji zX{#Y?0%g74CVEuP%tVFD<-cL3$~0C1qmy?mnflC-;4q5oQ+vcl^5?R~NrO!y8(g;) z&Af?vfr&rmtScmyy&n!GG9r}!Mgsc^9pQ6Yc#sD$=ih7{j1y?v^WSxxc2U5)Gn zB^CwMKvoHJD@{Vu)Yan2w;s0lMbYa=v4__DvD~A|UY3{FI~#1iy3_jwNzCy2+I;rn zpf;)`GOl;yR((UhXDv)^;@im8DQ<`Fw}-5`h%IOIP8Ya7vI@}EgFfMwV%5P2BkkQ z7q;3>Jr*0MbtP+l4gLDH)^hg~Y@sW&&;`&odYJ-SwzkRCbTL+`k2A^h8ceL+{@7L)vO$X&PJAuFZ(3-w*;*@ z;=>6WYRT#KR;+fIn8*D(obdj6zS+}R!3NV6Tv9==& z1EBf*a1=dH?bXqtSU}g4r05vO0>(lzywuqc^T6URLaPg5qxYu8vmn>_2LRQOtH&|B zEJWY9M2lFLE(sAcFM0g|bjk#K&Mev&@;7Xwx3BR}p%c&b4RL@J!zjo)uDSn}+OJmh zd@e+Iyago+kN5sk;$T0s1Ai%G3}ySl8NvXk8VbC+YCEUw>$H~wnty!9Ij#0g3Q(KhQg)qzRbzF>2!jEH;Vqe6PsqwAL$)F&F;Mx z&N%4|qFS$9X&)ZY(`saYQT!Iow~h`P?oY`ADLN+_#3f6kgD zFcoAo@aq>FA^DPnIh$s89|@7lWYo)2*^+YTl;3_YdeZ21LX$pon5>7=S@c)?;%4?A zuG~M*Ch1C4I$A(NBCSGVus?o6>|>WjMwg>Z0cW#9D7fWQK9u$IIH)CEc~hGb24d8V z@aFm;*thf(9r`D}aduwL>(O5Ws)86VeL>{;UvoB+&O^gdW2?4KJmWiG72wP>z>YQH z)xNyFeNXh=hWwXBQ&kW8Tj@F;`5PwnCYeZ8kWIv{TuGCD+ip=cU{S@S@VzC{(lgSs zv#tjEQx5MIVQA?ALZ^1m5e@QaG5Maw^iY;gI;g0i0F_s^K|79wbR_SWP7pYNaw;9v zj^K~7-}Kx+$4Om4a^wsd@I3>MipC^Hh|?+Od6 zO?t~UV>=*Iivi+gTzDL8pcxA}`i?DWbF)@mIX34y1V8ivUywnfz6PwwvG+R!_ajA9 zM7>eiM4g3%JmFV*q_ zfdxFLj?dGTCHfy$vEu;o1X>Vspi8hsAFTs2tZ(Q&pr5fhf5u5HqhepwFzsBT-p3{` z>dRR^!_mP!0}zJ@0{j|j?vK#*xQL2~Y$&t@lPTT?@ujVZ@5fA#IIJ&d2uOpFAKTl% z45W~1=GE+}pwZztX`c^e{LpekI>erUred!ZttT{B3w=XEz*3S>gG5|Vu^BQ$1!Jik zh-Bt+2O~VshcW;t6AoaTF2KH{~D!@&MVY|u4=k729UR*a~!$PBv{a95}>5@{I| z)3%8t?v;ZFES7Y_ZK;io-u@Q>2H53?ZB1}0QagVc-*aLiR8U}TJGV}shPE;K~9^TflLHji`;?7BfxP)&P%oW~=7x<&HqvWs8J z)Yo&YITWZlJRXVbFsFF|Kk%%iq~tQf@U=8|(x;mrMXg&1yR8wIa)gz9K$J9hSAHpE zUuJx`CDjSI(2_`vbFrT>tD9_;7fQgLRYG%)PU_PhC!DcXLAU<;iV!uEhT$Q_cAURHhzo05Yvi%@b7Kk}6tQroO7OXaEJ& zB`)ZvMHRgwXQ1-Z4Lc;P-df-f=ie?2SEL|Z$S5x?ooAxFlBF3N^DkcYS7gCtrFK3Z zE!g1DEpA7x`+{tgJ*~eEL5UhFZVP0OvVR~wBQ}2Ke0yn(p3XfFljm37gnGoC;|U~J z9I>!GV)byC;jeh#P#F};5@0_#Xpa@Nc?_30>AJ?5yTqC2HJQKOeD>_wXKshSpe({4 z9hI@yb^5!A)C#((XC1r0E}gokz?zl{x3#0PF4v%y_fd?F6X}NwZCBSoas_g6XpKM9(V>P_g`Xw;TMLl#SjVy%9z~rx_)b$3ljrz~ zvCt#oiR7)E4kYn*9_&h$(n97I7TcL`bW`vmZttM#TynDI#p5NZZN#rhk%|xlAoIA5 zS466%qOR7$GRfZ_22^Taph%Z;NZRZ)fS>0xyO>duDn!3MPgM)q)(Z!Fgv%sJRFI(_ zw)c8vWhGXM4$RYcd-&8}Ni*Jj&)dRv;>|+X$W*9i%X?TM@12~SXztq&K*N-ssLaQl zq)2BWMYky-;k}n2JtI7xmr3)aecA**je7GBA3pd|#d`nZa`*-(O4wc;KYQ<@ul*M{ z`z#y9%%usD{&zW}Rtw8G5}H<>bmtSpUoDQf&1V+Wtxcq8=XfS93n%GxcGYN)@dSuX zH9*N)+3#mdlD=7gG6&3#$L$!rP*5a%K_pHa=x~}qx+(_MwI7TVeHSpIuCH^OIH$;> z1G5xJRqO)O$;pJv8&h-{ zsf|xovQG>hNne;qme|bO8u*D+I+YiRwZ-CRHCtlHw6lC3p3K70`)j&!zf`CNp7uEu zA0EyQF3!-yzP`NDl02JNpXnV7m^1AnhPaU$@U~QGvxbk_;Y?`G&C9m*u<}L2ed44U z6TRHv!9mT>jAO^h>I%NhCajz(PR7h1|CGBsz>87%p2ph3OG^BRlAXe3M-qzwft^7;lAm8w zvs(gCt^$|C43~q_qe#E`p|UwS2ffSq)!#rKZG3%jrsRJ#-xruP?qv!JbO`-Mr==sxI=HV%0pje2RBk`5zv z+IPl?i}xChV;x^;aD5WrI0Y{kDRVFqmbja*b%R||AW(Kqwj+yjx0Wx6ZPso zxY)qEaL=1YK+xsCBv49MCDvl%c>V|dd+rIQ=7bzlOU7P}VkUT8>SbenBlAXiLcjiu zeu{bx@+6U!D-j9~uV(id@DCzIo^R`8m*e~(izBRXwRVxXo$a_Y9Il%Mr#2n+1gcOf zz2SHtm)~6*F zS?o$4Jf(NOHS4%na>j3ZK572Cqe{uY)mb#K`?PWTl6#%>^1()|O+2m79;lfnT&ln1 z8~-g4HKLUjfX4>KO27TZSqk0j^Wxw9vMn#3RuOx4T2mx#_n`9dgiq1(W#Mx??{K<7kzeFDWEsHF&7 zN>(h@V@zEkvP*vBJ6K#;M`l3Vp;j~BFQ+hBI9|68R0?I|^s6{bHsy=Mj>?dEkeenh0usQp5p=zothY@glh3C&d3C_kKQh17gH%-9NIa$Np+3h zc;ZO~hqvJSG4j39sp<}I!9pG{q%YA&-b-nTWhomtMb3&B>u0gP^LgRQ5yP`6<%+rR z%k>7~#8tk!qrw!)ldr|qeN?hCQo}ZJVf)8}h0G@DRJF3; z2(mW-f$EHQp`f)?dfHxSi}sqZ2Xi|ao@RkYwMzjcOk;Nli(0RB{!3^m7)oWVv2otd zZ~Yfot*ap@p0;LNj>=?FO9Y6w? z{@&hQHU-|vMY#0gT>jd&9|t1HilV8)99NgDC$(elrlVrTc zn81`FXB0cSF86d3@1v#;?k>*J!!N40624tr*v)9xe~ve&+mJinHloh@u2Z=@KfATz zw-$fLi0z<3wt5a~5<7eJrBA^y6$RBu^jMFoH{O@Vx>&sK=Ps9T^WM2HEV!%6Ub&4j zU+-GWU3p`43%TG_4<>PSvfnMKEj1fM1+}I60B&G8OXVvwU^m>$RVUaaY=;R zS>?u!U-EToM!S#V6d;muh|VoRnc)nrIC|3blDwSd-j#@(T&{;3{H@C7DgNwL*wILk zWkqLv$+Xo+dEou&moBPfh)swPe;cdxSW8cAsh3$8b^6w4(E!VIf*J1J>UoY*f$_`Z zyqDrGM7_jJ1EuLF^jU5x z%hS2!-^JYOzc;85Ff4B;S~2oG?q%px++i{MxFDa9kX`?9;n+RE<&`HHfC`SnEe*N! zd3@{KyD#T_s)!tE%O`h&!?;gHZC>uDfIwBjfAlUBH=Gm9pOJaCwfi{IU=4x{=#yXK zpH?lLBj2&Kk}fhw=l9w+nT%z{@lfHByWV*b8yB+D1L__Va{~6h|22=O%DYSzXMfRX z1#9X0Aw&RjrW6CObBX>Zx4HDs`XKFV#x^!KfK)>0AK~2Gt$@yVBTM(h(*ze8CrUZH zD4fX`>i0R(yJa;U$#qU$+Z#!L4IHZ>-ZjhO#tr}ToKf!3fz`>qmC+z|Dh{aQV+7RE zDv{f=$gHjJK52rUjZ5tfL)@EF>Nz1lspxQRWC0*K@fc-I$pl!MNC=m&(Y2Rm~}MIFA}UaEJ9#8SfXY!wlC94&DuQhGi5 zieojXqzLVw%+X)XUPY{Sdc94@gA~{yCaW?@4pO!nLqS|6ZeB z!8l~5p_N(Yp8{;-YW3l&x&q&GZe7XcT)hUE1~29)nzmt)Z#VhMlMU)P@jgR^LoWL^ zU%4RV|k0y+vmo!u)CfUZ{5`CcKjZzsnhOU=T8h{P++0^==K;la6Js6 z6p*(mG?Mq|-Z0JfTk=+^6Y*6^I6$<0Z*WHK-gsW{?j2gzlulphF@#BE#x1!f$HcvG z>PW5$AI%le6jk`X`RM}BxBK>VN3&`v&9 zADl0(xW9~cU|~*LUif&z@tGI!www(mOsTjV$2yu9$$a1I*9eeHT9tM$KPUPPwt zowG}RUp&2gZ&7&-GG#fO+=(bUGwn$cIxw}V;B~#ifa^`5(Ea696@JgS22P)I*2J8e z6KQ%3@bqgq>ZJ!Pq%%hBawi4px{N$-3+$}&|DM}26jpOiaWPLi8qiXipZ*A!iSo?t zLmu=?K4`gyF^BQ5w&Ue@ztB{uZF_8w4Odd2r33aQ#yRQ*#vQHH))hV2s*1~65enm4 z;rqX)mQPi-@^c?=d4moq+aGBClueF zsXRW{{m8|C;tpspm7dYCgOmUZZW2J4Ywz)K=I(e$(YUjuXIaY*N%&nAx-N$cae8(M zB81L-W~%U9%^v~QQBgHuzl!4X9HREe)F%vMZg%nd>ZaT!MMA;7V_`wzI8V;6t2knX zeL1GWk+F+cw#8({%GNf_j!lz>LOnqlM68cEBqcoE-D_w8S-;p@?u1Q6Eu>dc*Qx~S z`m8ti7llmDAiK_d6RCuNwC7p4-v2+YNplOO;i%Br@F8V1oTr(c>j(NuR-;sKl{EFZ zB>ZSA%s-^X(=V%o=Bn=6D=B6!gQFox_rZ;$9)H46t$48=Z4)oBJV|L2xgW)}X{>vU zFV-vn5iuS-Z`16Rv=>(}4FS_&TtN6hq)Jxxxi~mJ&H)P|q4&nfp!w*_Cg=7ir`#c; zQ-S<-&#m1%&%Es|b$z26jOljiETz+Gx)7n}?^69u0VrDCUZ3-P0jJO(MU*jZ?}kVY zo_bdFnGykq!7E?NpOFVXnK1B7K78Bi6b1z2N{hfgrGIzkzbf=pHbNA@-;aHJ!FX(C z>j+pya;-1g#-9Jz={in$iZ_whxoB3i)$o41kH?t@q~(|Y{{0z^MZ+_E`-m*Etg(2X z>{p^ep@$Uwi0jO;x-FI7&s8WYERb+y64QNSB>9^U#l7hXcm_>%UUhXa+0w%1MK)$G zF1~VKbmQlw-q1vNSZ6{c2%nUpdQUhTx*dBT?s${awB1K3)8?LN$LP~${no(5vJGGA zt691q$~b@z<^@>athsEb#__T=c$3HAv_NSr~f z@D-nJ32s`gPU$5PJbxVmh%cvlO)ulWd!4iy3nsa-*_+pte*N=B0YZZ!F)WzwBbwY^ zpiw?)v@ipBsC&D4X_O2VefW39#rt_X6ozcP)boMh!K&uN>B+Usb7&ggsyKZ`=(MKc z=WOY>)vZ(Q!m%5Va^B^-;96355x-j7HaJ3b&jDlPASE@n#UIQR3 zeK^1b92?z^T6q7C^B4z66VUAb3+-73;HkTU`)1I99}R~w2?3U?us7T_1vG9DSzOci zWIqsvA}Wo84Pekc-tY3|_Ep&8ZXw-^ZL0^}-ieb3z3Gz3?Y4NuM0Bdc)L;(~mFJj$*MYtmt2ytM3+x#R%fW zURrhW=g(`A5upD_`Xrpfh9NqB+@Qv2aBz2Kd}!vzsMzcK;>1m}31(Pnl0qQPZ%QPn z>r~4Tcx-M2W(DwFBXfhPfE$l5F>FkJ6PSwl-%MXAf*1i+_ra1=FXY{al){f6I{R15$Pvt67P-O}z<;QMJMnb|=|lnN zeWmecl7;8tqbDwDOeD`?MAc-%C5`Pqki|uksumK`l` zN|w__v+6+aAg~OZAYh;DhclwOvBSX5IKELZXD)zSE%MDV3ZW}fi$ijW_iF6dO}nh) zrRDL8+C4s^&NZ!Oi`xu2J#;M;e~!myS%yw~HrS|^Iydfmw<@9M;9DW^K1MA4) zd4+4r$oW?1pI_KFv41pxw!PHg!H>M%OCqs(-Q0L zmhd*SPwvCz+To|er4F37In(AsBn5Ig+TpP(E3-AD9?uoaN0m2iJ_^++DH7VrquF_Q zUL;{1%f;-+n<}4@)!N^a#mhI;43bC7yB(O9V%grqFJJ=4sAFW$XLn{U)|t>L-1)IoBvA!e=g9dA@r-38n%ZgS750`IhQr*uvs~(VFcd><+@V2BUz=-x|FiYl2m! zbL<%`pvQVbs+d)0IGE3?Ipl~BGbe1&r!WZ#E-ODp zDgz401!MRjO~cob_5w2Yw@6DFiLg#s353s zqlmZOG4a`f66rfr7qwU`8YM#S%=v)AmfU&o+7J&qsO6NwSq{a*ktbL4Y_%5+lX7|i zQ>7m`dSDv;2^pDjTm^M^@V6bl6QX~7mMiH#ji>Jt`y!sEW%29~heMQKGY{*|wF;O;9TwoFo;+wibgHt<9 z>D_9m=ln}$U3omfyY-VYkbg9aqOmzgfrr*fI^6gXtZ+w{*zygI3$Q*r_%#4IUCoep z=M86ZNtz_#P28H@N)DZK2X1Q6ex&H?>h_aKwj2=5qzCE;co!M4><7R%P?kpzs^tNu z!}eQk8O|q~@TZsyXz{}03aA>!oB)UKdz`D0(mRCjrrEoQ7FSAZ5?kZ=3|ecQq;%8* zMop?+FNkj5Ldw*^?9hf1^zdI*d zSKe{*0o_eoz3&_3GqLTyp_0t7eWC@pm)CS&kcl1R;p!uux7nrdb3FPx?ot}pzBkA@ z(@kLeU0Nf&-BUe|C&c-?d8hGXD;K3$UBU;c4#PYkc#XcC4tnP1`7qh;9P+UIyII5ttMhWs|@$^+LfN4R{GQzq;}IgCQy~@i?EoXf-WO*_Ai#^OuKpE<9eogJ4#TRnSnq zV$u}(gIrvnLcob-=&Zi;M(C)zOv70)TcBiCiJ@x2>G<9Gvd}8$bLQqmmPaPs4iM`L z$5-1UkhRDA4)jN7nJaZnDnMmZMardPqbyRvMdZJb8FGm8)C%b|7KrW68k08Z!Z2h$ zlcH*&?f8J$Q~SE2zMyvipgw+0RQdytSS zmI>`{GEkDb5yeUlQ+~L8-rEulOU3hpuUe{3`pv$vQM<#e{}zn@eWY&^dU~0ZNl6W3 zGf)DMo&d=<$)pHh!)vi2kvEv)(p~(X^$R~T8x}fq^;O`}`tIC!`&Fogb5nQsfk*v& z470oi)|1iVqUz;W6phal7xpWG$$NS)S+SYc7 z2l@Vz!c`4N1DUiP8wgwcbH3bNawTM6tfRyqBytCHVAv?tq{IyHX#A5A`?Ap!A_N5I zJoO)cMD|V#J+8RZ=X3p8W!!#WO!f7MF-DtL!@=X#%0+eK8B+_QY_wbsofjQCzb=<+ zYOrET3SB*dB}h|*=wIi{#z`N61Qn5kq@#&%K71bnU^r?$yKW|p=e1m1W6G4qYu21F z`A`C5dgi0y*!{=_3OU=b2G(mK!zK!9YgcV|37l;z@8&m}_x%P9wReBTXD6k_ghI3b z1w8%N>*p9DeVY7cT#$(g2nO+_2*vYoCPgV8y9&}t1=8O&KJGRgdX_ISoAsYLCnBNc z?iDbw*_br4A*!|G-@^`~8rmUTmGtVC3dG1hr)>4U2&ZyS8brSzfAct_d+wRn&DQ7v z*%?8^Rhnt0`mr;y{I&BbVT8ENnZuQ)St}s?aMluLQ!>%mIL-2~m9&az;9#fxm9X1< zu+}X9y|AudcJ=gRq%b45gGqlZzI@!uexs~IqrN+)Dh^qcUaH|o$U-EK_ln%XSQUhH zBuwX2P-Z^WYUPw=t!IH0>4Sky(?K>=ch$5FjvOos#h|xOU|h}Q!!~E;!Ffdn)66_! zleUC!))|y$^!401^OP|=cZg9_V=pjnXVoUW(3dpiAu5@LG*&@4<2$}9B*EjK-xN3~ z|NOqONH6_(#7mzaoAX$&uO{R*!IW>J>sv<>PmQh^RNqH|K+IL=p2M?ucJ46I;B+`? zCXWEEQTNp>I1`I}o$z|FNF3A?TI~ms$nFIfft+Q-^)_o>Tp`IwkMMZw=;6Lx_}os%V)@`WhZv)gH9$bOg%loX@oiCSrzLM%3QAIpvO z`PT=fAD)x0(hBp%$#$$vIuOCuCj8PZ&kFvEAWQ@N{7lF>+fQX1I|5cwc+O|$7{x*R zK$RJ-g*h*(9aj1!P5rQ;D+|eD1QMKrB^AlJFL+3zJ&{8J4@YN=RxY55bH3Ju=7aGS zuio)-I>%L#)zcwFt@=M02t6eTu^g_bsv^20;1e^4*^Yt(&)Dum`2w||E&ynM6|WkG zjHS>%sPLrIUdY@$d6o;ZW{<(J!u-F@r0CfQu?~x8Jh?8Ud{SZIX8DJTH1&I+D*d$B zg5B*RAj0!&Rb%Yf3VoG6eks=beb&ApL{pEz3n2aBm|oJOqHs_V}AB= zzW@8%L!6DaS6B?&Me;k!#XFRG;C%4j_}g5afd<2MlXoJEK@t}#ZC?h9|2cNne^t_b z7TfK+6MzWzy&vru|9ea|EzNbZ(6R!53Q8e+A)JBo5Gw4jYI2UV_fDS+kemxAnwu6` z1-Z&+>>ffuE(6SF5X?C|(LgMunj=S)Mi;QRnc^f-9!S2Mq=jU7Sh&2SoW|=|t7GY) z5MmW^_B6}kJt_UOn&NS)b(elwQI7ZC>wW)cWYscZ&o}GeKl8WU2ULISlaD0j$l6ws_@3MNf)5|8$q_)T*8yBSQZwxEX~0s$ zF*#qY8w>#zqYID)WS08fnIl%`(cG7?h0>54kS6g+`t7}t>Ab|=0@D;o9l{opvL6*- zwV%$L4EmUurB<|ic~}x)L=)x34~45X8U8=B_v9DFF^g%vmA{`0hC;^vnnKgt7Wn3{ zHAv#=DifQlsa;f0(i5ta=L%u#sAGq)_X}%eFRe8suJwLscU&oYf0ysU08MPL^rLsF zY`^VDa(^-AAkKOkT}!3J zcz5E|yVy$T)9n}%d}n(%-}ZFOtA zl|Ko)1PC8S6hgwFp}okL=Qv1#eT@s+rx@2qq$j9t|6xy&O7$8rU!r#c1bh96tB9p@{eJ2S zL-Mef7;C%$pTyKd10B*vzs3mL2^^WO%exKyPzsh~rh5NQViU_uYn5H9pN@?GfmtxPj*^>2+791 zYE2E}xLD^EEIe?Q2pnv7wAY2%WLi=mG@7y)GKqD>ayuN&zkPS}w!k+9lT7IlyYP2Z72VaNz8O&nz#t4ZOO`W(R!>B=2Z%*4CMs^t3xZseqwLmnXl; zKEDrKfK>P?M6zOn;6eT7a&RU$gT!E%LkCq>1ygVygZp#qAn1|SH0%9IxU#@f7tAOf zOliR0%D#_y_%We=;Pn7t)?awHvtjD z7b>jmshK<+wT8!$TGzM@n-#Lh0^PP=N0YuRAmUx^mT~1G6i+!A!|H%|`Rdg~<;&G$ zad&4d;)31yJgR@tB5YqY>1aGH0@T3*^vw@&LFWB_wxj_;yzfZ;%USNsxgeXoxi65C zOq!%<1&sx?lU&Oxp6_8}<83`Nu!u5=A?Ju&`PkjZ%KqY-@Y&YY>Noj!4+ei7?7eMGP&XFl{wvz=>P5DkY73Y`tD8y=chDG! zL{+Ns_y3F&62)jxIqtm?&qS2R&u~&@rNVSH((74cyR6~F){JYc)3f!1e>r>i;8qsm z!ZgE~)!fZO%j~wwJqcY#mwg@wI`31qv%X)S58F^I^}xN;e~bOVcKuEq%X3Kb`VDJ0 z=E^a69RIl++|;N4JtC`d+-caD1soQ+Fufp!jD%fgKG^x}o@4YG{0x=JPMN0#P#_K_ z95lZr?x>_iqKkQQnP`%Z3Tf^c1ktbPojP%FX7~z!w|o5Gg$SMwQWMi9)grbQlFdjb znDeB$U6!hd)N+?PvIlQ*a2`86ZeqAIbp2#v!N|t&;o00bZ>p-RRj8`>?BLly-jZr+ zBIgu0yMJ3=K!n6h{pTs*!o+kMd0Fo4CQ@ZwNcbWXLRIqpxr-4`1#!>rq>d z(yfS_qxp-yez8LDyrV!mWzig-qE*|{TP~Ss;_W4zSCo2gox4MXzD$x2;xCQ&le)k${B3TAcMP2;F0?NuSCuX*_NG-_HwnhY~n{GbdTMW}ZbB zj=((4K!Fl-4SD5+MiZADa#n_DWerDAAxIunQJ_2VSlplTe@b48`*kVGTfzy)nwdwt zG5oy@JAQg25Z>m2V2qo!6G-<3sP5K56A6Q1@suA)VP6^;owj5vy0!qSA0wPjvOV`5!&Whh5dzkog$7R*UZRBj$ z-hVgs@p<9`>46ZE*aO|Shzh3TOA+zn!G=M)kC1|Dg;`ay?hlcMRDOv0hIiq-Xy2p8 z(9GNTY`63HwtXerXyA5!VPPE1{`dv8EMaPinDwq6rp}xL+o4JCL3l9*JjTKbS{R0d z^A>vLSa>GkM)GXdt^HP0F{W-0lc33gfpT@omLD7SnoagVn7Vr^O^jkuFUIJPlh<>M z2QXdk%>Lxp6L`7{0hTqnV+?t%!wfLS8EmEB9c6AI77p&TaoLgcL!6}tXV(i8L=WO8 zccLM)H<;!UPk&ixW$`?WDH~F!AHR)=ULW3l9bu!YzA?{u`pek+i@d4H-xQvimUo84 zGt$70kz-^x>`zMEb83vD|3Lcf_olx2WVzKWY`Qjm4&i@%>e90plb87581S`@pLKY< ztU5}RX|kTCyqf!;!?HlmUf`lj)_ukX?zYFQI2-C8#cl=?le-5WoQ4J!3FH_U{QM`7 zY@RupM|x)FGX1~4l>4=#e6>D0_)xgqB!w{so23HM9%OcC=!((v#rY{Q2^&l%ZW(dHZ^WKo@gt2ZrcSAP9toSw`8P&q7>~gazDdO(zBZO5 zRuGvCkwI#v`j?^%E`xiwy|Opap={A^sx71CPAVa!)oy4X3jx0{=7NhfV#71{WV!(9 zhp+eM!SQ2JD8Io0S-xwp-Lp&}+Z@;VtNAv|s-fuhOXs6*} zrXxyD-nW5XmXMS*AS+f+jftU+k)AOz(dTj?MP_SI{J*QKOEt&V*F!J<3h{V+ z-liOdw`D_?f5#Ny6gDB|S0(%Z`H)&ttqPK?LS3-UU@bUhRdSxIu+Q1q6fDWJ45@N> z3BG@WMF<NMs$CT(Vc!)J+n0w##3=zi{K-a9~d2VI+m2J`?oztu!hZwWmyh|_$|gp z;ya61|99fyUjd822Oyv|M*i{x;Xe`#;)yY;uy>RS3ku$ShaA6os}LR(#PwgW#lJmj zv@3cucKz1hSXc}5<2({UqKhq(yHvo9Xc~;x{!Lz2jAi7DU@vE{q-quPH$k(z>(}Ld z$=`4h6}I6TA|1(laGgA_!6pRw-JMxK?AyZ{ z0cT9&B3>F9_@%L?tw9kqCTOFZE~#E58*2%WU%kVw-uEMr6p+!(EI5&T3R-fq7lQfL z#o@SftfXYwf#ils9MI!kD1K?c&sC{izh7FD0)Xntp%S{2w3tYRKwn=sb9hPamSYu* z5@z&wxa=ZWz`YO^WVGRf(lKM5+S6bN-%P}W2_YMX2nN3rPhV5Tamcs@f8+E-McwQ5 zEqp<%_UnJV*?gfR4Hr6L*{i$5t6yKnh2WcT5l`+XdFBp=8px;`G8X$G9`1fw*4W@@ z=!cuX)OIewB`064zZkel2j~oKO4Q10Q5<1BwG2(_d6eqs(s;o|cAPRU;L^<6 z_B;=)kQzf*lClVF9aujq_);1S-o#|9m;=2kCe>7LJ6dO8|Id{VIzE;hripcG@5Ak4 zGJLTT81Z(Rp50^na+F5C?!&&}lk_w0&=k2Pp!vDw_Ug#@r&F9L6y!vS${d!bB`Qxc@}mrbx6Rg1t1Ghv~7a6#?ra_2h1Gup%}Ff1?_L-as#tro>p+Q z>CU^WS5221E622SqHYk5Y11I)G6~ZRT4q;#33kHr!eAlXJC?Y>g|AW_aO+ z$4^OHpzVNu`7ph{rR7WCUedw)Eg&*fOsZ49SA z-W8ZPbUasMkLGYX`o?dRxnu9)Hg`zd-qxmx`9=e)fQheHT1tMi7db-8Up92^Lc}J_ zIg=@AR`^2Y%=DHGu|G?_A?!bWa3>z?Hu{uw*8#w9&Gq%PnC`wCD(nMu&k35hO73uDTMAXTKH3okhj?Z zr_~FN)Y)I1ISLt`DM+>lf|H(z3PJ%k*Ob!W3Fd~*@1263Qan)h7A-_y=$sS@pT&^! zA)r|)z1c+>&pzxH3V(aqXfb7h6In+wPh)a(gtjckX$1}lH zQxh#z_;P%GM#ZX2yP_bXOJcxQ!5dukkbYrNk(H5EK|*3J1Ss`~O!;V4y0?OvqIG!w z4~(ffNZpz-jPHk+FW|;1(p^tY?ts=}=HO5GL>yzv24?OHAjz*BC|lGVR;2Plm$KzH zlp^b1&^G53fct1xpyabUsaT%_I)42A&Ex#i)w`V72<02mh zC$n`z%ZY{*2bJLUoP|IF&i!NmjJUz{I9n|shDbq>ISPKS(Qt9zEOXR=fjmeGIWqS2 z+Z_sh+V9_0P)BflD`vQI!&0XNJE%-A-kF8#WynW{w_SX%%mMc|l21IY_Z<~|*fsMT zBu%gUimk=3%Mwv7UnA zY_nqtRW~A*fQRjqs@(4BQ6zeB=ajIgBqC79S53RTD*aS)n0Rz@+2{EbO@J2#dEI)m zn$Bdqw$E8gEk5ooyj;2$TT!E3tc75#cw@_S=luY;{lf>^Gv%T8?pw@8E|Hg?o)fu*kS}Md~!RFxbq+y-rp&d#N*JWYguhf(WJp&Sum&=8~|ONc{9L+ zs*73UrIXvKhHF6u9Ki?G>x&p+o6v#FveI^GL{GoUBpQn93`FxN@Qh6QbiD;#JY$#; zDxI2()GXfL^Xzjwqt~zH9p5`W={_W0CV7=H*C%2q4J-te&I6Hb%U0$*Rkw-_nbD;l zr@{jC9apn;*+mnBdOzOJ3F$LSCf(B(?Iz-oDx!|~BT#`cvkP5CT2hMnHd+Xyt;q60 zi|@wX`l4TAT6*@QYNE&xw7g&>BYg6%Hw zZPgwY*!2d0rvoV22~f6D@Oh@hq&g&tDKRCr&-S5k z9zwr1^XIb$hNP-=^#x71ngv?E9MIa`6FFX2kJa534co51ndWhr!$HloEWSUfbF*hGU0HM zt(f)4Tt2f>9f9H8;UTR9@#qnSej$WNV;EB!oT!+wAwdwd2*;CufkV!g$9q^@9Lmyj zOydUB5y?#2tNv zj>8ksD|-}=Ue39V<>5h07{fS+$0>4@-t2%vjgD_PGSd~kM?Dxy=5Ll;cc z3;tlUi!2khA&*DkeW5mwVoy?Gb)W_p&6H|KM&olhnN!0CngkmT*aP;CGSGNDNAw-~ zgF0ddBM4@dI};M!34BfcW3X)K)V4-=3C zboSMm_!H(+9WI8?n_VcngwjF-Xj{J49(D2c?ebPG1WSqspjKt9ks5Km_l8dj+3qnf zbBkSOT4BEl@+vVJhzF#_USbHOiG}3BofY^GE2&@`kWs!lu;rdV^;HUVJpO;YR-RSV z<#4%Y{Ul&l7aCs(T0IwK1Ie8kp*tXFexo;vtrQICL0`>Gk6?oG zPoGo+=`0mZ(mdr4+9)WWN@=}TiY@n%d|pM0ZGCVjf)uHTXyW;wuI@Ig2_(`qU!t9$ zVZprf+ocf3+nP_lGMTlCypFXQSpWAek3)O!gDdvz)kGDqAsr$)h8007n*nN3d9XDO zqiEu_`fty5(tVfL8FJN#qq}Xe2wol`no(K^wb-c%SyA$aVW`C3(hqq?F@{7|o#Fa- zmKFpx<&MF!V}1rq;`3$CV<63+mClr~Ro1OqeE!vv7Y2>|L9s&qrYa+5U|?*CR0yEs zI@crJ&LF#vDbK}^ZK}HC+E_#~Gj$ct7HL5_Q4pl_6~s59e$tW)k_u<+n7x69x5{-s zb4FDZg4D?MvwYYa7SjcAcS}UZw%u%vgwq`ozi;bWRa8kzza*KYag57(zANkB6 z-!!zk83mN4@w0@CXkF#Qxp!| z#2xYeFg$v8G%sl)nx^OY$s*pDG^y`f=ZHO!J5d@1!8a*4zuXdR5Ot!qL zXovXpj2GoGxcQv}*`N{1d}uwppl>jJVeT?8YVxYV-UL+ zckhp4N~XW#lw;ky&=|6YCJ=9iu~zDi&x4YP&Rh1G=Eom?j}u7F2c?86&3p4?}~ z=y9BF^PYrtNW1%$PXxL(^`fg(>HsKq^~V?syrATK7ml539I^{{xd5uWd!+!3ZUS>x z&T^m!#Un&7aK66`A zZPNGHrQBC4WL@iz5swU(N`>wikBlg8O*02-AE?!=p^`@uxjnB2|LNh4I4t>R)=H?_ zLr<((2(UXjl&;^2jkT2OAD!K7(jtTo_Bmy&1?Es{pKgkH>a;^wcJS!YLWT5B|Iq>< zNjv9H=>Y5-OX0r;DXX7IoK`g560yFs5WrEW*^)Sc)bjIP=uWvQBnW^Pa1sT1fiiGH z%{XcT$|kOfKL{z_G~CBj0D#Sy?U{r#_bwfxc;#$upb_P#;mv4lVxQ_ViyK-$AXLA6 zb*@MXeA}A&4L<=%UZ+iFutM%l!C@c!oIhy9*%n`WE}IcBn7J8T-xj1)OK;=)eh3k^+NShWyE`vE7fv&gl+TnKAV*Tn8${yZUIS*Y1}bCk0#kJhH$lZlwG&bg`{CD>{&NFw?J&GFa=hr* zEBC>*PG@4s9XuXy;Qigx(c*wp=E+^>>;!n+3dk$}h`7f66!%%Mp@y(o!A?O*h~h*6 z@tQIB%VC8$5A3?>3q<;;f+E^MqN%+pxzDEubyoZdfa|hCBpZ%)0dx*{6I?XR+- zFu_CEQOh~rB(sI0c&JAm^i5J(x|UjG^{y?f!xajB7NmC7H*~!1I=-1~hB0P*J1e4G zKh>V7uRvbnOlS?t#W$kQq(?T`(7aS*6yVx;4hU@Wwi2R(wt+Lpdn+t)Cjvvj_~1S_ zx5uwTuD-|kgTVXTym>edT;AW$wB-xGRkTyXJU5$qWD>0<&|jm3mo + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/wrap/python/pybind11/docs/pybind11_vs_boost_python2.png b/wrap/python/pybind11/docs/pybind11_vs_boost_python2.png new file mode 100644 index 0000000000000000000000000000000000000000..9f17272c50663957d6ae6d8e23fdd5a15757e71f GIT binary patch literal 41121 zcmcG$2{_bm-#7dlYuP7j)*2;A*6eFFmdcVCl08D%$sVSK#-6`~tdTIu8nP>8iAb_9 zL)2s)`(O;uIlBJW^<4LJy~lk&@A1CVag-dh{C?;8T|UeAoXD#NI?N2b3=jk{U(!Wh zgCOc22%>@=q65G27mTd{|IppMqJxC?DSxsX@)IHG7<37F-XtJ>VLbSrrEiAD-XO_G zx!q19+z#eMQJgxu2;=9Gah;QabMrGu=*Ck6;8Ic$aM$}OS zg7;p(a^lFo7y=)c-B}%i^PqzUeLd((3kW_d0lVX^DPi=bI3k(7O?~C}yW)A6q6IQ^ zCUD|s)fzwcuCiN|2QD;_jV6m)N(+_n#W9S2GNYHD&tB?|ybB_pm1jdtvY}D2u${ zg!|gpCu@j|!K&j)dz<%1qA)PDXjCoB&wydqO=O$brm2aEt7uo_%}-I&xuVY(6}v0+ z_4OrLDw_gS)knS3r(2{Iu-JO(8N1w#X4WA($@EFcy-9=vvA?|nI4yL1EMh6274$;6nK9*Bf@SCC*S<{Jq% zsbNcMh}A1ITuiUeE=BF=PLN3I$$BEmuje#iip7(v19az? zW2Z88_AI%0?Iq|vwQ)X1{Tr<*CBd2gVOeYM4mUr3QrE3Ym(8xJfHuGp;{|{76weDr zj;-%FwMePTaz&GMQ5uo^B-?<;7)ub3`W+6dZrJDVUATpUuc0)?M@DvPPwy0(%rzKs zgm5?85CfH|mf6rHTaEjpdom}FL?$6teIcEVO{4yOXjuRr$Payxy4Uht&c(VTt3?4; zWZJKC!@@$N&oIs(X>?Zu-A*L8?4$=1h+A@vgs|dCUnMk&9)qz2p>mdd z>l9ey_X4XqCy~g+OQBw+ry;S3z6sxP5$H`jXLmf+GHfiyG9lPVoGaL~AB*aHJYooz za)f8?3?xKdYK|O%&QWijMcc!66;t*0jL%mO-r`K)MmqR}*Tg9 z%{&F+=$^KlWsfZf1qMDiL?VB<+IN+}>V=v&cWbsF`Kb2O*dPy?)O#B@?xMyIP5N&& z(GFKpZCQDgDY4ndbYyk9ws|cX_ZvpH+e7a3%SX`W*dTkER8>Qi5Y@5>L@b;Oqxub7 zHig%;_>K?mTAVr(d29Q@MhQ&y4B`zmKs7`+sRjw&wW@xRwYFyluc2!;!tPv|*(2{= zLGD>2_w3PqDOB0k$X6TH(o8Kpdjy=TZftC<52TudJq(E<{G)W)(ff4EBB+L8-|;IE z6_f-HI%_a0lG9NnAs8>oTXf#dZPDJ$I`HTF-UZbJU2)n{D$PTa_i)6pZ*_0V%DfE3 zx$5YfN9*e9N~pdn4mI+(nHOSZQ5#FSamshRlr!Rjs%wf#z7Wo+Kg`wHc`GzHIM^?n zyw%wBwh7-i`*!yCZ)bW>2K1LN99d9DNn}EHKmGKFeO{@T4H*LA`tt>ZDVN z-#we^PIvV*VjlbYHG4ye2Y7QgTq8LcyK@rNpqzA>Tm|xdWnf^y<5&C!4%#zCrCC^5 zgeeYrG4O|vMNJcksstExz46|*UYl1ay=^ge;uwNeDQ+!tqHqKRuLo)aHlr@CNZs79 z&BXYGB=r&6f}`g zkkb=M#24Hl9qM-aezR=I7y5Nv0TC954@^5)18Jz5>fH%&nf_OuB%RTYQK%*+O*bH{5i>v1$Tz15y{=t`GCzk<2dU7O@zIyCezv1_ZOU3=VzqtGk; zG{2K*CUltkLTSs6zzhD*n~S3*(6Sd)q8R5hP&sH#Y9gn%p+Xp)pyiOTU=FQ@@cq9) z@tQn$2WrRV2J)iylai7;Nug2+2Km%IYkNjWK`OTBoZn}1m6G=g=1`3Ujjtr4oXbEx z0-><6H_lU0M3C#w#H$^e?17FULI~qztr_*}p?AB}m0pvIw=$YSl~V}{U%b*8gR8ZS z?jH9}zA$dG#T%4KltrE0`Qc7!Wso{_EGFl7Un9X|u5O%2&O#_qYvzdVwB5vm>i^vJ zx+;6G!vO7M&HKinpddQ_PXaOXwWlCOID~Yt3UdS1KuF6S>(S+vP9zS#O2()rg>3~6 z`ZlG4Hb8W*Tm5{7b*C|FIb^@?%a<>8+6fy7R0Er)A%_+-_`f01J-ThW4W@V)ijgK~ z>WCz63wRqB+P9{h@1bs{U&B|pqr+P{YFMeD$%nIdgY+gIBWJk7d$f$!FYHZq?{Re= zNf3atvBo4-^7~yMw{W4GkY;0wduR2w)DymbdQZpDto;cabrkthSWo;(`!4hC$6;L# zGKMTqrt`NS6D%t4pipJ9a5!9FB)v)>nK-zboYeHU%Ys6q-IbkZkp-T{tD#K`RuGmK|w)E0uJv(_60u;@kdaHM90Lc z;}Ughi%D73=jN?6i?DTdBxfj%&RGX^Wm>R-@K^)fr;2VKJJR6o+qZ|OYL_lRHuRo? z=$3>tCQbZWy~!%d%F0I~KXQZQ^bmA!c97XNKs6ji=VEc2AvhuNWK2ErY7ez0;fFJI zahF@n@Sufm>&>!4>Po)D@L7I`HBF&I^{qwb6?cMzyer;5JjNr{gjwk1{>jPA%*+X* zS~f@nE!DanY=Qmt>z5ViSu|22coppk2dSG32%RJ~?)cV_g{7ya`TF}*_H1FZm zR%cYk*4Pqav9)Z?Hn4YYXveUmeV=3k>0vBS^7no-oAJfkB}OQYE1`*Md46vsvfW~h zwHk&dkR-d^uM589CY%khn6&DxV2j@Q~=3&PXRH#LwpJQu^u(l^d+A2x)cDBoO z@>vV{yz=t$2_kt>ct{dt$9>@*Br?}~y;o-+u1OCejo!X&lJ88G)R5QKJ!)xC?UlKcC+qSM0Z^-1gyQ}u}IN}NeA#1FYr$QX}Yw7*wtxJT;4_W8k zHx>q+ot-_OkRWR8NSY05!w+IhSR;)VV(t|+;bW!iR!2!^|I(W2nxa!^U3Ux%MkFZK zG|7V)#7a%*52R3Ok2@R0P_#bwLA(J8qzr zU~`qJc@E@H$A>k@^WvVW_1xTCtxIXfr<-LWGq2p6E}_y$Twk|Y4@(&J6Oa3QEVx9p zn|d2@SkY$FH`@R-LD;ZjRs{fdZhpSxg8R&_EkH#Zyx#U*ob6T?Wa&X)jZy!s;`vO5 z$*iyOqESI+<~CQi)Sl{|cvdi%O{6DuuGQNdt4>LUCs+WAv)%fDOxDlhS70gSRR%lB zjP9$7#Awg93&+=Eb93$C=y=#Wxl}!M4z1o?XzszWEtMHA@*Gv^TLL+b#IDt=5F;%_ z=Xq00>r<2Rn=N2(@g$WNObOIYyL<&YMSp(T1P}nwW0{+&P-NXujd*}6 zJ>vFIl$=uZ4N$^vL|GcCiZ>GWPjW>!TtRtIT|JJ-y4EjQI5*rL@?>oq6gi^2 zoZO<&O*7D8OeTE?eLzYT=&B0ZK$E&q@PlJR-v%+^KRh->VN-+S@qwxqpdOaBrqsku z(?Ie}_PnaRyu9fz?3>s5EuyPCdE@e~ zBpakD`_5V9h&~rVNG?n?kZSD2Eh#PW|NjSj_z;U!Z%uJ994!PXUR|({#1vrT2FZe- zL$yc!Pms004$L%Nfb92z3~e8H?FMno<6Azgw66LJZZvB9gbFXpc5PBM!`OZ{9m?Ae z6*|qgy(JjvOs4$BvO;<};Fa!wPC-FK>D3F2bJr(V`jp?unWHH3MK&5d2kAN|C#MJN zgGttD-=@dqS-qPAmzt)kI1^G^Q~V3&N^(T!1aH6U5RJ;21x4{O?fKGSzi0Qs736+z z1L^@g&3l-AS0{Mkb#ZyQs2uxT(Vb4`o%mn7+9OVii?Pxugm;jkVUG~Y1}Gbs$z=6w z@~bOqt6z6k)V$Y`FK?i5hbCux*W*9k44a*u4ZIa&4~NHUfL^CJ=qn`gsq9+e_tVpX z|GcuBm1pSzu1QPKJu%^+(q?;^>|t6o{b_n-TH@X0gBDg_jpBLJ{A-2PF;)A{-5xJP zB1SVc;!6}JY}o&~DoR0Dk|i>p>7FnUbPF5w^;ZC$_h_dc(uBX&58_ovo&9{O-o6rd zak$5s6!+4m%(}_jHs&y@vdu5<{nH&>HKuJ|y7kfH+C(6rgxjSExb63*<8(>OPTuRS zBo`-PA)GMl8(hGCCT|am%0g*7kL=vOMArx}6iZS*8xvT`fS<6 z4%J&KtVT5!Wj8-Xs;Q~Too92seaPEW2l*@qM@+x_UlExb3v^sZgxC= z)W6?mgcpoO>N@d6q{T{Gx}`buOSRs8WXHo}&ob04lW;PzV;gae6|&>;mWsxFz6j`g zpYQl%H#|id%!zFC9UrGqY*+lToEPB2C^zW*l=oY;sexR-mywd${Y1!wDnOe?<2AOZ zeq?_x)lwte`LD@yaPV?~?VR;+fx9M!duk@dMz(Nt3#3QCY=E*H=+7W`ZYNKy3_i0z z(#tc|E^BoE4 z`~{soJbFgD?fbTI*XrAkQRlWUjoz^5yd!FcFuz0;ynkR z2yX10tw#jXgbE>}z|_L%a_3HWWkxs#YV+d#AXQ&lT)adxYF^Z7Y8CaK5pUgh@-LSt zfybDr_)oG%FnC8)`+4}`gOF@Zxr$`bHZmCywnR>cOGgkAAl~A4zG5_;+FyUh+?rM4 z;yA+!Pom3rW9I}EPI>ewMl`>sCQugL2^Kepzh}+;ZHAp{N^RKOD9j}OrJ<-dFS?22 z6dayJ1yX>r(At{0*U7php7$6MTkqC~KjGy}6LZ*x_qGtNwYWAHLQDY2laz;W>B;At zG{+?4v!g%!rq*IaB2T_|0hx5-NTd&}%d~$KV2TP#6jqps$$=a9G4TbIv8KaMFvlBT z>;4c67=cO%4(Ff}f3`_43ohQU-YpdQxjLfH+QhwPi7&dEQ-vGO$qg>ey2KPYr}grK zA6t%hK9&=4ji6}o24oUV!JRjl?>a^%w^gFuWF1pFVSx@j`dRUlme~LR9jb9O?Q6MsbYB4)#*4w6Y0+SpqceS_JWh66?wa&_Ts0I#}qg#x}_BWXs+T$$;qm!DhWuS%7@K}1t)CdVzpD$0I7#gZIckYlC~s$-JHm$WJY|NB_~_ zE&?UP=zf4|W4l-SQ9GXE9tRoW#&}_PYzA1qD=0(S(zdmF`h$1`lHfU1#;js@E)Z4g zJ*44DoRn~5OQ6NpUPaD<`x5iV-pI!?!o*8KprNIh3{CpO|5cE{2Z62;gnAR3gNe>z zGY948Xv9>A5yxURB`#4RddN)B{C~{#B2E0jrE@N;5)S_zP26ak;qLQDB|w`mf!|?V zr{20zG7se5aSBX7c<@qDf)LX-eF|0}-|7koVf>;h@@JRtc&%vEFW7Gis~_&ZXtHEl zblvNwp`oEZ8%^5C$cW!)_eG@1WdPX3jv?~-?73dgxq_PWIRn!r(<%-KRsv<$Y0i5- zmv;0L=TiChr^5cZp(-h+I@n!MtxcAYFJ+lpzO<$!gTz5J^Yp}+F{Y*iTHMulYo zB4U$)6XR8~Y(@rv2*^W&qm&!U#E;vnP{R|>QnZDG$2ppRggO#=QFQ+HXz_d~y!r8C z=S@~iubO&s^Kyrs_1V4*DJCMR5oZs|tCEjZ^#`x?=MBNci1~pxqb`(^>*DHK^ahKK zS{$oc(*zi9z)ujg53%_l<|tO~glW<+2el^?I;8BnxVV>ic~NccPNE%;U>;Tjwj4uQ zG(F_62)lPLU%h%ojrO3tp$~ulai$h~Kvmpf&7*B_BlFYqKWZu~H(o=HH@5D{r0(9w zh8iJx)1E)yw7_U{Me3R&S*RxIPa&Tjwf`U*1!~AgxI~UuGfyI|=T+pE;3ed({Gw?5 z9?0DIf;n!O!7Ur_AkJbU)6%8m=JzrPZRjH6jrn#e4u2SWJ& zWxb)aJpFeGc;N61@YuW4dSay=9mCvytZX5mePKkW)<;ac34Hr9hgLkmGBwl-JC=|d zz-bEHrtVn)A0fv`U8lE?vC#_fS7$j^%iP!i5h$0Z)2;*hn?MZ}z&5PMa8nqq)jB84pc- zvl)$wit>T+pGG8aa&<#rL2Av^EPeTsFtjXt!UI16RiU9r(yI3E$kWrtzqF0MH#mNI9vebT0{D#%&CDmS zO767TllfgyQUjctY3ZmiCgAEAM669p2gG!E#(?W!4~p+4Zb$kFs?x(P|<3Nd`zIR+_+>U_p2141&r?lb5jU!BcS)1gJSq}LK41RfH{Y0SJ|n`l6M=KLVUB0*|wc(TwUaw z*lJZU-3XzqZItds@CrW0+WOQsaCuCE5C8s$hu9YIg%F9|@q*XrqE3CZ<$~)!NpJ#2 z7C_vtK%t%gHhcGpo=6YR%k5EEGce_*=-|USShfTOZdc{wVd=dR_j*qw;+5kn8bQbP zAtbH@sNUtzzknicx}|?{tN_s?0QqesmQh2swY52oJ$&}obXP$Mf8W?cf4;QGE1l(E zS3_C4YXa1Lahiq;rRFKh^TPQ29;MaE_3p=`P0NuF*%wtW-;3D`HH-n$ugO#+NV(@v z`j7ytDwu4@z_;Jx153<9`hCaUpg5YVsCRe#0D3(cm4l0F&&b4|U8-negt~y1KcCy~ z{R;ak1gGKlH2>nX9$ zed&Y9mrrC6-0F9ooQlbxl}MKbpI{2wMLx>)2y?&+<~$x^4LbIRt-c}8z2LDQpnfMA zm6LH%UL+?+rgZ_ig!gKo!0rX(SrrypgoZ%2=hFQ5W!rF@zpet%B7amTlL#vSrF(=( z?r!8mzO+WcY(1LPBB6jx;-f_-!o86ncd60kqL~UMN-Id6md@IWjA&Tu z4`&(^(+G(6aPfi2Cb>t$i#0B;+bKrlWMIg)v$mUgouez=7PBt zgMH)vhnaY<3oz#Wzh?n19|x#JUzvH<;tZ{#`-u>m^6cw@t%-PqAGOJ$@%jRq080QNqcRy8N_tG%HYD|Kb=(3@&LqpdYC+|VQ z(3p!fB9`L6pMd&XQ(_wlgtCms1?j+E<_7jMlmYO=X;A(@8<7**Tn3{hPiuQ7bA=o1 zJXqfDI_zQe`;F*zOch%AiICe0UcRGbLpg1P~HSX{!l8W;GKxoN_sU%a}Ub*5{K5leM}${Iq?FU9GpoE z8J%*zC)?^8o#R}A^+5O{4stsj6Vu>uE&~+EPQLpv&#sQ<664 zPV}sS35WX_@6~+|8xIwFqni2NWgD@NmXPg$)N`Ebu-V9xX-KrD_PM{rpMY(Cr<;H& zpb>Fc83S4lU-Qz75n!>Mf~lJC9<<)XLH*fJDm_Yy&3m$M!>jUPA^dJo^c zQ20He2UjF^fde7-;;^}DyaM2Wl(_Iyc-6DFQQo?D7tB_N6~g>O_(hJ4Z<>A~SvNTgORC^m_2X;*ytyadpzho zYZm#DPp1PXV!`;usWx%kR?XSeZ9YhUdV{ghmwKmVpV{f&bVdhmMMf&;5*o~HfJd*W z03U9-g;}AyuBx0*Nc)jObOE(oTE+RhgY}$gI}LBd4p#Vptg*b`U6Ws;^?VIJ$HcP! z*8x=q`0EgVpdfX9&)Upix+l76r7Tb$fJ^kS4By8@iGaq=+_KD%8c*nOa4!c5IaX6V znvL~A&VUI8h2d^lqZM@^iLgiGrJG5rhRT)O3U3)k&jSRGHO1&QNWXGj61s9Ov+$q1 zs}tEuQe~&?`ah_a36LwJDCM@et}ghsbgLPv*yPGN7EJr%z4#M3-k*K|so_5|smOx# z6<)?a{NX=QiD>?|RCvVH4p3?TqTph2a4*;TjbRHbs)X~DN@4}NoIc7)Id09_*tjnm zP)~T$5sJ2hX{SP2iT+cjG42nCxB#L;YVt&!!p?ngmACLXU;MF( zUlvJR(|RcgMl$LpnObN;Km3_Ni)mGgQ;mnA)P4s}1dS>kJaczV)#D<;e$ZDq%^c&r z74YRC5I`ufDX!}Mf1~OAk+l9hQHP>Zjed|?p!<58QYhIIx}}&D08Xi*kV1Ps9iE8$ z(!bDPYms@alwHIJ`j2*NB9#CrAB8MIje`FK%6B|yn8+&65qU~DQ|{s)+!weR_knW7 z@INgJ|Cu)3Tv4S%I@|#}O$$uuQ9yC3M!J!?W>!|@4k@PiYyDYJKr2OI5JC8~NLgM3 zI|6I2ro_2YTpw^eqr4Ds4ApiUL8;=jtKn-+x%-sy1vG<0kO7owXhy)?y{3t(EeEgjUlvo&HOBV zy!D+>n*?Nzu~r`4SC-~oyz~k)z9ULOy+#nb=(j&bO(o z{t=dJrsM=_xebuzcP_Ob}_ZRK{mO_#;A0Tm_2fF2dBuR^98R4HXw#0VrOzByi zWYyN1f$95rsr8H-6KuRb6|YtdEm5A)GH=&|-2L4P z#5J9sd6?8f_&LDLnK$hoDpL690WuT zuEIMRSP6~<7Dzm^@MUq+7I>@FD}4Ar{e?pf`sadJ5e16 z>4~IO?Fs(iM~C=)+uePFcG3(ea7lF`eXnKYNadXovOD4rI^*Iz?!Dls0U~u|AM&8O zUOg4|!_b`hCSG%ebe>PFILLmwm5?OL1vk0`gdosua*lt|SFcoyqRl_O-icNpcQS_B z$yc{0%OYc6Yh@2yI0EN{{}08i#-=^tw$1f*RW_RQztY0U*;ECxNxgB?5&^}Xe)5Q% zn}0k51MY-elZ{gcoae*=HeGw|RuLdlE`I1iUyO9y$D3sq2Dsn&seYZ9$gIqGj460Z=~e%LVb%rMw&4R6&cPk1-vi&jr@Mgu3X7XQ z_sA~5&dO^1Fy+dVcn^B>fjD*O;Ko{0q@r>F)be^1P4NsIVEi2LMx7%@!=S#Ifa%Qn zzb%n3ki>x{qS{l}3jzXR0rXkQZd1U|pPU0fMl|0Z{SQ6`rI4Oe|2GrjzXmICxBi8j zDECas!7(YO9;1E%KwCs8U?XF`mKm$8gIogIX5ykMd(uCmm2bG~06qSynGzvk?r2cJcwtU=8x81wb__mFGd!j9Ne77gL8f)kD` zusl#LNqYtd8w=zyM$N|*c-cbKMTj|BW}^@8{=eQnl9r-rfeDyLcJI^^JL(-M8s(L| zYZWFNCQvX)r>~S&nS43Vz_>p(Zd!E&7`!=x+>M;R2nK?`9qjQR905(r&emxZB@;i-9ZIspcRqJlWp|u9xb(BfXcg3d`sjt1Mlejwh*L#auzGFKT zjE&^zY8z54tJ_(98D3z2{$C5&iT&S%c5gnXN@lIt?vi3^M19ws9*Q1p@_oL@R7Lw= zv~5bs045vo9=~8m{>EjyJ=5}|<|1#X)r6=#x0Y3$Td+doR;ahC(_I6VYZDbGWeH9e zGHaW@PAWu?j;{HUa>og>#SJ|9q1Z>i#%r>zcfnB5Fpp33ANib;{XqS8qfnQ(Z{NC7 zdp0ccC#GWReIKdau@0m?1#S5lQN^-9j~Mn|uMdkv6iE!3(0(Ev3&1^-TMHeT@|8$U zTo6rTwNUG+Yx|Rss{oOhbaMy`YH>X>j)LD(9o}hW|Mp;zv%BPYb6e2O{=pZ*FcD{VVeO z`}?y1^1pym>;9u405Dl!`s&p$OR(&(U7A*2yup_HrF`L(N(`%X>-Uc>sQF#^DN1HS z@c?Cp1C)7+!Z1wk9PlDajf>KCrl4xs)<+0$DbV^nIs4Ax8KD8zem$+eL95jS(v>Ie z5(%@y3)0^<*`HDDJ)}w1Ka3~K-Eil0XVCUyrf?5av}YqE!+xXF8mD6q$6x;vk>7jyec098 zs`@+%k7>^Ule2*Kf`$dkNrSc9p7P6or?$r@lCJ$sHFh|&$=&`SE#%AzUd(%XWKCJCr}Hz^xEzqB-QCuW5*x4!!7@@cwD~5v( z+>3)H2O|rpO8F>+MAQX`RB1zqB*`VPN1wvB>hoRli zek_R39l+(Iz-k9Z0HFTd&wscbjl-Ii(vG zXZQWd=?ps_clp+OS4x|0O^K6YqPFjX{keZiSN>ao14n79VDA7cM0^HHgW!MTd0sDf z=m4f*zKR{s5;5eTEhT(fQ7)Lc#60-MqI!^WSA+lWiVx-xz+=GuW1OFxGx!7fD9GzT zv0~HwyTTZ82*l)IC}RR>X%WWBY|OISUzpDq0IT_ zl>6>g6BHR<+~aS)bhYrRFkiZ8eZ$#?Ey=113dskf0!lr;;|%cB66`n_>Iy1uXvko+ zds+y_tR>LH*q~sro51+Y@qPxZp9s5vIP6lpgN#CKe<+`OLx1Y(_qUyFKNuk_IKze! zLrCK+o;S|7N|=OIsfD!el_`t#I!ylC$iTtW$_TJ-ea)zcUSPwhO3NA>LoI;!`E=3J zK_5&7MC*nx9;4uvGsu?{Ug;y!V}&OBHNUiBjS&+cwku-}b!UlX5EU%F=D$m;Nc5h_ z#sWGjq-B(M5YncbpM1cZQK8R3yBClXClNwWDGKEQ9PMcFHep8OOx3YNyI@ofe*j#8 zq-*i;*mA}2f}4G158!5_sNShDg`KB`q*oyxMR8Zo9R>Oq7(+PE=IO`*Iwp|6U$=z@an-i3XC3@b82hnT_~w zamEsh2jdwcQN;<>eC|+%w4zdpDN~SeYag6Wu+DD zCjfy?8tTXHj86b10enOzz<-Y zN*PY%darf$jVU;0XtKOJ5tvrB<=tDh6rtjVKLP6Wt@a;E83t)_adADc>yxCt%aE=} zqL5ktJj$0B?Ftstsb@{%wBJzKD=dNP$vE)Hg(=fiIr;f`J$NBk!efwVg4G%E7)9y}-JOjzy4%xB=KFVT4Zg7gj0y`x#3>C4+SEBYD|x8wnXTe;c(qXtZt zsz8klw)E&EirJcjeFMFMy<=@wMKvfU=&JUQj0E|3O~;*uD_Ns#ic3l~G!8v@t>wS~ z6<}+NgDVLnZrIgM>B5iy4PsutO3c^9>yi%L{Z{hMs;-1or|da3c7?{f-^b+_*?nm> zHvZ`eo>-NCo6(R2Bm#^zJe1(63fh<}gw$Cl!ARc(GX!S(2=r3y%>s>ttfSGN_86ME z;O0i_Z$sV{TMT~vDm8OC9?aw?&EBoWu^!G5#lobhn>i8Q$I&fXGY;???q+;q#|*wz zUQVCpKY?}ovL@{5Btxh@?qxhiU7o8=uq3m=ZwZdQF4y%dPLzT?&lQ7lwH&NOmt)1o zL8TnY{NE0Y&q3{~UW{c>fZ%YDH_uL`Lo^+)(0{xvt zK$m>2h=v;*8}#60LM`akC3M%-g2m9Csy*Of4{kPaA`297UTC)jYkj@QCwm1`!+Lm=cZWZcT%Pgf>GSAb}{9#-D*O&Twf4@GzRQ2d$Y&xx2IRhe*v?}oF@Dun3 z=BQU3_44B%G&w8cVDygC;}gz4j8lC*X9@=3x1q_}rPELx_ZHJmYu#!66KT@U^N z=BfcRgF`wj-zh@sGlR|I zL(W(f&l}J_fgn@^bAT_$mJ76(h1o5=ew+_*eEYKNY1mNy8d3-lTXM;jz&8N;j%k0G z+wI$dzL$-_@gFdtF%NwNrzS#`!5H<7HOfjLV(KOow%}GriF0}uenrmaX>b%svB~5+ z5E5An=JwaEZ0~%E;%uWo?^%zj2X(?`N7Y7%=KTfGe0$ccD}G-_By2$tWd!&=0Oe*S zo#4^NzS^Gtn3~{GYxcswz)K>n{3ovS$Npv< zIi8SdT*23pCpI4MuQ$56U*V5m@k06TH*4U0PF+eqkta@j;|9aoryy+3pA{_-wfLmt zcK-8o5r2_mn~&Aqv)MH7(Quobm>tu*a-HGwJtP|&2Q6GdQwVNe2U%S!IBVscD3Ti7 z)TGhPlxmQ8N#x6nqf8btI`Eb^L5XiHci-e1}UOx|PP>bfYHUbu=mwv(10D zd8^Np_8JlaVZGDC7~A(9=h!aot8z9sYdpE|WK9Unhrec>Tq|XKM5bv5Sn5_+iZnPG zg0-ffL_mgMfZv6Y)4|+)I27up@l-+kN4DFL#Lgfpj1B!~&$1%VQov$pe4Lo9gOA9rT{y1#DQ)F`o@jFs(fm`=-YGsuE>v?vl)V?ilsc5=~>Uu6#g;|y( z0ad8%YL6Mw4QbXl>Q_m4?qVKu5Hh`A>CoJ$jobv?88S3s{mw<#<}pFTZnwHL@Kej{ z8%=$4+%IF{yK7s9IzM?ec_Fghrd$PWRNTHr6OO3;W8RjprH@kl++tF}uul`L-m<7f z_@%txwu*GBo`m7aujk(G4@`jU|MR^7Oy~w!`tzVJdMWzAr79^Z0fua)jg3Ys%O;tP z6spPG(%d)=Slz9aCFLWURL$z5dJ8Q%qJ$5~++L4@xk`k$fvRBBnYHx!+7jxa;MJLq zpP+M{AE*KHOC45y2%NIoEF}P@tsJ~mgV%xh^RS@l?fb3#_|!?y)7gO?0W*0EdsmF5 zG1|HL+l@^MXdF0SBS$tpmh&L;(@kR_FYClg^MUgv#})##D^Sr+dq~dY8PRepxfF#4 z_n!}2xHw`Jd!5%gaKuwb?FH9VOD5;XpHdC_Dx6B}5Pl|ZF7qRJT>FV6q-%IoO{lrH zXzeHDNTtZ#OuE+ANI%)xa>Q!t9&PgmWUUh?m%X!md_AVCfww`jwMJ*ImeE#+pSrn3 z>RslND>GC~RZ6w#lsJ22$f#SOU5#JkE_qWmzkgt$(FXY|s(lJF4bJ3_)y~agd0^`T zX6J-~vu2Y7Royz(ecA#XP;7M+)MGZ>cbhwZ5*!jiq-8WA9CRc!FUZ0Kc;i5@0go-2gBP>$X2;b|5cK? zJs_p9e+oK7QXHg7lM012ndI-!yFE27+~!{Ry3lw6+7)aj*#$4e(=3lkeU$sLk*2C} z?i_O9jm2OQmfMj(lnyf4kOlh)1X_JC47ME>a-yi^4ZEhCYsrqmXf%&K_Te!!W?6_C z4mWysyYfsZ!({$zc3DTNltQV+S6zWiXh!QX9zR#)xeo=Ow+DBF1kvFt*=?}w;5Q5QFebfB7?Z7U6PU7{ zH`%y=3Snxl|853q+62`kExhI~n93Hu)!6C?C0vngxSQNRW8&NMz3=QW9*7z3&u`S- z-2Oho$*TX_YEzNj3GrE;Nbeu7MtDwd0VAKz7HaNR`ecOO4Je8U+w~b7uk*Mr?bvR~ zR#xJ+xk%3OA`#owea z^@%1>FW+8JZSdn-I5a#GBj1_K#@-(I0%=_eCr`XM!vFE9{0MtbhO9y#y^qSlKd_UNSq< zYy!za640_1q_LE@jjjrS@Pf*(<%K zksz5aW%nVb)c&;NO29qy9SQi~1L|-w+ zg)!F^SB0EF2iqkU3_`oyXz9|9SubesP+ihcJle{7?K~ui)_*hz+v0b^OsN_DqBZFuDHN4Terp4Kex^kbivNehA%@eQm(G z5FA3|8oze3RDnrl+8^33^rH2H2*Qb4l#(pvnq4KI*Sp1jVRyqjH zA~t+>!CYaHnKYzJ(5V&)T{=jkxqG|2zw}bS{1B3mU)s=y7WfdN?0PNP-6=k%*2%$g z+W)9q@qMdVWwj>73|0RR5>cCubHN%L~%FoP- zp77~lyk?U{zs#|)JDUW_=f(Nwp4yzKQV!+uOW6>zwIM{89^S|@#v68sHL*1xFKsF6 zq4|o*>}@*(vrJK@8?qbMu{E=Yb_F&gI!d6TaI)1716oC9L{90k8|Y@q0&VxPnJn3Z z{hX4GTR%R76Rd|JNqp^qr+IzAiZ?jWPe1AM^XJcaFoG<*Ky}lGPRan)^wmsK84hL| z{ayC+FwTnS_VHy{V1#Xk;0Uym6Q>*u&!4_@fCTEKIatTM3N?^)Q-SGW2Yv z=FlfliK0O}yZF6tsyMxRy1L@bszm)pm^_1(v#r7fxP z9YI|e41W}rsx=enm*b0S!yZ}LGn8KJl+B>ARd!ts#vijM1q-$Hk+S12_S9M>+CGk? zt_fqY=uMmnD~*>KE|ER!6Y7g=WOFLTSa2&UE%b)N5*d0mYw!>=) z(M=Y7pT09>H%k1#A{55tH&uS&9d(_==1-7oHq2?d#f1F5%F+gc4SMkfeNfPSp@@*P z+jH7DlBd(AcD_fDLt{Rf%#=*LcB=1}dYsc96M`(#lZk%=1TZyh&>KuwctbEXL_lX4 ze;peh-d+q)ofsyfJ|ysFexa>DusS0i{4hGSYA&@@^2R28aCB^7s+_~m>vf+U`>g1~ zliw>xZ~3iXlQdTDxr8^UGv+Q;`d(-E7@5U5+A`nFa;fpeMu4DSCpKAXeF?T4JzjvL zs{1m493pOTm#Tf3Arf{j1bmlGQt9+@v0G)=U26#>C+yq~5+Qx0>f#Bp z+r{(UsQwOwcN0F4ys>^&C@S!^nEmp!rqRPtF2T^W&#a7my=c|LX){Wt7oTOdbTc9d z_cK4e3rd{0c6yvI&2YS-eD2jEI>WkF)R&xSm-w^KE^$rRHt}0->00`9f-UpH?vMDE zZm&Jsg_~BWQpShl3VL1+`~2Rs^Y|yp=^bmglC9+ZNSliq90|{Wl#>k3Xb3gG9{y=L zXhmcD03R4~)?6K1ct;1!rOGTQI=7qTsek?af#p%b_rg1=7`=0?kA_{&BTr**oJ0Ut zCQ4{Jw{a4D+07LVe=Gl&C$*I-EdzHd@HYR8wzm$8vTfJJA3{KpQt47ckPwiTREClg zVL(7il#p&|6e%SHq@#Bc~?Q)^hW%9zlvc>-oB0J1Rr?Dbg7iCJByB z3((1hQM40ub4H^XO*ZCKTho7i)HoTqRfnG z*{UZyNo33X**`c~Mj*p$cS*ZrpI#M$s2ZrNS6XaY_PsuM-w2F@k_l5Hu$|Vk6(ZeU zd{bAo$!A+j-@MY$WUix^QGLX8M(^j1b@iF>Rl4yrRAZhFv1jf^()+)gIA zN+flBdq^D;&rO#jo(=!8m1pi_*@gFrSZYf0=sL`M>T|~NrUEBmB#!kqXSR8e9!ML##PeV z2}nZ6#K_YPO^Z5?zDCRp51VNyb9uU$F+6Xvx>v2>HjcjmdMOQyrB4hXhYs^&g1YM& zX!E!s^=N4S&d6t5^H7#1S`YKjTCKb49xYJ_ck@u~rttLm>>-C&>&`M%@|W#?c~jWM z?z4<#mtF8k+LxpkYCMsOU$E~Ov`($XglqunFg|V-v zX4~6`CXp>%eSsSHEK0>M49@IvG9S^6nJ;yjna*U@(YN|R2}p9+ri;6al~+986twF6 zStqWeGaz&6)5472?A(gwRGYX7Ty`hIaAbHG4oK^T2ya!6OXE*J(oiis*x5}b_@$m1 zIBPofrNv|3($4j0v&DAH3B1`XNE+ILe8qM;wzCcYf$h=4qxe5d6mR zYjaWd5&3jLIUs#jqL&4z9VM%9T&TGtL$$+B^G4&rFdDK82SQJw%oN%MZ@xV)hr4UF zJEuRhv-6c%d!GN~gaKL0v`8?<(nbv(8ns&T29}%qeAEhES9CXvn>TGGFW*oj4m<}H zhiar!oVy=`I5OJqZtuy3iXqBS=1M=hHNmw=$RrT8T2pmHEe(q5%iq#dV&pZen#1=% zwbB=?_NvKXY^`_9j;Y1Guw*WdRQ1f2`ujSim?4^Nj&h2;$6Xc1KhR6zaz1K>5K`Pc zv^U_AM@+@Dv5b?92csB!f2`cC;_*@0zSCart&G${d#$wF?ibgj1A~Cr2hbbI#fsqx zsIonN_Ust~GCSV?V=Rtx8w#7;dQYSYBi9+e!M1q`y50x7_F(ut!aE}DOS8YzCG9ZZ znG8<0Az*G2S~uWoK~CdO6C+V&PrCvuBXUgm75eTCE6hu-NjFKb3RsL@`$_Qm0#d_k zM72+}clY|*y-~jdiog-+$rUY0J2r~31N4cFGNxguODFn~iJFXy0jbn?vkxO5Pxqeq zSth5RTC>N5WvE{-RGcdWif=%oOc}nTM|EJ@w>9B9%rEq`Er|g70C?K$9Ur42s$Z?kq|*TzDdZ>o#YAoa}`ouj=^$Z1u{ z?qI0{P5B>|n)Ru0Y>rwp*j_s9}V+700EYr4DD&P3Ax$4Y-kC0tohuIoRGGp$-qQu*}wTJy$qk{AA_a1GuqFbZPufm?h3Ry;>CAeNOgX%UQY*Y$aY63GO z2UeV0gfm%!;A9&I|0Ds8re5K;Zv9~`h+AhELOQ~-bAaq(I?(#5s#|ufUCu3nu%IVj z2l55Tuf6HqbWo)ASE05~JAO@FKNx`4)sntK=ppR%>%Le{a1-yE;( zZ>*E$El#xG5@8$M00lvd?zXeUmu_g`$bXQoTn2ahLyUUoY5<|_9&FJJvm?#r{~i^hJZ z@l~eoZSEfllUhLy_c^=utz%+AW1=za;21FXKvwwMp77^*^W<5Ml-zqdrC~MorQ0#{Jjrf&Ig?5Rbpdk02(i1pn6mU^^cDmlx-=8 zzt)&8v>ye4uB=~* zB#J_J@Aw5wygGl`pD0i~AuK<8tt?&_{80m(O5`1gJdhrNYmZITtvD}F8@LLaV}j%e zXA4(wMY8e`QI|}7s+gNp%al~O)8o-T#c0$Had#EQ-f=h2q-U~-5MX1zLwQk^VsxdB zf{qs%?4>KY9KZiDluU6Fmi0m?Bm*$H$~>06KwqR0+a)}wKR|u39^5kL7?rOCzm1_x zM24+{1J(wyZw!cItBP}zjhH?Hr**+LO4mHX8I`d&mQ%y^wRTlk@c(j_0s`2fR$!gFIxnSFc7?FI`1K#9e!z-n7Yq; zg}x_3bDG!lGL^PDYTD^==t6@Fq*$dem)g#td5=aqpHjm}YKI3e%h!*A9*nES&|Y)t zwbxJI4QOR~BnPA>-DdXsbcc69(pHRWNEeY#@Z}fUYKMwhRJ?+Z?N-hSMCW_W!pvQa zJ&O^VG%-gqeMVH^onfsuiNlrQByhG{+OSQdoFr?)x)a2ZqaJ_CwU@ycj4#aMLC)}# zZXRaOA1dmpc=GTr*pp1O1YE(rr`Y2W#jL^6bg;Cx_Q*csk8Xueez8{vZGz{`I*WxH)XamKnWw`>^yjb%+d*E!tNO*P z2#;_j0;-zmjF>tBhDa7Rw##_PJwFdiD(djGOEaK@yfsp&k7D62;_x9TX{ah(*88Kf z{sx6B+u*Ev=JBUzvfHoZUzVSHP7D#hozL{{`!O-U7cSo#6&5EZ$0(f6R6Iw%b+?W;% z+S-&hUTDHNgGsMYKBbCj)!m_^N~SymXW>9OOSj78 zYfIvSSMZR$Br|WntGf~*#OON{z(MlT9(;>y4dZ7M(AU*<;`CScRS8W0Le`u(W8!C$ACH;V*h9uHnq5YFm;d+aOV3r?7ShsN?~e z-!CAB6NW(d98~Jj8Bw6h8prXrM`x5jK#_s+74s0u)L z4%A36i~Zz%evJBK27%L^sMUaTNNGp_FKMRhAR1J#SW*uCg#%3?YpCCd^^d(%;@QyBP8&z2F~trVdc;CHA0N_HAiibM&)Z%)Y5e2!d|^#Sh65guT#bG1eV;bM8EMj&CscQWOU%4GcY zs8In!=&hFO=~DeCZm;Sa7ps)ygxHU)gIod$BIFwg%ZSt+gE@%WU6N!(mO#FwNO9p6 z83HrBz&&I!-^nw9QL)m_IXuXJy6eEz{PLq0sLJoi>mNlSS%SLfBQs?y^|T&ITmA;^ z(M0#p&03UpVyk~RYZ#x(l!}v(hcuYKEx<<(>ZU;b=j*=xzyj8f6TZu$cL|bww2^E# zL_u~0+Q(n(35$|mrK!lQ8&W(wC_f)oJYV3#qhIpSQ1*~Q-{d!w*uqnPfnu@Y2}GO4 zDGRt`86hlh*71We4jm{J)h;Rr7KONAbG$cDqgE@B`By!Ko!0hk=rZ)B<@(oyeOWuq z&H=RhlKJI{5LA-WYZ_&I8B@}Fz4yW_!`R2^p$GFc1QIu>wM=h@YWQzyq~c8~_+P%q z=S(!VrT*p3!PX+sHP)8`#AQ&@mRfrrb}xCg_GuJa*8x>KY+CEKJaTqS{~3EZ+S@aC zv!Zn8bhoApt7(us!C{>9&mg()`;E+?EF2@vIlL=V;Of}2s}extk-zQfT{G>aK3(wb zZ!SPVNz)ySLTMGA1ii=U+?Sb_>%##-8oxk+I;q{31oGuxecu#>$~f37?c5F>5T5hV zf=o4KPKE3QyeHapk1m^;a*SR`Yeg4#$3sKIwhHS^Yu(qY#kJ1dmKSs>{bDGOZtv zp6WIkA)Q=$a>Pm-nvlgZNCAR<+m!=JdQ;}HhP2aIbgj>#M52S1IV~6OyKSena7i`1 zV1}EfWxy@`^`X=otmki0`P!T1R6KpQ{yOvmU9YxeZ_iyVignk9R7X`mnadtLwgIHU zIX&IZ8!`nYUH8XKW)dHmM#E-Y3)xFCcx2aly{>?6edQ}S&Tg55Z#bkj69*Zrm@V9 zZG!-t%#&#fGa_%txt1TJ8W0O+{#eVrDsF;Q%vqM)W8W=c>##2b#VTn;z4p=q`n~F3 z{JC!91qJO{*nqwcPYqQV8o59wEYK40KDbE018`{DlR#>ep+xdoYQ-2!DJM* z{A772qV1eYX`}BcBvcXlWh*5H7{@XR724?&P_ zstgNeXWRQD96M+U(=Wz%QVhH1MzDW1(8@g2sD$`8-q^G`vB$ zd5=d1q#vk|HW15;^^-J;I>#^g`vKfeo<83>p=r{(rE#6oBP}_Kx)OJ?wYNJv&~-8e zKF%Nze9-i5iM?VbAe;6Yoep?@>utMYMaemts0%PwDa^`IAC8~K!ZI>@w~R*!Z5KTK zBCV>XV_OxiJl&A%wLnafZ!|qqN!yA5ot4DiyJ(Kgx8QRtCCRmtcQ!I1Bkkc5DseYdwKJX8Lpf=a4KX zkK~3HAzd>knML=~hTk>2%{RTlwy^$@WI3@|@GA_DCWG#U0m*DiaKsI}mD$22KcPgE zj`Jm)jYDc#F9}LG*?WE_g5W;1YU=xC+ zbr_hgJjm%U#n=GEr3+8cizORiB=us>zhDFq+k;ps`BzJ~#twQgA!(P%AUSdYCZ6jc zv@T{5PM_UPzq}+x{76}8#Aoowk1yvN`p|5dlz`AnwR1|s zW1!XS@NL^S;GEB&tAR3jgr%xm;xQ8gvH5bT7I$D-Ar{@t9cThUy2f>myI1D680z5N zTBI}=fP?DaKOg7?F%W6*U4V#NG*O4Q0+|(PX(Bz&HkWnH=8rt61~`g&0V(nse=BqL z3mG~npl3--q-W?TUAi#;!fyQzt{mhdVVA-U)Y{j7LT&UG2|npnoNLdy<(T1VtTj^R-%}qEi2{~+MTo|DyC^h|=*}KT z*tqX1aAxN_E!dZ|=RUkKL0z0J^cKHqT6Zu@->3qo{4>hpHc;qMn0)SM+bAuS&7NOC zj*z9r*k@cHxy_cJ9LS<@ITcLz2|(dGi&wEX0E7x2`TGE&uK^nCE@RG=+NWT(anFM1 zS;3w9>&wGtN$~OhJE+L>^xwH;My+Q^_>UjDa9v%PnB7=u131h$XB`%D*$0Ga5scy+ zV4x9DO}%rLX`dl{qyXUqa=sup2P!bDN7$D0m#=q|{AY5`Hpt1w3@M$kAYtrjLTy0M z^FO#jNkFWVt)&n2NuTBAIR49+5M|6T*vOZVJLc_oU_gJViG7VOEUcx){BJqV6Ej=~ zEAH`w;_nn1b~2j^fB=BeSrLrs!!cm!RLL3A59(V(Kt)XlJ__zu-5JzhQ!J$q=X%p| z0$2?sQb6(X=hwMpYkhzeQOO&Oy`YT04d=fc6At>$aNvnNyb$)}F(u(V4onc4`YVO@ ziS2v>=2AI=t)*SC`Ztb)tC^61K~A8^3(I-^pDvBc04I(JeF{@Us!Cazf=52QA|;tQ8VIGdhN;*R7P<%B@MxRntI!jOyB+{8(^Trqp4!V05lMO zci{-jN0kgJr4>w2oE00-4e(?cokhCtFybmnHTS(3@A-sf3w6qa6&~ZQbNS;s588u@ zEGG2%)4kq=!-{XuzN8foVc;MO6S54#97Pk}Ddop4-~Hh{#kqMPO$cuP-|G#k3w>vi z0WK9!VSY}6B=(k+(WFk?M|J9$8o4ZW5|7l^yHumIjsbJZ9{)EC9EBJlgNUUD@GQ*y zC;mB@2;vlsJRY1-6) z9fH2sOU&!>>*7`Z&L%c?eH_2!w-7(Ca9?6z`&ZfLqP{X0F3YlS#BfClO#+BA%(@z6 z7T5Z_eKo)atE4^?4i>TTu(v&M+c;?IteB{j1X#EVmhJwtl0sL`d`pP=8( zc!{(Idevsu+^Zf!I7p4&e09^xDzR7Do-G7btHo@CYgX= zfQ?ks?)moXGram%v7jo!OX@#n4#^hSeB>7<#VSOH6}hD6!H79&6wx<#)U9@Bo+<~_ z3J}*}bG5Z+1d$ z2Fg5wu?Gs}0%?k{h$UcfGw%W;`tI9SJ+S$pB-x+f$jt9LLc^92vl3W4ZwpOPc`%7Q z2f~Md^~mbM1bgxg?TnR+54%SLmYMp7>3o%!p4V;^ucm?iTeCA$rX&e$vEnnER+~Q3 z--Ry{Xi0o9XFnhc2bPd(i(T^yas~VShTC$He!BOf;H$ISCc@(kgv}B_&Al9Ntq`#X z6l3*UqPP;JiY1<+jzfs$mQVeF(<>2$(fcw@gOV%EqWn zQ3Jp~r`H`-gSc$~+W>&6BFH(Z$hg2KszY3g35Nhf>dDmvvD8W;X-xydMvK&C<8*Zc1g4f~B5JXi| zLMO)_9u|TRwlN>*MJ16UVk-lMWe@1Uu}cXS+>G;jPag?JoUPHndu!n741fZ>mJ^c| z#mrs?7}nwVw=av+-I0KdfCWe6u-+8_sN2C&pqo4oFvd+O{&HqGL>w0ev#_(_q7}dl z!$rG9Nb|EThB*R_Y)N2rP556s>|W#IK?|t>)8%kj)Eau55ex$ADJ6n^1Y^4j5OB~H zt9>Q&Exm;p7;UFQNeE8$nGCfd%%nI!|KVTJPtjc5B2G*eOi%Pn#mWYrvh+UZ_67Qq z$)y%_pDOo1`glq<>z?nYe#fcL1fm>J`U zf7<#QP&}Dqqi#TCJodTM(_ov}E#ZBy=k;*wCAtAh=l`MA=UJXRTV(<>nm{WMzesCpEpipvVlwb>Q4wcOb`=7VpZ^?idtbTg?yy7Hb4PdX1D?t0M(xci zr5ktJk}B>{e$pM@Ew$);s%+KHML1^lVO~+lb3EEg@5-&~nIEsStrrAD+n#M>3w5BI z!22JLf!e;$6||smDb8i2FYeS(J^-gM8xeZYSaOH**tIj3)A1<~;%u65PHie&L4oq< zTiK1;jdPG8B!a)M^3jAKQXTAyX0R(rUNj2#@x;%^C*jQ=-2JMcOY+}=c;LBjd{18l zwt<1FMjvLm=K)3?0!~T5CBkMy_(_n^!XHqms9mi!?d3~U;qYe#Qllw=J^|G4s$O@P z;-yxbHNTW0-G2~9)OQtQ@}y$u(%E6-)>2Fa3eZP4sBFH&m0%7;PUizd;qFlge;OnM zBo2}=W)&&Kp)>^Ctpe=CgEBe6IYCDso&*K=m;!#NO0n{Hev{CZMpxx!%lmmdU38GbEvTNeWzjlpZHP|wkk%zzBd2eGcKt<`5HQnT+7 z&n6}&x&};L5)Qx~1J&?n?RzKo>5J~6%vz>w*Pjd0t6U<$dVUIcZ+JA7a+1i-Ao=Lu z>i$(BI1X1~K|uky>0uyXH}?Uo3H>wcmzSxM4x-9zAl@uTX2uh!4Am1(me-TQWrzc* zVluKXTR|$ovQ!uQkOr1iR8?hMn5Df#sZJg9rtAB6?D-Fp#(+hGHJjPf!v9^D;!s=Q z3SHZvk5n?Y=w`<`h9P3`r=mfGLI=mG23PHk6%`aDKho3l2thb(N|%Uk-5s$0aV}7N z#&>HM%+HC6K)XU~ePS18+Wysj0jf~o{j``0O3*7!D_iM3$?Sky*o+-c@83>!5K^I^E39{$g;aP7Zzr941@aW!&jnCTW_Csrt_k1IxLa`Gh zFF$Z&S-3LURMX+^_>d_abwekY&jk4LdBlYNpS`>lX;hbcIt}O+bcXytBC6hW=)>lG zidPX~$9PC8(D`;1jx8j(=$wjZ6i8Ng0JS5ZJc`#HF@Wnp6C;`&+yx#%SChbaxcXDX zZF;CJg1%e_<4sBE6W%cgGDESg=Ny*`09VWYqB-MP_EXyA%6{ms`!4e2v6cSO02I~J z=#aZOGqpz%;E>Yj-klUhb%491j)68=sBOP7gKu-RS!}E=-@27<=p4wGUOs~}>zuU+ zM)e#^X~So-5ba?dkY^f4W+}De<|7l6Mg*V+^@Eut4p5kqtEN#pIgY<_+9~@}qPOiT z31mj}+rx2N8IKRIKQ-oU6E|B1m>iG+uCf6w0fg08L0fTE4#mjmsDLYzRVGjYB@+dV z0W_lzreV)s%42QpsY)qYq6!ZQ+HO3aunvlLe$3_-F(;mEfiwG!aso$&Fp*o-^J&G_B8Oz~20d6WNDDll zrUNP$LEy8#Egop?hm5h2(UGP_w=mnL6BvBTxixjh+CobR!{&Ox+9Ym;%|C(L1DeHX zd{cp7uWj`yGg}gIlBfJ^7*UsQn(6e2)5_(OQI@n3kv?f;XnO8jf^Q$xbTeXBdPDPi zjfMsSa03-C1g+MlfSM~6&}Fm1Ri(cdaeJq4i4e(4m0hxe?ho(&7%E$Ht(tP_3V_xI zjWpQ1g2|$z&iDIYCKQD(ekeF4d^@YQXnKMysS}krEe?@nY>9HOX1-tLO9l!2mDYn+ z%gjl{GiU-&w+E1>S&qXV{ zzk;gT$hP!FGH5qh#Ac8M60=MPb22l-fD%bnP9~cm{5B2#VL09unMXOGQRo@*5U#Co z9NL8sAAu@3Z%_>p6WA465oX0ND^qwYkG_TG1nBzbj^4in=Pa4Knks3^)5OB*YgxYk5 zjrA%yGkrTchmzO{uZAwWT%8LGzTA0YWF*2}u-1^T{I z#6ikz%*UpNciicYGR4b(Fgyg=oquU|f6MH~6CTGqn`-HJPUaH0%#@Ac(zn~~zr3I# zwlYLj9AIh6!H1)v=NFNo5Ys0Fe_N6TxM8HNbX;UHjT9 zPy1Y@Sx(Odn$Gb6q4Z;7D1a_KEWh87QFForw0&YP_LCAloOk5cPnXRP{`p^G&Wj5S zFcFb|a5iMKSK*Y}*#BM7sryN$PxmF;gr8)f`!c4mTaQWi^F`tI`mpd`&DDf8$^kW^ z$*3@~nB_l%-NjY-EC{eTTcdKW)Ym>=@YM!ZaugeT;hQM&2)`p;TPbcmaYmu5DB4v!+VLj)Ss^b=no!Ba@YHGMXogObfif% zX?z%!W0uSPgv5!ugPx{vfL8HbC~2dZF&#MhDUDz%^?b7R2V&`|D*7kyL#=Tq+#1Y9 zm%2vsG8vkv8NRB$|6c&l6oA=*lL!FM*Doc~l&{W69=>KL9!}`^185zHT8!Ds<$?ac zNFGt>R2-j%5NOhmgC7Eh&nXUDU~pLT%FVp`m}wZ>wf;z%2y`(;7_1)oa|P};|KQ5} z$j-Ljh$#_iv%?W?@c#=`;9Rkex&nMSkyAt1SI7Yl=Pu!w+%_X@e(k%$Jr}WD(Z#~8 zdxq8p#Zd@AoY>EALh^AqK~C#+}pQ& zA-~yQtK9#ApuRjX@~dL^@txNRD~9jb%!Pd{FGapHY49$rGOl>cPgB@&-PHr1l!P0J z_xs0xZ~^4*Db~P^R-^9~d}Y0I-=FXxhEOn;ld}_>`k`xJ;c?$s#(Y zUA^}p6;p2&=cp;`+M8PLWH4<2nIW9#=!JX3za2UJ?j1#K_q(!4qOub^6r7f^3vQ!L zOi?-&J$A_MU6p$j3Xh=BtFPW#8dP$1-HLL;85IB&>*Aj`E1h}o*F^Ly9@}`V!*B7CRhfIFLL%s$}hhmVsBC!9M_>Nyavi@Ls{I0?{b&dho8mkpkFY>cg=Hd zV0l!v;5_k|xin&Hw|SQX(G7oHFjiq;czEaGv=?N?<2>i}{`<4#(*(DWZ`R=vgjmD{NnuWA;)@~b({isAWZ*#DlRBYa-|JvvxCL%K2>cxk2fLh&9{A3OK z2F0~h-sPF=H#8K^Uz^(4AT8rVXL8H;-X)nF5;?Ioj;jvjBD@5{)RAOll>jyW(Fp^#5TRSu!qnE5mU}kIV4&IQ(6&Y#bYDQT{@~O9L#JdgOzGZC_#A_-ql4 z0|rh(g??#PqK!uI_EY}VZRNd=qbw6nn+==JzU_VPdq2JXaK8iOxLjs_Z-MHjbU7sP zTm)R)s*)$g*(N+qQ6Q-U?+2t0gnZ zxKj>tRsm}pn;UjBjeetTk&MKfy#$a>IB5u8R(FaxCVEJuVGNa#_}4Xu+q^fC21)i7 zxK#Pqnfd%0LvLtrKC0#er(SSaV)J6eV@m?dO66a7?c}HLlGr3X^#Oa7gjSI36(teJ zx{xsLppyfGa4(i)bS@1K`PO}P#6Dp=9Cx4}6zIw(dJ;h$q&-{aW|qKjj66EEuXRQ% z$wr<7Hci&u!-Hm{cJ*eX?D=j%5n%f2ssKv9^ey&@WwhEvf-47Zcj-jS9xk~8KH`^B ztkHXGvycy7veJiu-x(ln5LD%k?K-Y8-%F7mDpZ%9d1@529cg>J58L~s;X3%`>&n0! zI^j&5LAn9NBn^(v#>;5m9qBDpM$D?UuI5Sn%9R0D}9p+GF>G*rEw%t7bJ*t;7 zNfsN$k~KHnTsAp9?$t$_drP0-AuynpBkw#ZKMd6P#3ffKX@9x;Ps_?$%>Y@_g3q_o z5|f!KRH(Mm;JV zjx{W5OEv&^B+p(;XJh%u{da(Do~$)*Z>(Dvhte}T)mXbeDT2UjV7Q=PY~=zl5|p?b zNUzMBS5n@l?|}Y<^HLBKANU~o>zgSH_Y9?bdo+_G_;61{nv>}X{uYaU%#F9y@V1{d0*6Dc#GUFR7Oj3_?REZrv^vHUjm^S_yxDhr?2~M)s z*+~Wp;vOo8CexD8#R9!TxgIG3Xf7C-gM!F3N5!;A z#mds3?ugUu?(Fbie18h_le~WC^F!a5Y_Dstj)1@B!TIzz=;!7MPr1}4jEnRzonV!h z^h!+pzR%9i9vc?z%7dwdj%WU9K)Ua0CvorddzX5qIE2e*gvxU^{Dbzr2x@MXb6$Jp z+HF_J@!smHRfXZY=(SguF9f&HatuflSaajf;C~B0TD}HTR%Y8w2-tYycAk}G-H-^1 z>Fz!p=h?2kDzbS$au;VSZ^gym%UMh@DCEeo`98{xCld01ihbhF7VF<*A0+o;MgTTO znZ@e~@X14}u@`Y??TIs!I1pG304?mxJENve!eA+~Y#kj`_|oPXPLLNw051ri(#Ta%;VN&_lpHh8D5QW)^m#^c@0azLaW3YoVlI@!gR|*4? z!P=~`rB75Ttq$g`@X#hPWf>V;J?_jwQ-8S&9*^_8t{KmPo@8+NNl$sj@T+N*?m z*R{SUJ<$dJ4TeP{Q=_Av9iv%5a+(~#u&&qt_2(p$4qa;MIl9V*)N%%G+f%H>QdXKU z=y+w>-I&lyRP#te*Zk-c1CPV^qP9_KD!Jp|Bo`b4n_8IDPvVu+ z!jmRFlAqKD3HI-c(JbF3E~7l8Cz7Kbvb+F$Bx~X| zXTj=ajr#-da~D&_c~K3#uQPqxQ*6Xs_PjRy?~?qqx;!qcF=V>Ev(vCYVOxT7sV>Kp zsIQ*b{pb^3SE4es{khZsBVSiH%C9!cha0W#Hu=ZSv$Vp}GInlbF~{civ`YDe8`evG z))E)#y67s)3})##|B zJm4cHe&i5ZCIX8B!s0wPPtO4FPw!o7d>_BhwMrWQyn!VZu9H-a&1>VX0(!19aoaA! zq?R5=IS&qsIWpdfL*4h!_9%(@4zQM{d)wRF8->@S&|VwZ>%vBsmQuDA6QkmGV@{_J zEok0+qXlkCZtBF^^Ry<}PgFG)b%e0DwS5zHdnI4I_Q)}5JTMyrVmnrr+$v%y?)3sa zSrJfkl@_iWKnY+rHn65yqrh#`RN7CDpf?ty4J%X!Svge8?4QNrmn#?OdNwS-x;dz7=m{nP1Jf=Em71Aae0 zzpD4+tAipk&aEM26p_U@Xx?-wkeJ47uTj0xQ4NUU=*-DlMN43lviHecc`iK3UxU;|Z=oV2&B;P-}2*vOzi^hdycBlmXmks2Xr{d6%+9jg#5j5;Jfg?YG65_~@1= ztcLnRaKPK`2f{}d1%<2f7C*9sgz z)&6A-JXLG0+M}2qS^tFZAKl9tbl&jy2kzFd!tiAA#(DB?GvIS-ju=!ESCFhz9`_Kc zxAW@ij$Ry=G2Y90@TSfb&>q}AXH%$x5Z6#!u3@_nB;pON1YasD8nVD#+nQLtBEyQ6 zL4eg0Feu{QI3VEkwyHpXzrSN|6ccVFKjyh@%EmdD4H9*b!7 zrOr+g2Hv={6%k@#d1_;6#ihEbrz+Kk=qg+L;(cO#M29XuL>I)-TuD;AOCrV5PzOlP z2cYfu)b&%XH@d#hYp+1d?^$#?_q`7;U{#s8VKX2$gfK zYH8)mv2dwgd-Zu?B`#Le4un5W!*Kl*{f5Q_j?P}8XPmnQP%fC&Mqpv|Fknj7`x~|X zqX7Y%#B48}_asRtZKMU1Y(>l6?kVANDNazuwi#bKq_Pm!$5Xcz=|j?i8M^N|Jog$l zs8%-|3*`JQz6arzKaAy&i`x!NZt$P~9^d4_vzx$g)Z5=b%Bj>_XS5O>AmaUrvc+gc zt4WgH;Dx~wjjAiCM@~z)n4gR|Ille!6j(z~wL!4y_C(yI5UwkxPra4=nryOmW2#gD zBC;(zJarPyL6$V$#4_SZ0EN3?)+s`A(#IE_oBm?*$7*3Z+F$zLQf1N=s4r&maAr2qELGSmWPAE7~ zxY`oBz@GxC4$^@5*u!o+V=yhci_@m(z33KcaEnH)A?lsv+M<~CF zY^&sP3baIHxn7}tj9YHqOtstcAg|I$AAn`DVjDS^>#9`aJS?y7eGt+537`{=M?WuaWclV=H=Z^**C@En9T%f$;RI$=+?5lkFiN z;65=R+-iurFyps}@^5GM^mPWp*K!_v?~_jw>jHYZ@2ST6+Pa+pH30vE6@8E=@O62p z-0N90@x-t&G4a6*;lIz#ZW_3owOxrr~6F@<_R4=8MfxbfSPMmYU4CQ&zZ~ zwfaaI1Uqurb;p3C(TxG$N&Bi{&D+b_tBc*qu8t(;_Z9X$ur43(SLZ({Slc<72bUq^ zyHb#6Vr3~M>gHUQQF}zKmU#1IsOx6kCr3A#|8cze|N4bV-U*%n+u8>Kt%0f)YkqIH z?EM1WM!|D27 z&YYQh?tJ(AJ-)f$y$GADudN#l`Fyw|2U`XN@3*NlLy#*@K*5lMJPq#(@gb?7A3ic5 zOnSR;zAc7!@3`Ztb8pk3!l=xP`QzK*@pr?!JrN{+Qjv240HdEX>wYq_w8LMvSjWFE zZ`0V$Sc0ASqUPxlb0j08KAcwuHXL%nSj*XXVWXvVaiKzTeTfShda0ovn1dTt0Qp)TL@B93zQ6DHZM=Q(=r)kg|Q20Aa~n0^M^IG#I&?G z#R8#3&&R`^tr%9`BWOLUHu=k*l#s344B42GxuT!2Z-Iu2p(!b^4k?V^&17(t;5eH= z%=nRF83QYejd88v`zt3jx%<>r!1oP*uou||>zK61ing<<#jHX?hqbdFGY{bZ$+L`W zU+lOz&xwJ_1zf@LM z4$Nw{H89q`t)sF{*fRcs_o=g31kCTPO0X(?jd9npc zt-PsL`Gsn8Ngauh=5u#S7l-@jnV2dHqWWV~AI!zP&+__Qh)pPlrv?qZ3*Bx^wi8BP zBY^7&C{fNBv-$NwiFPk024(qXT0$TC%e${DDk`k7?3pM?jUe6UvDs&$c0lB;FW8kTMk3o0(a@?_erDDrqW}(o+=F_r`{%Cut*%a zX#Z}S>v=mNhhIS+SRqj#epAgV@gJ`MLtj)Qm4B3o9!EEH56f%#<+ONv2 z#>^*FdkN@%J)R%ZLbs7xkSf`Zr^N;@|0n1UO6!Y@_Fvv12Y8S!{pySNeOt5UZbBZd zEkqYMJQ|0e}_?rrr(WpOnMVklR28I*6RP zF~@Z0d3-_)A0QP%(T-Lj-d{M?hD&}zdpZ|Rj|k9?LFGU!v`jt(2NUj1Y7tkH)!x`u zv7tHy6_#hV88$G7l)wMp=zQtTF>G1U5i9G#8#HrsH#jg8o%!qYk9c@`ra&6?l?|Zx z%H;)`wIs}|#vJT1RoXOKysaf7#?` z*49q88u!3@`3Up*B7DtLDAu&cZZa&t_kZNKU(M~6-=Pf)Klpk566PE1)8HL{@qbes BtT6xp literal 0 HcmV?d00001 diff --git a/wrap/python/pybind11/docs/pybind11_vs_boost_python2.svg b/wrap/python/pybind11/docs/pybind11_vs_boost_python2.svg new file mode 100644 index 000000000..5ed6530ca --- /dev/null +++ b/wrap/python/pybind11/docs/pybind11_vs_boost_python2.svg @@ -0,0 +1,427 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/wrap/python/pybind11/docs/reference.rst b/wrap/python/pybind11/docs/reference.rst new file mode 100644 index 000000000..a9fbe6001 --- /dev/null +++ b/wrap/python/pybind11/docs/reference.rst @@ -0,0 +1,117 @@ +.. _reference: + +.. warning:: + + Please be advised that the reference documentation discussing pybind11 + internals is currently incomplete. Please refer to the previous sections + and the pybind11 header files for the nitty gritty details. + +Reference +######### + +.. _macros: + +Macros +====== + +.. doxygendefine:: PYBIND11_MODULE + +.. _core_types: + +Convenience classes for arbitrary Python types +============================================== + +Common member functions +----------------------- + +.. doxygenclass:: object_api + :members: + +Without reference counting +-------------------------- + +.. doxygenclass:: handle + :members: + +With reference counting +----------------------- + +.. doxygenclass:: object + :members: + +.. doxygenfunction:: reinterpret_borrow + +.. doxygenfunction:: reinterpret_steal + +Convenience classes for specific Python types +============================================= + +.. doxygenclass:: module + :members: + +.. doxygengroup:: pytypes + :members: + +.. _extras: + +Passing extra arguments to ``def`` or ``class_`` +================================================ + +.. doxygengroup:: annotations + :members: + +Embedding the interpreter +========================= + +.. doxygendefine:: PYBIND11_EMBEDDED_MODULE + +.. doxygenfunction:: initialize_interpreter + +.. doxygenfunction:: finalize_interpreter + +.. doxygenclass:: scoped_interpreter + +Redirecting C++ streams +======================= + +.. doxygenclass:: scoped_ostream_redirect + +.. doxygenclass:: scoped_estream_redirect + +.. doxygenfunction:: add_ostream_redirect + +Python built-in functions +========================= + +.. doxygengroup:: python_builtins + :members: + +Inheritance +=========== + +See :doc:`/classes` and :doc:`/advanced/classes` for more detail. + +.. doxygendefine:: PYBIND11_OVERLOAD + +.. doxygendefine:: PYBIND11_OVERLOAD_PURE + +.. doxygendefine:: PYBIND11_OVERLOAD_NAME + +.. doxygendefine:: PYBIND11_OVERLOAD_PURE_NAME + +.. doxygenfunction:: get_overload + +Exceptions +========== + +.. doxygenclass:: error_already_set + :members: + +.. doxygenclass:: builtin_exception + :members: + + +Literals +======== + +.. doxygennamespace:: literals diff --git a/wrap/python/pybind11/docs/release.rst b/wrap/python/pybind11/docs/release.rst new file mode 100644 index 000000000..b31bbe97e --- /dev/null +++ b/wrap/python/pybind11/docs/release.rst @@ -0,0 +1,25 @@ +To release a new version of pybind11: + +- Update the version number and push to pypi + - Update ``pybind11/_version.py`` (set release version, remove 'dev'). + - Update ``PYBIND11_VERSION_MAJOR`` etc. in ``include/pybind11/detail/common.h``. + - Ensure that all the information in ``setup.py`` is up-to-date. + - Update version in ``docs/conf.py``. + - Tag release date in ``docs/changelog.rst``. + - ``git add`` and ``git commit``. + - if new minor version: ``git checkout -b vX.Y``, ``git push -u origin vX.Y`` + - ``git tag -a vX.Y.Z -m 'vX.Y.Z release'``. + - ``git push`` + - ``git push --tags``. + - ``python setup.py sdist upload``. + - ``python setup.py bdist_wheel upload``. +- Update conda-forge (https://github.com/conda-forge/pybind11-feedstock) via PR + - download release package from Github: ``wget https://github.com/pybind/pybind11/archive/vX.Y.Z.tar.gz`` + - compute checksum: ``shasum -a 256 vX.Y.Z.tar.gz`` + - change version number and checksum in ``recipe/meta.yml`` +- Get back to work + - Update ``_version.py`` (add 'dev' and increment minor). + - Update version in ``docs/conf.py`` + - Update version macros in ``include/pybind11/common.h`` + - ``git add`` and ``git commit``. + ``git push`` diff --git a/wrap/python/pybind11/docs/requirements.txt b/wrap/python/pybind11/docs/requirements.txt new file mode 100644 index 000000000..3818fe80e --- /dev/null +++ b/wrap/python/pybind11/docs/requirements.txt @@ -0,0 +1 @@ +breathe == 4.5.0 diff --git a/wrap/python/pybind11/docs/upgrade.rst b/wrap/python/pybind11/docs/upgrade.rst new file mode 100644 index 000000000..3f5697391 --- /dev/null +++ b/wrap/python/pybind11/docs/upgrade.rst @@ -0,0 +1,404 @@ +Upgrade guide +############# + +This is a companion guide to the :doc:`changelog`. While the changelog briefly +lists all of the new features, improvements and bug fixes, this upgrade guide +focuses only the subset which directly impacts your experience when upgrading +to a new version. But it goes into more detail. This includes things like +deprecated APIs and their replacements, build system changes, general code +modernization and other useful information. + + +v2.2 +==== + +Deprecation of the ``PYBIND11_PLUGIN`` macro +-------------------------------------------- + +``PYBIND11_MODULE`` is now the preferred way to create module entry points. +The old macro emits a compile-time deprecation warning. + +.. code-block:: cpp + + // old + PYBIND11_PLUGIN(example) { + py::module m("example", "documentation string"); + + m.def("add", [](int a, int b) { return a + b; }); + + return m.ptr(); + } + + // new + PYBIND11_MODULE(example, m) { + m.doc() = "documentation string"; // optional + + m.def("add", [](int a, int b) { return a + b; }); + } + + +New API for defining custom constructors and pickling functions +--------------------------------------------------------------- + +The old placement-new custom constructors have been deprecated. The new approach +uses ``py::init()`` and factory functions to greatly improve type safety. + +Placement-new can be called accidentally with an incompatible type (without any +compiler errors or warnings), or it can initialize the same object multiple times +if not careful with the Python-side ``__init__`` calls. The new-style custom +constructors prevent such mistakes. See :ref:`custom_constructors` for details. + +.. code-block:: cpp + + // old -- deprecated (runtime warning shown only in debug mode) + py::class(m, "Foo") + .def("__init__", [](Foo &self, ...) { + new (&self) Foo(...); // uses placement-new + }); + + // new + py::class(m, "Foo") + .def(py::init([](...) { // Note: no `self` argument + return new Foo(...); // return by raw pointer + // or: return std::make_unique(...); // return by holder + // or: return Foo(...); // return by value (move constructor) + })); + +Mirroring the custom constructor changes, ``py::pickle()`` is now the preferred +way to get and set object state. See :ref:`pickling` for details. + +.. code-block:: cpp + + // old -- deprecated (runtime warning shown only in debug mode) + py::class(m, "Foo") + ... + .def("__getstate__", [](const Foo &self) { + return py::make_tuple(self.value1(), self.value2(), ...); + }) + .def("__setstate__", [](Foo &self, py::tuple t) { + new (&self) Foo(t[0].cast(), ...); + }); + + // new + py::class(m, "Foo") + ... + .def(py::pickle( + [](const Foo &self) { // __getstate__ + return py::make_tuple(f.value1(), f.value2(), ...); // unchanged + }, + [](py::tuple t) { // __setstate__, note: no `self` argument + return new Foo(t[0].cast(), ...); + // or: return std::make_unique(...); // return by holder + // or: return Foo(...); // return by value (move constructor) + } + )); + +For both the constructors and pickling, warnings are shown at module +initialization time (on import, not when the functions are called). +They're only visible when compiled in debug mode. Sample warning: + +.. code-block:: none + + pybind11-bound class 'mymodule.Foo' is using an old-style placement-new '__init__' + which has been deprecated. See the upgrade guide in pybind11's docs. + + +Stricter enforcement of hidden symbol visibility for pybind11 modules +--------------------------------------------------------------------- + +pybind11 now tries to actively enforce hidden symbol visibility for modules. +If you're using either one of pybind11's :doc:`CMake or Python build systems +` (the two example repositories) and you haven't been exporting any +symbols, there's nothing to be concerned about. All the changes have been done +transparently in the background. If you were building manually or relied on +specific default visibility, read on. + +Setting default symbol visibility to *hidden* has always been recommended for +pybind11 (see :ref:`faq:symhidden`). On Linux and macOS, hidden symbol +visibility (in conjunction with the ``strip`` utility) yields much smaller +module binaries. `CPython's extension docs`_ also recommend hiding symbols +by default, with the goal of avoiding symbol name clashes between modules. +Starting with v2.2, pybind11 enforces this more strictly: (1) by declaring +all symbols inside the ``pybind11`` namespace as hidden and (2) by including +the ``-fvisibility=hidden`` flag on Linux and macOS (only for extension +modules, not for embedding the interpreter). + +.. _CPython's extension docs: https://docs.python.org/3/extending/extending.html#providing-a-c-api-for-an-extension-module + +The namespace-scope hidden visibility is done automatically in pybind11's +headers and it's generally transparent to users. It ensures that: + +* Modules compiled with different pybind11 versions don't clash with each other. + +* Some new features, like ``py::module_local`` bindings, can work as intended. + +The ``-fvisibility=hidden`` flag applies the same visibility to user bindings +outside of the ``pybind11`` namespace. It's now set automatic by pybind11's +CMake and Python build systems, but this needs to be done manually by users +of other build systems. Adding this flag: + +* Minimizes the chances of symbol conflicts between modules. E.g. if two + unrelated modules were statically linked to different (ABI-incompatible) + versions of the same third-party library, a symbol clash would be likely + (and would end with unpredictable results). + +* Produces smaller binaries on Linux and macOS, as pointed out previously. + +Within pybind11's CMake build system, ``pybind11_add_module`` has always been +setting the ``-fvisibility=hidden`` flag in release mode. From now on, it's +being applied unconditionally, even in debug mode and it can no longer be opted +out of with the ``NO_EXTRAS`` option. The ``pybind11::module`` target now also +adds this flag to it's interface. The ``pybind11::embed`` target is unchanged. + +The most significant change here is for the ``pybind11::module`` target. If you +were previously relying on default visibility, i.e. if your Python module was +doubling as a shared library with dependents, you'll need to either export +symbols manually (recommended for cross-platform libraries) or factor out the +shared library (and have the Python module link to it like the other +dependents). As a temporary workaround, you can also restore default visibility +using the CMake code below, but this is not recommended in the long run: + +.. code-block:: cmake + + target_link_libraries(mymodule PRIVATE pybind11::module) + + add_library(restore_default_visibility INTERFACE) + target_compile_options(restore_default_visibility INTERFACE -fvisibility=default) + target_link_libraries(mymodule PRIVATE restore_default_visibility) + + +Local STL container bindings +---------------------------- + +Previous pybind11 versions could only bind types globally -- all pybind11 +modules, even unrelated ones, would have access to the same exported types. +However, this would also result in a conflict if two modules exported the +same C++ type, which is especially problematic for very common types, e.g. +``std::vector``. :ref:`module_local` were added to resolve this (see +that section for a complete usage guide). + +``py::class_`` still defaults to global bindings (because these types are +usually unique across modules), however in order to avoid clashes of opaque +types, ``py::bind_vector`` and ``py::bind_map`` will now bind STL containers +as ``py::module_local`` if their elements are: builtins (``int``, ``float``, +etc.), not bound using ``py::class_``, or bound as ``py::module_local``. For +example, this change allows multiple modules to bind ``std::vector`` +without causing conflicts. See :ref:`stl_bind` for more details. + +When upgrading to this version, if you have multiple modules which depend on +a single global binding of an STL container, note that all modules can still +accept foreign ``py::module_local`` types in the direction of Python-to-C++. +The locality only affects the C++-to-Python direction. If this is needed in +multiple modules, you'll need to either: + +* Add a copy of the same STL binding to all of the modules which need it. + +* Restore the global status of that single binding by marking it + ``py::module_local(false)``. + +The latter is an easy workaround, but in the long run it would be best to +localize all common type bindings in order to avoid conflicts with +third-party modules. + + +Negative strides for Python buffer objects and numpy arrays +----------------------------------------------------------- + +Support for negative strides required changing the integer type from unsigned +to signed in the interfaces of ``py::buffer_info`` and ``py::array``. If you +have compiler warnings enabled, you may notice some new conversion warnings +after upgrading. These can be resolved using ``static_cast``. + + +Deprecation of some ``py::object`` APIs +--------------------------------------- + +To compare ``py::object`` instances by pointer, you should now use +``obj1.is(obj2)`` which is equivalent to ``obj1 is obj2`` in Python. +Previously, pybind11 used ``operator==`` for this (``obj1 == obj2``), but +that could be confusing and is now deprecated (so that it can eventually +be replaced with proper rich object comparison in a future release). + +For classes which inherit from ``py::object``, ``borrowed`` and ``stolen`` +were previously available as protected constructor tags. Now the types +should be used directly instead: ``borrowed_t{}`` and ``stolen_t{}`` +(`#771 `_). + + +Stricter compile-time error checking +------------------------------------ + +Some error checks have been moved from run time to compile time. Notably, +automatic conversion of ``std::shared_ptr`` is not possible when ``T`` is +not directly registered with ``py::class_`` (e.g. ``std::shared_ptr`` +or ``std::shared_ptr>`` are not automatically convertible). +Attempting to bind a function with such arguments now results in a compile-time +error instead of waiting to fail at run time. + +``py::init<...>()`` constructor definitions are also stricter and now prevent +bindings which could cause unexpected behavior: + +.. code-block:: cpp + + struct Example { + Example(int &); + }; + + py::class_(m, "Example") + .def(py::init()); // OK, exact match + // .def(py::init()); // compile-time error, mismatch + +A non-``const`` lvalue reference is not allowed to bind to an rvalue. However, +note that a constructor taking ``const T &`` can still be registered using +``py::init()`` because a ``const`` lvalue reference can bind to an rvalue. + +v2.1 +==== + +Minimum compiler versions are enforced at compile time +------------------------------------------------------ + +The minimums also apply to v2.0 but the check is now explicit and a compile-time +error is raised if the compiler does not meet the requirements: + +* GCC >= 4.8 +* clang >= 3.3 (appleclang >= 5.0) +* MSVC >= 2015u3 +* Intel C++ >= 15.0 + + +The ``py::metaclass`` attribute is not required for static properties +--------------------------------------------------------------------- + +Binding classes with static properties is now possible by default. The +zero-parameter version of ``py::metaclass()`` is deprecated. However, a new +one-parameter ``py::metaclass(python_type)`` version was added for rare +cases when a custom metaclass is needed to override pybind11's default. + +.. code-block:: cpp + + // old -- emits a deprecation warning + py::class_(m, "Foo", py::metaclass()) + .def_property_readonly_static("foo", ...); + + // new -- static properties work without the attribute + py::class_(m, "Foo") + .def_property_readonly_static("foo", ...); + + // new -- advanced feature, override pybind11's default metaclass + py::class_(m, "Bar", py::metaclass(custom_python_type)) + ... + + +v2.0 +==== + +Breaking changes in ``py::class_`` +---------------------------------- + +These changes were necessary to make type definitions in pybind11 +future-proof, to support PyPy via its ``cpyext`` mechanism (`#527 +`_), and to improve efficiency +(`rev. 86d825 `_). + +1. Declarations of types that provide access via the buffer protocol must + now include the ``py::buffer_protocol()`` annotation as an argument to + the ``py::class_`` constructor. + + .. code-block:: cpp + + py::class_("Matrix", py::buffer_protocol()) + .def(py::init<...>()) + .def_buffer(...); + +2. Classes which include static properties (e.g. ``def_readwrite_static()``) + must now include the ``py::metaclass()`` attribute. Note: this requirement + has since been removed in v2.1. If you're upgrading from 1.x, it's + recommended to skip directly to v2.1 or newer. + +3. This version of pybind11 uses a redesigned mechanism for instantiating + trampoline classes that are used to override virtual methods from within + Python. This led to the following user-visible syntax change: + + .. code-block:: cpp + + // old v1.x syntax + py::class_("MyClass") + .alias() + ... + + // new v2.x syntax + py::class_("MyClass") + ... + + Importantly, both the original and the trampoline class are now specified + as arguments to the ``py::class_`` template, and the ``alias<..>()`` call + is gone. The new scheme has zero overhead in cases when Python doesn't + override any functions of the underlying C++ class. + `rev. 86d825 `_. + + The class type must be the first template argument given to ``py::class_`` + while the trampoline can be mixed in arbitrary order with other arguments + (see the following section). + + +Deprecation of the ``py::base()`` attribute +---------------------------------------------- + +``py::base()`` was deprecated in favor of specifying ``T`` as a template +argument to ``py::class_``. This new syntax also supports multiple inheritance. +Note that, while the type being exported must be the first argument in the +``py::class_`` template, the order of the following types (bases, +holder and/or trampoline) is not important. + +.. code-block:: cpp + + // old v1.x + py::class_("Derived", py::base()); + + // new v2.x + py::class_("Derived"); + + // new -- multiple inheritance + py::class_("Derived"); + + // new -- apart from `Derived` the argument order can be arbitrary + py::class_("Derived"); + + +Out-of-the-box support for ``std::shared_ptr`` +---------------------------------------------- + +The relevant type caster is now built in, so it's no longer necessary to +include a declaration of the form: + +.. code-block:: cpp + + PYBIND11_DECLARE_HOLDER_TYPE(T, std::shared_ptr) + +Continuing to do so won’t cause an error or even a deprecation warning, +but it's completely redundant. + + +Deprecation of a few ``py::object`` APIs +---------------------------------------- + +All of the old-style calls emit deprecation warnings. + ++---------------------------------------+---------------------------------------------+ +| Old syntax | New syntax | ++=======================================+=============================================+ +| ``obj.call(args...)`` | ``obj(args...)`` | ++---------------------------------------+---------------------------------------------+ +| ``obj.str()`` | ``py::str(obj)`` | ++---------------------------------------+---------------------------------------------+ +| ``auto l = py::list(obj); l.check()`` | ``py::isinstance(obj)`` | ++---------------------------------------+---------------------------------------------+ +| ``py::object(ptr, true)`` | ``py::reinterpret_borrow(ptr)`` | ++---------------------------------------+---------------------------------------------+ +| ``py::object(ptr, false)`` | ``py::reinterpret_steal(ptr)`` | ++---------------------------------------+---------------------------------------------+ +| ``if (obj.attr("foo"))`` | ``if (py::hasattr(obj, "foo"))`` | ++---------------------------------------+---------------------------------------------+ +| ``if (obj["bar"])`` | ``if (obj.contains("bar"))`` | ++---------------------------------------+---------------------------------------------+ diff --git a/wrap/python/pybind11/include/pybind11/attr.h b/wrap/python/pybind11/include/pybind11/attr.h new file mode 100644 index 000000000..6962d6fc5 --- /dev/null +++ b/wrap/python/pybind11/include/pybind11/attr.h @@ -0,0 +1,493 @@ +/* + pybind11/attr.h: Infrastructure for processing custom + type and function attributes + + Copyright (c) 2016 Wenzel Jakob + + All rights reserved. Use of this source code is governed by a + BSD-style license that can be found in the LICENSE file. +*/ + +#pragma once + +#include "cast.h" + +NAMESPACE_BEGIN(PYBIND11_NAMESPACE) + +/// \addtogroup annotations +/// @{ + +/// Annotation for methods +struct is_method { handle class_; is_method(const handle &c) : class_(c) { } }; + +/// Annotation for operators +struct is_operator { }; + +/// Annotation for parent scope +struct scope { handle value; scope(const handle &s) : value(s) { } }; + +/// Annotation for documentation +struct doc { const char *value; doc(const char *value) : value(value) { } }; + +/// Annotation for function names +struct name { const char *value; name(const char *value) : value(value) { } }; + +/// Annotation indicating that a function is an overload associated with a given "sibling" +struct sibling { handle value; sibling(const handle &value) : value(value.ptr()) { } }; + +/// Annotation indicating that a class derives from another given type +template struct base { + PYBIND11_DEPRECATED("base() was deprecated in favor of specifying 'T' as a template argument to class_") + base() { } +}; + +/// Keep patient alive while nurse lives +template struct keep_alive { }; + +/// Annotation indicating that a class is involved in a multiple inheritance relationship +struct multiple_inheritance { }; + +/// Annotation which enables dynamic attributes, i.e. adds `__dict__` to a class +struct dynamic_attr { }; + +/// Annotation which enables the buffer protocol for a type +struct buffer_protocol { }; + +/// Annotation which requests that a special metaclass is created for a type +struct metaclass { + handle value; + + PYBIND11_DEPRECATED("py::metaclass() is no longer required. It's turned on by default now.") + metaclass() {} + + /// Override pybind11's default metaclass + explicit metaclass(handle value) : value(value) { } +}; + +/// Annotation that marks a class as local to the module: +struct module_local { const bool value; constexpr module_local(bool v = true) : value(v) { } }; + +/// Annotation to mark enums as an arithmetic type +struct arithmetic { }; + +/** \rst + A call policy which places one or more guard variables (``Ts...``) around the function call. + + For example, this definition: + + .. code-block:: cpp + + m.def("foo", foo, py::call_guard()); + + is equivalent to the following pseudocode: + + .. code-block:: cpp + + m.def("foo", [](args...) { + T scope_guard; + return foo(args...); // forwarded arguments + }); + \endrst */ +template struct call_guard; + +template <> struct call_guard<> { using type = detail::void_type; }; + +template +struct call_guard { + static_assert(std::is_default_constructible::value, + "The guard type must be default constructible"); + + using type = T; +}; + +template +struct call_guard { + struct type { + T guard{}; // Compose multiple guard types with left-to-right default-constructor order + typename call_guard::type next{}; + }; +}; + +/// @} annotations + +NAMESPACE_BEGIN(detail) +/* Forward declarations */ +enum op_id : int; +enum op_type : int; +struct undefined_t; +template struct op_; +inline void keep_alive_impl(size_t Nurse, size_t Patient, function_call &call, handle ret); + +/// Internal data structure which holds metadata about a keyword argument +struct argument_record { + const char *name; ///< Argument name + const char *descr; ///< Human-readable version of the argument value + handle value; ///< Associated Python object + bool convert : 1; ///< True if the argument is allowed to convert when loading + bool none : 1; ///< True if None is allowed when loading + + argument_record(const char *name, const char *descr, handle value, bool convert, bool none) + : name(name), descr(descr), value(value), convert(convert), none(none) { } +}; + +/// Internal data structure which holds metadata about a bound function (signature, overloads, etc.) +struct function_record { + function_record() + : is_constructor(false), is_new_style_constructor(false), is_stateless(false), + is_operator(false), has_args(false), has_kwargs(false), is_method(false) { } + + /// Function name + char *name = nullptr; /* why no C++ strings? They generate heavier code.. */ + + // User-specified documentation string + char *doc = nullptr; + + /// Human-readable version of the function signature + char *signature = nullptr; + + /// List of registered keyword arguments + std::vector args; + + /// Pointer to lambda function which converts arguments and performs the actual call + handle (*impl) (function_call &) = nullptr; + + /// Storage for the wrapped function pointer and captured data, if any + void *data[3] = { }; + + /// Pointer to custom destructor for 'data' (if needed) + void (*free_data) (function_record *ptr) = nullptr; + + /// Return value policy associated with this function + return_value_policy policy = return_value_policy::automatic; + + /// True if name == '__init__' + bool is_constructor : 1; + + /// True if this is a new-style `__init__` defined in `detail/init.h` + bool is_new_style_constructor : 1; + + /// True if this is a stateless function pointer + bool is_stateless : 1; + + /// True if this is an operator (__add__), etc. + bool is_operator : 1; + + /// True if the function has a '*args' argument + bool has_args : 1; + + /// True if the function has a '**kwargs' argument + bool has_kwargs : 1; + + /// True if this is a method + bool is_method : 1; + + /// Number of arguments (including py::args and/or py::kwargs, if present) + std::uint16_t nargs; + + /// Python method object + PyMethodDef *def = nullptr; + + /// Python handle to the parent scope (a class or a module) + handle scope; + + /// Python handle to the sibling function representing an overload chain + handle sibling; + + /// Pointer to next overload + function_record *next = nullptr; +}; + +/// Special data structure which (temporarily) holds metadata about a bound class +struct type_record { + PYBIND11_NOINLINE type_record() + : multiple_inheritance(false), dynamic_attr(false), buffer_protocol(false), + default_holder(true), module_local(false) { } + + /// Handle to the parent scope + handle scope; + + /// Name of the class + const char *name = nullptr; + + // Pointer to RTTI type_info data structure + const std::type_info *type = nullptr; + + /// How large is the underlying C++ type? + size_t type_size = 0; + + /// What is the alignment of the underlying C++ type? + size_t type_align = 0; + + /// How large is the type's holder? + size_t holder_size = 0; + + /// The global operator new can be overridden with a class-specific variant + void *(*operator_new)(size_t) = nullptr; + + /// Function pointer to class_<..>::init_instance + void (*init_instance)(instance *, const void *) = nullptr; + + /// Function pointer to class_<..>::dealloc + void (*dealloc)(detail::value_and_holder &) = nullptr; + + /// List of base classes of the newly created type + list bases; + + /// Optional docstring + const char *doc = nullptr; + + /// Custom metaclass (optional) + handle metaclass; + + /// Multiple inheritance marker + bool multiple_inheritance : 1; + + /// Does the class manage a __dict__? + bool dynamic_attr : 1; + + /// Does the class implement the buffer protocol? + bool buffer_protocol : 1; + + /// Is the default (unique_ptr) holder type used? + bool default_holder : 1; + + /// Is the class definition local to the module shared object? + bool module_local : 1; + + PYBIND11_NOINLINE void add_base(const std::type_info &base, void *(*caster)(void *)) { + auto base_info = detail::get_type_info(base, false); + if (!base_info) { + std::string tname(base.name()); + detail::clean_type_id(tname); + pybind11_fail("generic_type: type \"" + std::string(name) + + "\" referenced unknown base type \"" + tname + "\""); + } + + if (default_holder != base_info->default_holder) { + std::string tname(base.name()); + detail::clean_type_id(tname); + pybind11_fail("generic_type: type \"" + std::string(name) + "\" " + + (default_holder ? "does not have" : "has") + + " a non-default holder type while its base \"" + tname + "\" " + + (base_info->default_holder ? "does not" : "does")); + } + + bases.append((PyObject *) base_info->type); + + if (base_info->type->tp_dictoffset != 0) + dynamic_attr = true; + + if (caster) + base_info->implicit_casts.emplace_back(type, caster); + } +}; + +inline function_call::function_call(const function_record &f, handle p) : + func(f), parent(p) { + args.reserve(f.nargs); + args_convert.reserve(f.nargs); +} + +/// Tag for a new-style `__init__` defined in `detail/init.h` +struct is_new_style_constructor { }; + +/** + * Partial template specializations to process custom attributes provided to + * cpp_function_ and class_. These are either used to initialize the respective + * fields in the type_record and function_record data structures or executed at + * runtime to deal with custom call policies (e.g. keep_alive). + */ +template struct process_attribute; + +template struct process_attribute_default { + /// Default implementation: do nothing + static void init(const T &, function_record *) { } + static void init(const T &, type_record *) { } + static void precall(function_call &) { } + static void postcall(function_call &, handle) { } +}; + +/// Process an attribute specifying the function's name +template <> struct process_attribute : process_attribute_default { + static void init(const name &n, function_record *r) { r->name = const_cast(n.value); } +}; + +/// Process an attribute specifying the function's docstring +template <> struct process_attribute : process_attribute_default { + static void init(const doc &n, function_record *r) { r->doc = const_cast(n.value); } +}; + +/// Process an attribute specifying the function's docstring (provided as a C-style string) +template <> struct process_attribute : process_attribute_default { + static void init(const char *d, function_record *r) { r->doc = const_cast(d); } + static void init(const char *d, type_record *r) { r->doc = const_cast(d); } +}; +template <> struct process_attribute : process_attribute { }; + +/// Process an attribute indicating the function's return value policy +template <> struct process_attribute : process_attribute_default { + static void init(const return_value_policy &p, function_record *r) { r->policy = p; } +}; + +/// Process an attribute which indicates that this is an overloaded function associated with a given sibling +template <> struct process_attribute : process_attribute_default { + static void init(const sibling &s, function_record *r) { r->sibling = s.value; } +}; + +/// Process an attribute which indicates that this function is a method +template <> struct process_attribute : process_attribute_default { + static void init(const is_method &s, function_record *r) { r->is_method = true; r->scope = s.class_; } +}; + +/// Process an attribute which indicates the parent scope of a method +template <> struct process_attribute : process_attribute_default { + static void init(const scope &s, function_record *r) { r->scope = s.value; } +}; + +/// Process an attribute which indicates that this function is an operator +template <> struct process_attribute : process_attribute_default { + static void init(const is_operator &, function_record *r) { r->is_operator = true; } +}; + +template <> struct process_attribute : process_attribute_default { + static void init(const is_new_style_constructor &, function_record *r) { r->is_new_style_constructor = true; } +}; + +/// Process a keyword argument attribute (*without* a default value) +template <> struct process_attribute : process_attribute_default { + static void init(const arg &a, function_record *r) { + if (r->is_method && r->args.empty()) + r->args.emplace_back("self", nullptr, handle(), true /*convert*/, false /*none not allowed*/); + r->args.emplace_back(a.name, nullptr, handle(), !a.flag_noconvert, a.flag_none); + } +}; + +/// Process a keyword argument attribute (*with* a default value) +template <> struct process_attribute : process_attribute_default { + static void init(const arg_v &a, function_record *r) { + if (r->is_method && r->args.empty()) + r->args.emplace_back("self", nullptr /*descr*/, handle() /*parent*/, true /*convert*/, false /*none not allowed*/); + + if (!a.value) { +#if !defined(NDEBUG) + std::string descr("'"); + if (a.name) descr += std::string(a.name) + ": "; + descr += a.type + "'"; + if (r->is_method) { + if (r->name) + descr += " in method '" + (std::string) str(r->scope) + "." + (std::string) r->name + "'"; + else + descr += " in method of '" + (std::string) str(r->scope) + "'"; + } else if (r->name) { + descr += " in function '" + (std::string) r->name + "'"; + } + pybind11_fail("arg(): could not convert default argument " + + descr + " into a Python object (type not registered yet?)"); +#else + pybind11_fail("arg(): could not convert default argument " + "into a Python object (type not registered yet?). " + "Compile in debug mode for more information."); +#endif + } + r->args.emplace_back(a.name, a.descr, a.value.inc_ref(), !a.flag_noconvert, a.flag_none); + } +}; + +/// Process a parent class attribute. Single inheritance only (class_ itself already guarantees that) +template +struct process_attribute::value>> : process_attribute_default { + static void init(const handle &h, type_record *r) { r->bases.append(h); } +}; + +/// Process a parent class attribute (deprecated, does not support multiple inheritance) +template +struct process_attribute> : process_attribute_default> { + static void init(const base &, type_record *r) { r->add_base(typeid(T), nullptr); } +}; + +/// Process a multiple inheritance attribute +template <> +struct process_attribute : process_attribute_default { + static void init(const multiple_inheritance &, type_record *r) { r->multiple_inheritance = true; } +}; + +template <> +struct process_attribute : process_attribute_default { + static void init(const dynamic_attr &, type_record *r) { r->dynamic_attr = true; } +}; + +template <> +struct process_attribute : process_attribute_default { + static void init(const buffer_protocol &, type_record *r) { r->buffer_protocol = true; } +}; + +template <> +struct process_attribute : process_attribute_default { + static void init(const metaclass &m, type_record *r) { r->metaclass = m.value; } +}; + +template <> +struct process_attribute : process_attribute_default { + static void init(const module_local &l, type_record *r) { r->module_local = l.value; } +}; + +/// Process an 'arithmetic' attribute for enums (does nothing here) +template <> +struct process_attribute : process_attribute_default {}; + +template +struct process_attribute> : process_attribute_default> { }; + +/** + * Process a keep_alive call policy -- invokes keep_alive_impl during the + * pre-call handler if both Nurse, Patient != 0 and use the post-call handler + * otherwise + */ +template struct process_attribute> : public process_attribute_default> { + template = 0> + static void precall(function_call &call) { keep_alive_impl(Nurse, Patient, call, handle()); } + template = 0> + static void postcall(function_call &, handle) { } + template = 0> + static void precall(function_call &) { } + template = 0> + static void postcall(function_call &call, handle ret) { keep_alive_impl(Nurse, Patient, call, ret); } +}; + +/// Recursively iterate over variadic template arguments +template struct process_attributes { + static void init(const Args&... args, function_record *r) { + int unused[] = { 0, (process_attribute::type>::init(args, r), 0) ... }; + ignore_unused(unused); + } + static void init(const Args&... args, type_record *r) { + int unused[] = { 0, (process_attribute::type>::init(args, r), 0) ... }; + ignore_unused(unused); + } + static void precall(function_call &call) { + int unused[] = { 0, (process_attribute::type>::precall(call), 0) ... }; + ignore_unused(unused); + } + static void postcall(function_call &call, handle fn_ret) { + int unused[] = { 0, (process_attribute::type>::postcall(call, fn_ret), 0) ... }; + ignore_unused(unused); + } +}; + +template +using is_call_guard = is_instantiation; + +/// Extract the ``type`` from the first `call_guard` in `Extras...` (or `void_type` if none found) +template +using extract_guard_t = typename exactly_one_t, Extra...>::type; + +/// Check the number of named arguments at compile time +template ::value...), + size_t self = constexpr_sum(std::is_same::value...)> +constexpr bool expected_num_args(size_t nargs, bool has_args, bool has_kwargs) { + return named == 0 || (self + named + has_args + has_kwargs) == nargs; +} + +NAMESPACE_END(detail) +NAMESPACE_END(PYBIND11_NAMESPACE) diff --git a/wrap/python/pybind11/include/pybind11/buffer_info.h b/wrap/python/pybind11/include/pybind11/buffer_info.h new file mode 100644 index 000000000..9f072fa73 --- /dev/null +++ b/wrap/python/pybind11/include/pybind11/buffer_info.h @@ -0,0 +1,108 @@ +/* + pybind11/buffer_info.h: Python buffer object interface + + Copyright (c) 2016 Wenzel Jakob + + All rights reserved. Use of this source code is governed by a + BSD-style license that can be found in the LICENSE file. +*/ + +#pragma once + +#include "detail/common.h" + +NAMESPACE_BEGIN(PYBIND11_NAMESPACE) + +/// Information record describing a Python buffer object +struct buffer_info { + void *ptr = nullptr; // Pointer to the underlying storage + ssize_t itemsize = 0; // Size of individual items in bytes + ssize_t size = 0; // Total number of entries + std::string format; // For homogeneous buffers, this should be set to format_descriptor::format() + ssize_t ndim = 0; // Number of dimensions + std::vector shape; // Shape of the tensor (1 entry per dimension) + std::vector strides; // Number of entries between adjacent entries (for each per dimension) + + buffer_info() { } + + buffer_info(void *ptr, ssize_t itemsize, const std::string &format, ssize_t ndim, + detail::any_container shape_in, detail::any_container strides_in) + : ptr(ptr), itemsize(itemsize), size(1), format(format), ndim(ndim), + shape(std::move(shape_in)), strides(std::move(strides_in)) { + if (ndim != (ssize_t) shape.size() || ndim != (ssize_t) strides.size()) + pybind11_fail("buffer_info: ndim doesn't match shape and/or strides length"); + for (size_t i = 0; i < (size_t) ndim; ++i) + size *= shape[i]; + } + + template + buffer_info(T *ptr, detail::any_container shape_in, detail::any_container strides_in) + : buffer_info(private_ctr_tag(), ptr, sizeof(T), format_descriptor::format(), static_cast(shape_in->size()), std::move(shape_in), std::move(strides_in)) { } + + buffer_info(void *ptr, ssize_t itemsize, const std::string &format, ssize_t size) + : buffer_info(ptr, itemsize, format, 1, {size}, {itemsize}) { } + + template + buffer_info(T *ptr, ssize_t size) + : buffer_info(ptr, sizeof(T), format_descriptor::format(), size) { } + + explicit buffer_info(Py_buffer *view, bool ownview = true) + : buffer_info(view->buf, view->itemsize, view->format, view->ndim, + {view->shape, view->shape + view->ndim}, {view->strides, view->strides + view->ndim}) { + this->view = view; + this->ownview = ownview; + } + + buffer_info(const buffer_info &) = delete; + buffer_info& operator=(const buffer_info &) = delete; + + buffer_info(buffer_info &&other) { + (*this) = std::move(other); + } + + buffer_info& operator=(buffer_info &&rhs) { + ptr = rhs.ptr; + itemsize = rhs.itemsize; + size = rhs.size; + format = std::move(rhs.format); + ndim = rhs.ndim; + shape = std::move(rhs.shape); + strides = std::move(rhs.strides); + std::swap(view, rhs.view); + std::swap(ownview, rhs.ownview); + return *this; + } + + ~buffer_info() { + if (view && ownview) { PyBuffer_Release(view); delete view; } + } + +private: + struct private_ctr_tag { }; + + buffer_info(private_ctr_tag, void *ptr, ssize_t itemsize, const std::string &format, ssize_t ndim, + detail::any_container &&shape_in, detail::any_container &&strides_in) + : buffer_info(ptr, itemsize, format, ndim, std::move(shape_in), std::move(strides_in)) { } + + Py_buffer *view = nullptr; + bool ownview = false; +}; + +NAMESPACE_BEGIN(detail) + +template struct compare_buffer_info { + static bool compare(const buffer_info& b) { + return b.format == format_descriptor::format() && b.itemsize == (ssize_t) sizeof(T); + } +}; + +template struct compare_buffer_info::value>> { + static bool compare(const buffer_info& b) { + return (size_t) b.itemsize == sizeof(T) && (b.format == format_descriptor::value || + ((sizeof(T) == sizeof(long)) && b.format == (std::is_unsigned::value ? "L" : "l")) || + ((sizeof(T) == sizeof(size_t)) && b.format == (std::is_unsigned::value ? "N" : "n"))); + } +}; + +NAMESPACE_END(detail) +NAMESPACE_END(PYBIND11_NAMESPACE) diff --git a/wrap/python/pybind11/include/pybind11/cast.h b/wrap/python/pybind11/include/pybind11/cast.h new file mode 100644 index 000000000..8d0fd5d90 --- /dev/null +++ b/wrap/python/pybind11/include/pybind11/cast.h @@ -0,0 +1,2128 @@ +/* + pybind11/cast.h: Partial template specializations to cast between + C++ and Python types + + Copyright (c) 2016 Wenzel Jakob + + All rights reserved. Use of this source code is governed by a + BSD-style license that can be found in the LICENSE file. +*/ + +#pragma once + +#include "pytypes.h" +#include "detail/typeid.h" +#include "detail/descr.h" +#include "detail/internals.h" +#include +#include +#include +#include + +#if defined(PYBIND11_CPP17) +# if defined(__has_include) +# if __has_include() +# define PYBIND11_HAS_STRING_VIEW +# endif +# elif defined(_MSC_VER) +# define PYBIND11_HAS_STRING_VIEW +# endif +#endif +#ifdef PYBIND11_HAS_STRING_VIEW +#include +#endif + +NAMESPACE_BEGIN(PYBIND11_NAMESPACE) +NAMESPACE_BEGIN(detail) + +/// A life support system for temporary objects created by `type_caster::load()`. +/// Adding a patient will keep it alive up until the enclosing function returns. +class loader_life_support { +public: + /// A new patient frame is created when a function is entered + loader_life_support() { + get_internals().loader_patient_stack.push_back(nullptr); + } + + /// ... and destroyed after it returns + ~loader_life_support() { + auto &stack = get_internals().loader_patient_stack; + if (stack.empty()) + pybind11_fail("loader_life_support: internal error"); + + auto ptr = stack.back(); + stack.pop_back(); + Py_CLEAR(ptr); + + // A heuristic to reduce the stack's capacity (e.g. after long recursive calls) + if (stack.capacity() > 16 && stack.size() != 0 && stack.capacity() / stack.size() > 2) + stack.shrink_to_fit(); + } + + /// This can only be used inside a pybind11-bound function, either by `argument_loader` + /// at argument preparation time or by `py::cast()` at execution time. + PYBIND11_NOINLINE static void add_patient(handle h) { + auto &stack = get_internals().loader_patient_stack; + if (stack.empty()) + throw cast_error("When called outside a bound function, py::cast() cannot " + "do Python -> C++ conversions which require the creation " + "of temporary values"); + + auto &list_ptr = stack.back(); + if (list_ptr == nullptr) { + list_ptr = PyList_New(1); + if (!list_ptr) + pybind11_fail("loader_life_support: error allocating list"); + PyList_SET_ITEM(list_ptr, 0, h.inc_ref().ptr()); + } else { + auto result = PyList_Append(list_ptr, h.ptr()); + if (result == -1) + pybind11_fail("loader_life_support: error adding patient"); + } + } +}; + +// Gets the cache entry for the given type, creating it if necessary. The return value is the pair +// returned by emplace, i.e. an iterator for the entry and a bool set to `true` if the entry was +// just created. +inline std::pair all_type_info_get_cache(PyTypeObject *type); + +// Populates a just-created cache entry. +PYBIND11_NOINLINE inline void all_type_info_populate(PyTypeObject *t, std::vector &bases) { + std::vector check; + for (handle parent : reinterpret_borrow(t->tp_bases)) + check.push_back((PyTypeObject *) parent.ptr()); + + auto const &type_dict = get_internals().registered_types_py; + for (size_t i = 0; i < check.size(); i++) { + auto type = check[i]; + // Ignore Python2 old-style class super type: + if (!PyType_Check((PyObject *) type)) continue; + + // Check `type` in the current set of registered python types: + auto it = type_dict.find(type); + if (it != type_dict.end()) { + // We found a cache entry for it, so it's either pybind-registered or has pre-computed + // pybind bases, but we have to make sure we haven't already seen the type(s) before: we + // want to follow Python/virtual C++ rules that there should only be one instance of a + // common base. + for (auto *tinfo : it->second) { + // NB: Could use a second set here, rather than doing a linear search, but since + // having a large number of immediate pybind11-registered types seems fairly + // unlikely, that probably isn't worthwhile. + bool found = false; + for (auto *known : bases) { + if (known == tinfo) { found = true; break; } + } + if (!found) bases.push_back(tinfo); + } + } + else if (type->tp_bases) { + // It's some python type, so keep follow its bases classes to look for one or more + // registered types + if (i + 1 == check.size()) { + // When we're at the end, we can pop off the current element to avoid growing + // `check` when adding just one base (which is typical--i.e. when there is no + // multiple inheritance) + check.pop_back(); + i--; + } + for (handle parent : reinterpret_borrow(type->tp_bases)) + check.push_back((PyTypeObject *) parent.ptr()); + } + } +} + +/** + * Extracts vector of type_info pointers of pybind-registered roots of the given Python type. Will + * be just 1 pybind type for the Python type of a pybind-registered class, or for any Python-side + * derived class that uses single inheritance. Will contain as many types as required for a Python + * class that uses multiple inheritance to inherit (directly or indirectly) from multiple + * pybind-registered classes. Will be empty if neither the type nor any base classes are + * pybind-registered. + * + * The value is cached for the lifetime of the Python type. + */ +inline const std::vector &all_type_info(PyTypeObject *type) { + auto ins = all_type_info_get_cache(type); + if (ins.second) + // New cache entry: populate it + all_type_info_populate(type, ins.first->second); + + return ins.first->second; +} + +/** + * Gets a single pybind11 type info for a python type. Returns nullptr if neither the type nor any + * ancestors are pybind11-registered. Throws an exception if there are multiple bases--use + * `all_type_info` instead if you want to support multiple bases. + */ +PYBIND11_NOINLINE inline detail::type_info* get_type_info(PyTypeObject *type) { + auto &bases = all_type_info(type); + if (bases.size() == 0) + return nullptr; + if (bases.size() > 1) + pybind11_fail("pybind11::detail::get_type_info: type has multiple pybind11-registered bases"); + return bases.front(); +} + +inline detail::type_info *get_local_type_info(const std::type_index &tp) { + auto &locals = registered_local_types_cpp(); + auto it = locals.find(tp); + if (it != locals.end()) + return it->second; + return nullptr; +} + +inline detail::type_info *get_global_type_info(const std::type_index &tp) { + auto &types = get_internals().registered_types_cpp; + auto it = types.find(tp); + if (it != types.end()) + return it->second; + return nullptr; +} + +/// Return the type info for a given C++ type; on lookup failure can either throw or return nullptr. +PYBIND11_NOINLINE inline detail::type_info *get_type_info(const std::type_index &tp, + bool throw_if_missing = false) { + if (auto ltype = get_local_type_info(tp)) + return ltype; + if (auto gtype = get_global_type_info(tp)) + return gtype; + + if (throw_if_missing) { + std::string tname = tp.name(); + detail::clean_type_id(tname); + pybind11_fail("pybind11::detail::get_type_info: unable to find type info for \"" + tname + "\""); + } + return nullptr; +} + +PYBIND11_NOINLINE inline handle get_type_handle(const std::type_info &tp, bool throw_if_missing) { + detail::type_info *type_info = get_type_info(tp, throw_if_missing); + return handle(type_info ? ((PyObject *) type_info->type) : nullptr); +} + +struct value_and_holder { + instance *inst = nullptr; + size_t index = 0u; + const detail::type_info *type = nullptr; + void **vh = nullptr; + + // Main constructor for a found value/holder: + value_and_holder(instance *i, const detail::type_info *type, size_t vpos, size_t index) : + inst{i}, index{index}, type{type}, + vh{inst->simple_layout ? inst->simple_value_holder : &inst->nonsimple.values_and_holders[vpos]} + {} + + // Default constructor (used to signal a value-and-holder not found by get_value_and_holder()) + value_and_holder() {} + + // Used for past-the-end iterator + value_and_holder(size_t index) : index{index} {} + + template V *&value_ptr() const { + return reinterpret_cast(vh[0]); + } + // True if this `value_and_holder` has a non-null value pointer + explicit operator bool() const { return value_ptr(); } + + template H &holder() const { + return reinterpret_cast(vh[1]); + } + bool holder_constructed() const { + return inst->simple_layout + ? inst->simple_holder_constructed + : inst->nonsimple.status[index] & instance::status_holder_constructed; + } + void set_holder_constructed(bool v = true) { + if (inst->simple_layout) + inst->simple_holder_constructed = v; + else if (v) + inst->nonsimple.status[index] |= instance::status_holder_constructed; + else + inst->nonsimple.status[index] &= (uint8_t) ~instance::status_holder_constructed; + } + bool instance_registered() const { + return inst->simple_layout + ? inst->simple_instance_registered + : inst->nonsimple.status[index] & instance::status_instance_registered; + } + void set_instance_registered(bool v = true) { + if (inst->simple_layout) + inst->simple_instance_registered = v; + else if (v) + inst->nonsimple.status[index] |= instance::status_instance_registered; + else + inst->nonsimple.status[index] &= (uint8_t) ~instance::status_instance_registered; + } +}; + +// Container for accessing and iterating over an instance's values/holders +struct values_and_holders { +private: + instance *inst; + using type_vec = std::vector; + const type_vec &tinfo; + +public: + values_and_holders(instance *inst) : inst{inst}, tinfo(all_type_info(Py_TYPE(inst))) {} + + struct iterator { + private: + instance *inst = nullptr; + const type_vec *types = nullptr; + value_and_holder curr; + friend struct values_and_holders; + iterator(instance *inst, const type_vec *tinfo) + : inst{inst}, types{tinfo}, + curr(inst /* instance */, + types->empty() ? nullptr : (*types)[0] /* type info */, + 0, /* vpos: (non-simple types only): the first vptr comes first */ + 0 /* index */) + {} + // Past-the-end iterator: + iterator(size_t end) : curr(end) {} + public: + bool operator==(const iterator &other) { return curr.index == other.curr.index; } + bool operator!=(const iterator &other) { return curr.index != other.curr.index; } + iterator &operator++() { + if (!inst->simple_layout) + curr.vh += 1 + (*types)[curr.index]->holder_size_in_ptrs; + ++curr.index; + curr.type = curr.index < types->size() ? (*types)[curr.index] : nullptr; + return *this; + } + value_and_holder &operator*() { return curr; } + value_and_holder *operator->() { return &curr; } + }; + + iterator begin() { return iterator(inst, &tinfo); } + iterator end() { return iterator(tinfo.size()); } + + iterator find(const type_info *find_type) { + auto it = begin(), endit = end(); + while (it != endit && it->type != find_type) ++it; + return it; + } + + size_t size() { return tinfo.size(); } +}; + +/** + * Extracts C++ value and holder pointer references from an instance (which may contain multiple + * values/holders for python-side multiple inheritance) that match the given type. Throws an error + * if the given type (or ValueType, if omitted) is not a pybind11 base of the given instance. If + * `find_type` is omitted (or explicitly specified as nullptr) the first value/holder are returned, + * regardless of type (and the resulting .type will be nullptr). + * + * The returned object should be short-lived: in particular, it must not outlive the called-upon + * instance. + */ +PYBIND11_NOINLINE inline value_and_holder instance::get_value_and_holder(const type_info *find_type /*= nullptr default in common.h*/, bool throw_if_missing /*= true in common.h*/) { + // Optimize common case: + if (!find_type || Py_TYPE(this) == find_type->type) + return value_and_holder(this, find_type, 0, 0); + + detail::values_and_holders vhs(this); + auto it = vhs.find(find_type); + if (it != vhs.end()) + return *it; + + if (!throw_if_missing) + return value_and_holder(); + +#if defined(NDEBUG) + pybind11_fail("pybind11::detail::instance::get_value_and_holder: " + "type is not a pybind11 base of the given instance " + "(compile in debug mode for type details)"); +#else + pybind11_fail("pybind11::detail::instance::get_value_and_holder: `" + + std::string(find_type->type->tp_name) + "' is not a pybind11 base of the given `" + + std::string(Py_TYPE(this)->tp_name) + "' instance"); +#endif +} + +PYBIND11_NOINLINE inline void instance::allocate_layout() { + auto &tinfo = all_type_info(Py_TYPE(this)); + + const size_t n_types = tinfo.size(); + + if (n_types == 0) + pybind11_fail("instance allocation failed: new instance has no pybind11-registered base types"); + + simple_layout = + n_types == 1 && tinfo.front()->holder_size_in_ptrs <= instance_simple_holder_in_ptrs(); + + // Simple path: no python-side multiple inheritance, and a small-enough holder + if (simple_layout) { + simple_value_holder[0] = nullptr; + simple_holder_constructed = false; + simple_instance_registered = false; + } + else { // multiple base types or a too-large holder + // Allocate space to hold: [v1*][h1][v2*][h2]...[bb...] where [vN*] is a value pointer, + // [hN] is the (uninitialized) holder instance for value N, and [bb...] is a set of bool + // values that tracks whether each associated holder has been initialized. Each [block] is + // padded, if necessary, to an integer multiple of sizeof(void *). + size_t space = 0; + for (auto t : tinfo) { + space += 1; // value pointer + space += t->holder_size_in_ptrs; // holder instance + } + size_t flags_at = space; + space += size_in_ptrs(n_types); // status bytes (holder_constructed and instance_registered) + + // Allocate space for flags, values, and holders, and initialize it to 0 (flags and values, + // in particular, need to be 0). Use Python's memory allocation functions: in Python 3.6 + // they default to using pymalloc, which is designed to be efficient for small allocations + // like the one we're doing here; in earlier versions (and for larger allocations) they are + // just wrappers around malloc. +#if PY_VERSION_HEX >= 0x03050000 + nonsimple.values_and_holders = (void **) PyMem_Calloc(space, sizeof(void *)); + if (!nonsimple.values_and_holders) throw std::bad_alloc(); +#else + nonsimple.values_and_holders = (void **) PyMem_New(void *, space); + if (!nonsimple.values_and_holders) throw std::bad_alloc(); + std::memset(nonsimple.values_and_holders, 0, space * sizeof(void *)); +#endif + nonsimple.status = reinterpret_cast(&nonsimple.values_and_holders[flags_at]); + } + owned = true; +} + +PYBIND11_NOINLINE inline void instance::deallocate_layout() { + if (!simple_layout) + PyMem_Free(nonsimple.values_and_holders); +} + +PYBIND11_NOINLINE inline bool isinstance_generic(handle obj, const std::type_info &tp) { + handle type = detail::get_type_handle(tp, false); + if (!type) + return false; + return isinstance(obj, type); +} + +PYBIND11_NOINLINE inline std::string error_string() { + if (!PyErr_Occurred()) { + PyErr_SetString(PyExc_RuntimeError, "Unknown internal error occurred"); + return "Unknown internal error occurred"; + } + + error_scope scope; // Preserve error state + + std::string errorString; + if (scope.type) { + errorString += handle(scope.type).attr("__name__").cast(); + errorString += ": "; + } + if (scope.value) + errorString += (std::string) str(scope.value); + + PyErr_NormalizeException(&scope.type, &scope.value, &scope.trace); + +#if PY_MAJOR_VERSION >= 3 + if (scope.trace != nullptr) + PyException_SetTraceback(scope.value, scope.trace); +#endif + +#if !defined(PYPY_VERSION) + if (scope.trace) { + PyTracebackObject *trace = (PyTracebackObject *) scope.trace; + + /* Get the deepest trace possible */ + while (trace->tb_next) + trace = trace->tb_next; + + PyFrameObject *frame = trace->tb_frame; + errorString += "\n\nAt:\n"; + while (frame) { + int lineno = PyFrame_GetLineNumber(frame); + errorString += + " " + handle(frame->f_code->co_filename).cast() + + "(" + std::to_string(lineno) + "): " + + handle(frame->f_code->co_name).cast() + "\n"; + frame = frame->f_back; + } + } +#endif + + return errorString; +} + +PYBIND11_NOINLINE inline handle get_object_handle(const void *ptr, const detail::type_info *type ) { + auto &instances = get_internals().registered_instances; + auto range = instances.equal_range(ptr); + for (auto it = range.first; it != range.second; ++it) { + for (auto vh : values_and_holders(it->second)) { + if (vh.type == type) + return handle((PyObject *) it->second); + } + } + return handle(); +} + +inline PyThreadState *get_thread_state_unchecked() { +#if defined(PYPY_VERSION) + return PyThreadState_GET(); +#elif PY_VERSION_HEX < 0x03000000 + return _PyThreadState_Current; +#elif PY_VERSION_HEX < 0x03050000 + return (PyThreadState*) _Py_atomic_load_relaxed(&_PyThreadState_Current); +#elif PY_VERSION_HEX < 0x03050200 + return (PyThreadState*) _PyThreadState_Current.value; +#else + return _PyThreadState_UncheckedGet(); +#endif +} + +// Forward declarations +inline void keep_alive_impl(handle nurse, handle patient); +inline PyObject *make_new_instance(PyTypeObject *type); + +class type_caster_generic { +public: + PYBIND11_NOINLINE type_caster_generic(const std::type_info &type_info) + : typeinfo(get_type_info(type_info)), cpptype(&type_info) { } + + type_caster_generic(const type_info *typeinfo) + : typeinfo(typeinfo), cpptype(typeinfo ? typeinfo->cpptype : nullptr) { } + + bool load(handle src, bool convert) { + return load_impl(src, convert); + } + + PYBIND11_NOINLINE static handle cast(const void *_src, return_value_policy policy, handle parent, + const detail::type_info *tinfo, + void *(*copy_constructor)(const void *), + void *(*move_constructor)(const void *), + const void *existing_holder = nullptr) { + if (!tinfo) // no type info: error will be set already + return handle(); + + void *src = const_cast(_src); + if (src == nullptr) + return none().release(); + + auto it_instances = get_internals().registered_instances.equal_range(src); + for (auto it_i = it_instances.first; it_i != it_instances.second; ++it_i) { + for (auto instance_type : detail::all_type_info(Py_TYPE(it_i->second))) { + if (instance_type && same_type(*instance_type->cpptype, *tinfo->cpptype)) + return handle((PyObject *) it_i->second).inc_ref(); + } + } + + auto inst = reinterpret_steal(make_new_instance(tinfo->type)); + auto wrapper = reinterpret_cast(inst.ptr()); + wrapper->owned = false; + void *&valueptr = values_and_holders(wrapper).begin()->value_ptr(); + + switch (policy) { + case return_value_policy::automatic: + case return_value_policy::take_ownership: + valueptr = src; + wrapper->owned = true; + break; + + case return_value_policy::automatic_reference: + case return_value_policy::reference: + valueptr = src; + wrapper->owned = false; + break; + + case return_value_policy::copy: + if (copy_constructor) + valueptr = copy_constructor(src); + else + throw cast_error("return_value_policy = copy, but the " + "object is non-copyable!"); + wrapper->owned = true; + break; + + case return_value_policy::move: + if (move_constructor) + valueptr = move_constructor(src); + else if (copy_constructor) + valueptr = copy_constructor(src); + else + throw cast_error("return_value_policy = move, but the " + "object is neither movable nor copyable!"); + wrapper->owned = true; + break; + + case return_value_policy::reference_internal: + valueptr = src; + wrapper->owned = false; + keep_alive_impl(inst, parent); + break; + + default: + throw cast_error("unhandled return_value_policy: should not happen!"); + } + + tinfo->init_instance(wrapper, existing_holder); + + return inst.release(); + } + + // Base methods for generic caster; there are overridden in copyable_holder_caster + void load_value(value_and_holder &&v_h) { + auto *&vptr = v_h.value_ptr(); + // Lazy allocation for unallocated values: + if (vptr == nullptr) { + auto *type = v_h.type ? v_h.type : typeinfo; + if (type->operator_new) { + vptr = type->operator_new(type->type_size); + } else { + #if defined(PYBIND11_CPP17) + if (type->type_align > __STDCPP_DEFAULT_NEW_ALIGNMENT__) + vptr = ::operator new(type->type_size, + (std::align_val_t) type->type_align); + else + #endif + vptr = ::operator new(type->type_size); + } + } + value = vptr; + } + bool try_implicit_casts(handle src, bool convert) { + for (auto &cast : typeinfo->implicit_casts) { + type_caster_generic sub_caster(*cast.first); + if (sub_caster.load(src, convert)) { + value = cast.second(sub_caster.value); + return true; + } + } + return false; + } + bool try_direct_conversions(handle src) { + for (auto &converter : *typeinfo->direct_conversions) { + if (converter(src.ptr(), value)) + return true; + } + return false; + } + void check_holder_compat() {} + + PYBIND11_NOINLINE static void *local_load(PyObject *src, const type_info *ti) { + auto caster = type_caster_generic(ti); + if (caster.load(src, false)) + return caster.value; + return nullptr; + } + + /// Try to load with foreign typeinfo, if available. Used when there is no + /// native typeinfo, or when the native one wasn't able to produce a value. + PYBIND11_NOINLINE bool try_load_foreign_module_local(handle src) { + constexpr auto *local_key = PYBIND11_MODULE_LOCAL_ID; + const auto pytype = src.get_type(); + if (!hasattr(pytype, local_key)) + return false; + + type_info *foreign_typeinfo = reinterpret_borrow(getattr(pytype, local_key)); + // Only consider this foreign loader if actually foreign and is a loader of the correct cpp type + if (foreign_typeinfo->module_local_load == &local_load + || (cpptype && !same_type(*cpptype, *foreign_typeinfo->cpptype))) + return false; + + if (auto result = foreign_typeinfo->module_local_load(src.ptr(), foreign_typeinfo)) { + value = result; + return true; + } + return false; + } + + // Implementation of `load`; this takes the type of `this` so that it can dispatch the relevant + // bits of code between here and copyable_holder_caster where the two classes need different + // logic (without having to resort to virtual inheritance). + template + PYBIND11_NOINLINE bool load_impl(handle src, bool convert) { + if (!src) return false; + if (!typeinfo) return try_load_foreign_module_local(src); + if (src.is_none()) { + // Defer accepting None to other overloads (if we aren't in convert mode): + if (!convert) return false; + value = nullptr; + return true; + } + + auto &this_ = static_cast(*this); + this_.check_holder_compat(); + + PyTypeObject *srctype = Py_TYPE(src.ptr()); + + // Case 1: If src is an exact type match for the target type then we can reinterpret_cast + // the instance's value pointer to the target type: + if (srctype == typeinfo->type) { + this_.load_value(reinterpret_cast(src.ptr())->get_value_and_holder()); + return true; + } + // Case 2: We have a derived class + else if (PyType_IsSubtype(srctype, typeinfo->type)) { + auto &bases = all_type_info(srctype); + bool no_cpp_mi = typeinfo->simple_type; + + // Case 2a: the python type is a Python-inherited derived class that inherits from just + // one simple (no MI) pybind11 class, or is an exact match, so the C++ instance is of + // the right type and we can use reinterpret_cast. + // (This is essentially the same as case 2b, but because not using multiple inheritance + // is extremely common, we handle it specially to avoid the loop iterator and type + // pointer lookup overhead) + if (bases.size() == 1 && (no_cpp_mi || bases.front()->type == typeinfo->type)) { + this_.load_value(reinterpret_cast(src.ptr())->get_value_and_holder()); + return true; + } + // Case 2b: the python type inherits from multiple C++ bases. Check the bases to see if + // we can find an exact match (or, for a simple C++ type, an inherited match); if so, we + // can safely reinterpret_cast to the relevant pointer. + else if (bases.size() > 1) { + for (auto base : bases) { + if (no_cpp_mi ? PyType_IsSubtype(base->type, typeinfo->type) : base->type == typeinfo->type) { + this_.load_value(reinterpret_cast(src.ptr())->get_value_and_holder(base)); + return true; + } + } + } + + // Case 2c: C++ multiple inheritance is involved and we couldn't find an exact type match + // in the registered bases, above, so try implicit casting (needed for proper C++ casting + // when MI is involved). + if (this_.try_implicit_casts(src, convert)) + return true; + } + + // Perform an implicit conversion + if (convert) { + for (auto &converter : typeinfo->implicit_conversions) { + auto temp = reinterpret_steal(converter(src.ptr(), typeinfo->type)); + if (load_impl(temp, false)) { + loader_life_support::add_patient(temp); + return true; + } + } + if (this_.try_direct_conversions(src)) + return true; + } + + // Failed to match local typeinfo. Try again with global. + if (typeinfo->module_local) { + if (auto gtype = get_global_type_info(*typeinfo->cpptype)) { + typeinfo = gtype; + return load(src, false); + } + } + + // Global typeinfo has precedence over foreign module_local + return try_load_foreign_module_local(src); + } + + + // Called to do type lookup and wrap the pointer and type in a pair when a dynamic_cast + // isn't needed or can't be used. If the type is unknown, sets the error and returns a pair + // with .second = nullptr. (p.first = nullptr is not an error: it becomes None). + PYBIND11_NOINLINE static std::pair src_and_type( + const void *src, const std::type_info &cast_type, const std::type_info *rtti_type = nullptr) { + if (auto *tpi = get_type_info(cast_type)) + return {src, const_cast(tpi)}; + + // Not found, set error: + std::string tname = rtti_type ? rtti_type->name() : cast_type.name(); + detail::clean_type_id(tname); + std::string msg = "Unregistered type : " + tname; + PyErr_SetString(PyExc_TypeError, msg.c_str()); + return {nullptr, nullptr}; + } + + const type_info *typeinfo = nullptr; + const std::type_info *cpptype = nullptr; + void *value = nullptr; +}; + +/** + * Determine suitable casting operator for pointer-or-lvalue-casting type casters. The type caster + * needs to provide `operator T*()` and `operator T&()` operators. + * + * If the type supports moving the value away via an `operator T&&() &&` method, it should use + * `movable_cast_op_type` instead. + */ +template +using cast_op_type = + conditional_t>::value, + typename std::add_pointer>::type, + typename std::add_lvalue_reference>::type>; + +/** + * Determine suitable casting operator for a type caster with a movable value. Such a type caster + * needs to provide `operator T*()`, `operator T&()`, and `operator T&&() &&`. The latter will be + * called in appropriate contexts where the value can be moved rather than copied. + * + * These operator are automatically provided when using the PYBIND11_TYPE_CASTER macro. + */ +template +using movable_cast_op_type = + conditional_t::type>::value, + typename std::add_pointer>::type, + conditional_t::value, + typename std::add_rvalue_reference>::type, + typename std::add_lvalue_reference>::type>>; + +// std::is_copy_constructible isn't quite enough: it lets std::vector (and similar) through when +// T is non-copyable, but code containing such a copy constructor fails to actually compile. +template struct is_copy_constructible : std::is_copy_constructible {}; + +// Specialization for types that appear to be copy constructible but also look like stl containers +// (we specifically check for: has `value_type` and `reference` with `reference = value_type&`): if +// so, copy constructability depends on whether the value_type is copy constructible. +template struct is_copy_constructible, + std::is_same + >::value>> : is_copy_constructible {}; + +#if !defined(PYBIND11_CPP17) +// Likewise for std::pair before C++17 (which mandates that the copy constructor not exist when the +// two types aren't themselves copy constructible). +template struct is_copy_constructible> + : all_of, is_copy_constructible> {}; +#endif + +NAMESPACE_END(detail) + +// polymorphic_type_hook::get(src, tinfo) determines whether the object pointed +// to by `src` actually is an instance of some class derived from `itype`. +// If so, it sets `tinfo` to point to the std::type_info representing that derived +// type, and returns a pointer to the start of the most-derived object of that type +// (in which `src` is a subobject; this will be the same address as `src` in most +// single inheritance cases). If not, or if `src` is nullptr, it simply returns `src` +// and leaves `tinfo` at its default value of nullptr. +// +// The default polymorphic_type_hook just returns src. A specialization for polymorphic +// types determines the runtime type of the passed object and adjusts the this-pointer +// appropriately via dynamic_cast. This is what enables a C++ Animal* to appear +// to Python as a Dog (if Dog inherits from Animal, Animal is polymorphic, Dog is +// registered with pybind11, and this Animal is in fact a Dog). +// +// You may specialize polymorphic_type_hook yourself for types that want to appear +// polymorphic to Python but do not use C++ RTTI. (This is a not uncommon pattern +// in performance-sensitive applications, used most notably in LLVM.) +template +struct polymorphic_type_hook +{ + static const void *get(const itype *src, const std::type_info*&) { return src; } +}; +template +struct polymorphic_type_hook::value>> +{ + static const void *get(const itype *src, const std::type_info*& type) { + type = src ? &typeid(*src) : nullptr; + return dynamic_cast(src); + } +}; + +NAMESPACE_BEGIN(detail) + +/// Generic type caster for objects stored on the heap +template class type_caster_base : public type_caster_generic { + using itype = intrinsic_t; + +public: + static constexpr auto name = _(); + + type_caster_base() : type_caster_base(typeid(type)) { } + explicit type_caster_base(const std::type_info &info) : type_caster_generic(info) { } + + static handle cast(const itype &src, return_value_policy policy, handle parent) { + if (policy == return_value_policy::automatic || policy == return_value_policy::automatic_reference) + policy = return_value_policy::copy; + return cast(&src, policy, parent); + } + + static handle cast(itype &&src, return_value_policy, handle parent) { + return cast(&src, return_value_policy::move, parent); + } + + // Returns a (pointer, type_info) pair taking care of necessary type lookup for a + // polymorphic type (using RTTI by default, but can be overridden by specializing + // polymorphic_type_hook). If the instance isn't derived, returns the base version. + static std::pair src_and_type(const itype *src) { + auto &cast_type = typeid(itype); + const std::type_info *instance_type = nullptr; + const void *vsrc = polymorphic_type_hook::get(src, instance_type); + if (instance_type && !same_type(cast_type, *instance_type)) { + // This is a base pointer to a derived type. If the derived type is registered + // with pybind11, we want to make the full derived object available. + // In the typical case where itype is polymorphic, we get the correct + // derived pointer (which may be != base pointer) by a dynamic_cast to + // most derived type. If itype is not polymorphic, we won't get here + // except via a user-provided specialization of polymorphic_type_hook, + // and the user has promised that no this-pointer adjustment is + // required in that case, so it's OK to use static_cast. + if (const auto *tpi = get_type_info(*instance_type)) + return {vsrc, tpi}; + } + // Otherwise we have either a nullptr, an `itype` pointer, or an unknown derived pointer, so + // don't do a cast + return type_caster_generic::src_and_type(src, cast_type, instance_type); + } + + static handle cast(const itype *src, return_value_policy policy, handle parent) { + auto st = src_and_type(src); + return type_caster_generic::cast( + st.first, policy, parent, st.second, + make_copy_constructor(src), make_move_constructor(src)); + } + + static handle cast_holder(const itype *src, const void *holder) { + auto st = src_and_type(src); + return type_caster_generic::cast( + st.first, return_value_policy::take_ownership, {}, st.second, + nullptr, nullptr, holder); + } + + template using cast_op_type = detail::cast_op_type; + + operator itype*() { return (type *) value; } + operator itype&() { if (!value) throw reference_cast_error(); return *((itype *) value); } + +protected: + using Constructor = void *(*)(const void *); + + /* Only enabled when the types are {copy,move}-constructible *and* when the type + does not have a private operator new implementation. */ + template ::value>> + static auto make_copy_constructor(const T *x) -> decltype(new T(*x), Constructor{}) { + return [](const void *arg) -> void * { + return new T(*reinterpret_cast(arg)); + }; + } + + template ::value>> + static auto make_move_constructor(const T *x) -> decltype(new T(std::move(*const_cast(x))), Constructor{}) { + return [](const void *arg) -> void * { + return new T(std::move(*const_cast(reinterpret_cast(arg)))); + }; + } + + static Constructor make_copy_constructor(...) { return nullptr; } + static Constructor make_move_constructor(...) { return nullptr; } +}; + +template class type_caster : public type_caster_base { }; +template using make_caster = type_caster>; + +// Shortcut for calling a caster's `cast_op_type` cast operator for casting a type_caster to a T +template typename make_caster::template cast_op_type cast_op(make_caster &caster) { + return caster.operator typename make_caster::template cast_op_type(); +} +template typename make_caster::template cast_op_type::type> +cast_op(make_caster &&caster) { + return std::move(caster).operator + typename make_caster::template cast_op_type::type>(); +} + +template class type_caster> { +private: + using caster_t = make_caster; + caster_t subcaster; + using subcaster_cast_op_type = typename caster_t::template cast_op_type; + static_assert(std::is_same::type &, subcaster_cast_op_type>::value, + "std::reference_wrapper caster requires T to have a caster with an `T &` operator"); +public: + bool load(handle src, bool convert) { return subcaster.load(src, convert); } + static constexpr auto name = caster_t::name; + static handle cast(const std::reference_wrapper &src, return_value_policy policy, handle parent) { + // It is definitely wrong to take ownership of this pointer, so mask that rvp + if (policy == return_value_policy::take_ownership || policy == return_value_policy::automatic) + policy = return_value_policy::automatic_reference; + return caster_t::cast(&src.get(), policy, parent); + } + template using cast_op_type = std::reference_wrapper; + operator std::reference_wrapper() { return subcaster.operator subcaster_cast_op_type&(); } +}; + +#define PYBIND11_TYPE_CASTER(type, py_name) \ + protected: \ + type value; \ + public: \ + static constexpr auto name = py_name; \ + template >::value, int> = 0> \ + static handle cast(T_ *src, return_value_policy policy, handle parent) { \ + if (!src) return none().release(); \ + if (policy == return_value_policy::take_ownership) { \ + auto h = cast(std::move(*src), policy, parent); delete src; return h; \ + } else { \ + return cast(*src, policy, parent); \ + } \ + } \ + operator type*() { return &value; } \ + operator type&() { return value; } \ + operator type&&() && { return std::move(value); } \ + template using cast_op_type = pybind11::detail::movable_cast_op_type + + +template using is_std_char_type = any_of< + std::is_same, /* std::string */ + std::is_same, /* std::u16string */ + std::is_same, /* std::u32string */ + std::is_same /* std::wstring */ +>; + +template +struct type_caster::value && !is_std_char_type::value>> { + using _py_type_0 = conditional_t; + using _py_type_1 = conditional_t::value, _py_type_0, typename std::make_unsigned<_py_type_0>::type>; + using py_type = conditional_t::value, double, _py_type_1>; +public: + + bool load(handle src, bool convert) { + py_type py_value; + + if (!src) + return false; + + if (std::is_floating_point::value) { + if (convert || PyFloat_Check(src.ptr())) + py_value = (py_type) PyFloat_AsDouble(src.ptr()); + else + return false; + } else if (PyFloat_Check(src.ptr())) { + return false; + } else if (std::is_unsigned::value) { + py_value = as_unsigned(src.ptr()); + } else { // signed integer: + py_value = sizeof(T) <= sizeof(long) + ? (py_type) PyLong_AsLong(src.ptr()) + : (py_type) PYBIND11_LONG_AS_LONGLONG(src.ptr()); + } + + bool py_err = py_value == (py_type) -1 && PyErr_Occurred(); + if (py_err || (std::is_integral::value && sizeof(py_type) != sizeof(T) && + (py_value < (py_type) std::numeric_limits::min() || + py_value > (py_type) std::numeric_limits::max()))) { + bool type_error = py_err && PyErr_ExceptionMatches( +#if PY_VERSION_HEX < 0x03000000 && !defined(PYPY_VERSION) + PyExc_SystemError +#else + PyExc_TypeError +#endif + ); + PyErr_Clear(); + if (type_error && convert && PyNumber_Check(src.ptr())) { + auto tmp = reinterpret_steal(std::is_floating_point::value + ? PyNumber_Float(src.ptr()) + : PyNumber_Long(src.ptr())); + PyErr_Clear(); + return load(tmp, false); + } + return false; + } + + value = (T) py_value; + return true; + } + + template + static typename std::enable_if::value, handle>::type + cast(U src, return_value_policy /* policy */, handle /* parent */) { + return PyFloat_FromDouble((double) src); + } + + template + static typename std::enable_if::value && std::is_signed::value && (sizeof(U) <= sizeof(long)), handle>::type + cast(U src, return_value_policy /* policy */, handle /* parent */) { + return PYBIND11_LONG_FROM_SIGNED((long) src); + } + + template + static typename std::enable_if::value && std::is_unsigned::value && (sizeof(U) <= sizeof(unsigned long)), handle>::type + cast(U src, return_value_policy /* policy */, handle /* parent */) { + return PYBIND11_LONG_FROM_UNSIGNED((unsigned long) src); + } + + template + static typename std::enable_if::value && std::is_signed::value && (sizeof(U) > sizeof(long)), handle>::type + cast(U src, return_value_policy /* policy */, handle /* parent */) { + return PyLong_FromLongLong((long long) src); + } + + template + static typename std::enable_if::value && std::is_unsigned::value && (sizeof(U) > sizeof(unsigned long)), handle>::type + cast(U src, return_value_policy /* policy */, handle /* parent */) { + return PyLong_FromUnsignedLongLong((unsigned long long) src); + } + + PYBIND11_TYPE_CASTER(T, _::value>("int", "float")); +}; + +template struct void_caster { +public: + bool load(handle src, bool) { + if (src && src.is_none()) + return true; + return false; + } + static handle cast(T, return_value_policy /* policy */, handle /* parent */) { + return none().inc_ref(); + } + PYBIND11_TYPE_CASTER(T, _("None")); +}; + +template <> class type_caster : public void_caster {}; + +template <> class type_caster : public type_caster { +public: + using type_caster::cast; + + bool load(handle h, bool) { + if (!h) { + return false; + } else if (h.is_none()) { + value = nullptr; + return true; + } + + /* Check if this is a capsule */ + if (isinstance(h)) { + value = reinterpret_borrow(h); + return true; + } + + /* Check if this is a C++ type */ + auto &bases = all_type_info((PyTypeObject *) h.get_type().ptr()); + if (bases.size() == 1) { // Only allowing loading from a single-value type + value = values_and_holders(reinterpret_cast(h.ptr())).begin()->value_ptr(); + return true; + } + + /* Fail */ + return false; + } + + static handle cast(const void *ptr, return_value_policy /* policy */, handle /* parent */) { + if (ptr) + return capsule(ptr).release(); + else + return none().inc_ref(); + } + + template using cast_op_type = void*&; + operator void *&() { return value; } + static constexpr auto name = _("capsule"); +private: + void *value = nullptr; +}; + +template <> class type_caster : public void_caster { }; + +template <> class type_caster { +public: + bool load(handle src, bool convert) { + if (!src) return false; + else if (src.ptr() == Py_True) { value = true; return true; } + else if (src.ptr() == Py_False) { value = false; return true; } + else if (convert || !strcmp("numpy.bool_", Py_TYPE(src.ptr())->tp_name)) { + // (allow non-implicit conversion for numpy booleans) + + Py_ssize_t res = -1; + if (src.is_none()) { + res = 0; // None is implicitly converted to False + } + #if defined(PYPY_VERSION) + // On PyPy, check that "__bool__" (or "__nonzero__" on Python 2.7) attr exists + else if (hasattr(src, PYBIND11_BOOL_ATTR)) { + res = PyObject_IsTrue(src.ptr()); + } + #else + // Alternate approach for CPython: this does the same as the above, but optimized + // using the CPython API so as to avoid an unneeded attribute lookup. + else if (auto tp_as_number = src.ptr()->ob_type->tp_as_number) { + if (PYBIND11_NB_BOOL(tp_as_number)) { + res = (*PYBIND11_NB_BOOL(tp_as_number))(src.ptr()); + } + } + #endif + if (res == 0 || res == 1) { + value = (bool) res; + return true; + } + } + return false; + } + static handle cast(bool src, return_value_policy /* policy */, handle /* parent */) { + return handle(src ? Py_True : Py_False).inc_ref(); + } + PYBIND11_TYPE_CASTER(bool, _("bool")); +}; + +// Helper class for UTF-{8,16,32} C++ stl strings: +template struct string_caster { + using CharT = typename StringType::value_type; + + // Simplify life by being able to assume standard char sizes (the standard only guarantees + // minimums, but Python requires exact sizes) + static_assert(!std::is_same::value || sizeof(CharT) == 1, "Unsupported char size != 1"); + static_assert(!std::is_same::value || sizeof(CharT) == 2, "Unsupported char16_t size != 2"); + static_assert(!std::is_same::value || sizeof(CharT) == 4, "Unsupported char32_t size != 4"); + // wchar_t can be either 16 bits (Windows) or 32 (everywhere else) + static_assert(!std::is_same::value || sizeof(CharT) == 2 || sizeof(CharT) == 4, + "Unsupported wchar_t size != 2/4"); + static constexpr size_t UTF_N = 8 * sizeof(CharT); + + bool load(handle src, bool) { +#if PY_MAJOR_VERSION < 3 + object temp; +#endif + handle load_src = src; + if (!src) { + return false; + } else if (!PyUnicode_Check(load_src.ptr())) { +#if PY_MAJOR_VERSION >= 3 + return load_bytes(load_src); +#else + if (sizeof(CharT) == 1) { + return load_bytes(load_src); + } + + // The below is a guaranteed failure in Python 3 when PyUnicode_Check returns false + if (!PYBIND11_BYTES_CHECK(load_src.ptr())) + return false; + + temp = reinterpret_steal(PyUnicode_FromObject(load_src.ptr())); + if (!temp) { PyErr_Clear(); return false; } + load_src = temp; +#endif + } + + object utfNbytes = reinterpret_steal(PyUnicode_AsEncodedString( + load_src.ptr(), UTF_N == 8 ? "utf-8" : UTF_N == 16 ? "utf-16" : "utf-32", nullptr)); + if (!utfNbytes) { PyErr_Clear(); return false; } + + const CharT *buffer = reinterpret_cast(PYBIND11_BYTES_AS_STRING(utfNbytes.ptr())); + size_t length = (size_t) PYBIND11_BYTES_SIZE(utfNbytes.ptr()) / sizeof(CharT); + if (UTF_N > 8) { buffer++; length--; } // Skip BOM for UTF-16/32 + value = StringType(buffer, length); + + // If we're loading a string_view we need to keep the encoded Python object alive: + if (IsView) + loader_life_support::add_patient(utfNbytes); + + return true; + } + + static handle cast(const StringType &src, return_value_policy /* policy */, handle /* parent */) { + const char *buffer = reinterpret_cast(src.data()); + ssize_t nbytes = ssize_t(src.size() * sizeof(CharT)); + handle s = decode_utfN(buffer, nbytes); + if (!s) throw error_already_set(); + return s; + } + + PYBIND11_TYPE_CASTER(StringType, _(PYBIND11_STRING_NAME)); + +private: + static handle decode_utfN(const char *buffer, ssize_t nbytes) { +#if !defined(PYPY_VERSION) + return + UTF_N == 8 ? PyUnicode_DecodeUTF8(buffer, nbytes, nullptr) : + UTF_N == 16 ? PyUnicode_DecodeUTF16(buffer, nbytes, nullptr, nullptr) : + PyUnicode_DecodeUTF32(buffer, nbytes, nullptr, nullptr); +#else + // PyPy seems to have multiple problems related to PyUnicode_UTF*: the UTF8 version + // sometimes segfaults for unknown reasons, while the UTF16 and 32 versions require a + // non-const char * arguments, which is also a nuisance, so bypass the whole thing by just + // passing the encoding as a string value, which works properly: + return PyUnicode_Decode(buffer, nbytes, UTF_N == 8 ? "utf-8" : UTF_N == 16 ? "utf-16" : "utf-32", nullptr); +#endif + } + + // When loading into a std::string or char*, accept a bytes object as-is (i.e. + // without any encoding/decoding attempt). For other C++ char sizes this is a no-op. + // which supports loading a unicode from a str, doesn't take this path. + template + bool load_bytes(enable_if_t src) { + if (PYBIND11_BYTES_CHECK(src.ptr())) { + // We were passed a Python 3 raw bytes; accept it into a std::string or char* + // without any encoding attempt. + const char *bytes = PYBIND11_BYTES_AS_STRING(src.ptr()); + if (bytes) { + value = StringType(bytes, (size_t) PYBIND11_BYTES_SIZE(src.ptr())); + return true; + } + } + + return false; + } + + template + bool load_bytes(enable_if_t) { return false; } +}; + +template +struct type_caster, enable_if_t::value>> + : string_caster> {}; + +#ifdef PYBIND11_HAS_STRING_VIEW +template +struct type_caster, enable_if_t::value>> + : string_caster, true> {}; +#endif + +// Type caster for C-style strings. We basically use a std::string type caster, but also add the +// ability to use None as a nullptr char* (which the string caster doesn't allow). +template struct type_caster::value>> { + using StringType = std::basic_string; + using StringCaster = type_caster; + StringCaster str_caster; + bool none = false; + CharT one_char = 0; +public: + bool load(handle src, bool convert) { + if (!src) return false; + if (src.is_none()) { + // Defer accepting None to other overloads (if we aren't in convert mode): + if (!convert) return false; + none = true; + return true; + } + return str_caster.load(src, convert); + } + + static handle cast(const CharT *src, return_value_policy policy, handle parent) { + if (src == nullptr) return pybind11::none().inc_ref(); + return StringCaster::cast(StringType(src), policy, parent); + } + + static handle cast(CharT src, return_value_policy policy, handle parent) { + if (std::is_same::value) { + handle s = PyUnicode_DecodeLatin1((const char *) &src, 1, nullptr); + if (!s) throw error_already_set(); + return s; + } + return StringCaster::cast(StringType(1, src), policy, parent); + } + + operator CharT*() { return none ? nullptr : const_cast(static_cast(str_caster).c_str()); } + operator CharT&() { + if (none) + throw value_error("Cannot convert None to a character"); + + auto &value = static_cast(str_caster); + size_t str_len = value.size(); + if (str_len == 0) + throw value_error("Cannot convert empty string to a character"); + + // If we're in UTF-8 mode, we have two possible failures: one for a unicode character that + // is too high, and one for multiple unicode characters (caught later), so we need to figure + // out how long the first encoded character is in bytes to distinguish between these two + // errors. We also allow want to allow unicode characters U+0080 through U+00FF, as those + // can fit into a single char value. + if (StringCaster::UTF_N == 8 && str_len > 1 && str_len <= 4) { + unsigned char v0 = static_cast(value[0]); + size_t char0_bytes = !(v0 & 0x80) ? 1 : // low bits only: 0-127 + (v0 & 0xE0) == 0xC0 ? 2 : // 0b110xxxxx - start of 2-byte sequence + (v0 & 0xF0) == 0xE0 ? 3 : // 0b1110xxxx - start of 3-byte sequence + 4; // 0b11110xxx - start of 4-byte sequence + + if (char0_bytes == str_len) { + // If we have a 128-255 value, we can decode it into a single char: + if (char0_bytes == 2 && (v0 & 0xFC) == 0xC0) { // 0x110000xx 0x10xxxxxx + one_char = static_cast(((v0 & 3) << 6) + (static_cast(value[1]) & 0x3F)); + return one_char; + } + // Otherwise we have a single character, but it's > U+00FF + throw value_error("Character code point not in range(0x100)"); + } + } + + // UTF-16 is much easier: we can only have a surrogate pair for values above U+FFFF, thus a + // surrogate pair with total length 2 instantly indicates a range error (but not a "your + // string was too long" error). + else if (StringCaster::UTF_N == 16 && str_len == 2) { + one_char = static_cast(value[0]); + if (one_char >= 0xD800 && one_char < 0xE000) + throw value_error("Character code point not in range(0x10000)"); + } + + if (str_len != 1) + throw value_error("Expected a character, but multi-character string found"); + + one_char = value[0]; + return one_char; + } + + static constexpr auto name = _(PYBIND11_STRING_NAME); + template using cast_op_type = pybind11::detail::cast_op_type<_T>; +}; + +// Base implementation for std::tuple and std::pair +template class Tuple, typename... Ts> class tuple_caster { + using type = Tuple; + static constexpr auto size = sizeof...(Ts); + using indices = make_index_sequence; +public: + + bool load(handle src, bool convert) { + if (!isinstance(src)) + return false; + const auto seq = reinterpret_borrow(src); + if (seq.size() != size) + return false; + return load_impl(seq, convert, indices{}); + } + + template + static handle cast(T &&src, return_value_policy policy, handle parent) { + return cast_impl(std::forward(src), policy, parent, indices{}); + } + + static constexpr auto name = _("Tuple[") + concat(make_caster::name...) + _("]"); + + template using cast_op_type = type; + + operator type() & { return implicit_cast(indices{}); } + operator type() && { return std::move(*this).implicit_cast(indices{}); } + +protected: + template + type implicit_cast(index_sequence) & { return type(cast_op(std::get(subcasters))...); } + template + type implicit_cast(index_sequence) && { return type(cast_op(std::move(std::get(subcasters)))...); } + + static constexpr bool load_impl(const sequence &, bool, index_sequence<>) { return true; } + + template + bool load_impl(const sequence &seq, bool convert, index_sequence) { + for (bool r : {std::get(subcasters).load(seq[Is], convert)...}) + if (!r) + return false; + return true; + } + + /* Implementation: Convert a C++ tuple into a Python tuple */ + template + static handle cast_impl(T &&src, return_value_policy policy, handle parent, index_sequence) { + std::array entries{{ + reinterpret_steal(make_caster::cast(std::get(std::forward(src)), policy, parent))... + }}; + for (const auto &entry: entries) + if (!entry) + return handle(); + tuple result(size); + int counter = 0; + for (auto & entry: entries) + PyTuple_SET_ITEM(result.ptr(), counter++, entry.release().ptr()); + return result.release(); + } + + Tuple...> subcasters; +}; + +template class type_caster> + : public tuple_caster {}; + +template class type_caster> + : public tuple_caster {}; + +/// Helper class which abstracts away certain actions. Users can provide specializations for +/// custom holders, but it's only necessary if the type has a non-standard interface. +template +struct holder_helper { + static auto get(const T &p) -> decltype(p.get()) { return p.get(); } +}; + +/// Type caster for holder types like std::shared_ptr, etc. +template +struct copyable_holder_caster : public type_caster_base { +public: + using base = type_caster_base; + static_assert(std::is_base_of>::value, + "Holder classes are only supported for custom types"); + using base::base; + using base::cast; + using base::typeinfo; + using base::value; + + bool load(handle src, bool convert) { + return base::template load_impl>(src, convert); + } + + explicit operator type*() { return this->value; } + explicit operator type&() { return *(this->value); } + explicit operator holder_type*() { return std::addressof(holder); } + + // Workaround for Intel compiler bug + // see pybind11 issue 94 + #if defined(__ICC) || defined(__INTEL_COMPILER) + operator holder_type&() { return holder; } + #else + explicit operator holder_type&() { return holder; } + #endif + + static handle cast(const holder_type &src, return_value_policy, handle) { + const auto *ptr = holder_helper::get(src); + return type_caster_base::cast_holder(ptr, &src); + } + +protected: + friend class type_caster_generic; + void check_holder_compat() { + if (typeinfo->default_holder) + throw cast_error("Unable to load a custom holder type from a default-holder instance"); + } + + bool load_value(value_and_holder &&v_h) { + if (v_h.holder_constructed()) { + value = v_h.value_ptr(); + holder = v_h.template holder(); + return true; + } else { + throw cast_error("Unable to cast from non-held to held instance (T& to Holder) " +#if defined(NDEBUG) + "(compile in debug mode for type information)"); +#else + "of type '" + type_id() + "''"); +#endif + } + } + + template ::value, int> = 0> + bool try_implicit_casts(handle, bool) { return false; } + + template ::value, int> = 0> + bool try_implicit_casts(handle src, bool convert) { + for (auto &cast : typeinfo->implicit_casts) { + copyable_holder_caster sub_caster(*cast.first); + if (sub_caster.load(src, convert)) { + value = cast.second(sub_caster.value); + holder = holder_type(sub_caster.holder, (type *) value); + return true; + } + } + return false; + } + + static bool try_direct_conversions(handle) { return false; } + + + holder_type holder; +}; + +/// Specialize for the common std::shared_ptr, so users don't need to +template +class type_caster> : public copyable_holder_caster> { }; + +template +struct move_only_holder_caster { + static_assert(std::is_base_of, type_caster>::value, + "Holder classes are only supported for custom types"); + + static handle cast(holder_type &&src, return_value_policy, handle) { + auto *ptr = holder_helper::get(src); + return type_caster_base::cast_holder(ptr, std::addressof(src)); + } + static constexpr auto name = type_caster_base::name; +}; + +template +class type_caster> + : public move_only_holder_caster> { }; + +template +using type_caster_holder = conditional_t::value, + copyable_holder_caster, + move_only_holder_caster>; + +template struct always_construct_holder { static constexpr bool value = Value; }; + +/// Create a specialization for custom holder types (silently ignores std::shared_ptr) +#define PYBIND11_DECLARE_HOLDER_TYPE(type, holder_type, ...) \ + namespace pybind11 { namespace detail { \ + template \ + struct always_construct_holder : always_construct_holder { }; \ + template \ + class type_caster::value>> \ + : public type_caster_holder { }; \ + }} + +// PYBIND11_DECLARE_HOLDER_TYPE holder types: +template struct is_holder_type : + std::is_base_of, detail::type_caster> {}; +// Specialization for always-supported unique_ptr holders: +template struct is_holder_type> : + std::true_type {}; + +template struct handle_type_name { static constexpr auto name = _(); }; +template <> struct handle_type_name { static constexpr auto name = _(PYBIND11_BYTES_NAME); }; +template <> struct handle_type_name { static constexpr auto name = _("*args"); }; +template <> struct handle_type_name { static constexpr auto name = _("**kwargs"); }; + +template +struct pyobject_caster { + template ::value, int> = 0> + bool load(handle src, bool /* convert */) { value = src; return static_cast(value); } + + template ::value, int> = 0> + bool load(handle src, bool /* convert */) { + if (!isinstance(src)) + return false; + value = reinterpret_borrow(src); + return true; + } + + static handle cast(const handle &src, return_value_policy /* policy */, handle /* parent */) { + return src.inc_ref(); + } + PYBIND11_TYPE_CASTER(type, handle_type_name::name); +}; + +template +class type_caster::value>> : public pyobject_caster { }; + +// Our conditions for enabling moving are quite restrictive: +// At compile time: +// - T needs to be a non-const, non-pointer, non-reference type +// - type_caster::operator T&() must exist +// - the type must be move constructible (obviously) +// At run-time: +// - if the type is non-copy-constructible, the object must be the sole owner of the type (i.e. it +// must have ref_count() == 1)h +// If any of the above are not satisfied, we fall back to copying. +template using move_is_plain_type = satisfies_none_of; +template struct move_always : std::false_type {}; +template struct move_always, + negation>, + std::is_move_constructible, + std::is_same>().operator T&()), T&> +>::value>> : std::true_type {}; +template struct move_if_unreferenced : std::false_type {}; +template struct move_if_unreferenced, + negation>, + std::is_move_constructible, + std::is_same>().operator T&()), T&> +>::value>> : std::true_type {}; +template using move_never = none_of, move_if_unreferenced>; + +// Detect whether returning a `type` from a cast on type's type_caster is going to result in a +// reference or pointer to a local variable of the type_caster. Basically, only +// non-reference/pointer `type`s and reference/pointers from a type_caster_generic are safe; +// everything else returns a reference/pointer to a local variable. +template using cast_is_temporary_value_reference = bool_constant< + (std::is_reference::value || std::is_pointer::value) && + !std::is_base_of>::value && + !std::is_same, void>::value +>; + +// When a value returned from a C++ function is being cast back to Python, we almost always want to +// force `policy = move`, regardless of the return value policy the function/method was declared +// with. +template struct return_value_policy_override { + static return_value_policy policy(return_value_policy p) { return p; } +}; + +template struct return_value_policy_override>::value, void>> { + static return_value_policy policy(return_value_policy p) { + return !std::is_lvalue_reference::value && + !std::is_pointer::value + ? return_value_policy::move : p; + } +}; + +// Basic python -> C++ casting; throws if casting fails +template type_caster &load_type(type_caster &conv, const handle &handle) { + if (!conv.load(handle, true)) { +#if defined(NDEBUG) + throw cast_error("Unable to cast Python instance to C++ type (compile in debug mode for details)"); +#else + throw cast_error("Unable to cast Python instance of type " + + (std::string) str(handle.get_type()) + " to C++ type '" + type_id() + "'"); +#endif + } + return conv; +} +// Wrapper around the above that also constructs and returns a type_caster +template make_caster load_type(const handle &handle) { + make_caster conv; + load_type(conv, handle); + return conv; +} + +NAMESPACE_END(detail) + +// pytype -> C++ type +template ::value, int> = 0> +T cast(const handle &handle) { + using namespace detail; + static_assert(!cast_is_temporary_value_reference::value, + "Unable to cast type to reference: value is local to type caster"); + return cast_op(load_type(handle)); +} + +// pytype -> pytype (calls converting constructor) +template ::value, int> = 0> +T cast(const handle &handle) { return T(reinterpret_borrow(handle)); } + +// C++ type -> py::object +template ::value, int> = 0> +object cast(const T &value, return_value_policy policy = return_value_policy::automatic_reference, + handle parent = handle()) { + if (policy == return_value_policy::automatic) + policy = std::is_pointer::value ? return_value_policy::take_ownership : return_value_policy::copy; + else if (policy == return_value_policy::automatic_reference) + policy = std::is_pointer::value ? return_value_policy::reference : return_value_policy::copy; + return reinterpret_steal(detail::make_caster::cast(value, policy, parent)); +} + +template T handle::cast() const { return pybind11::cast(*this); } +template <> inline void handle::cast() const { return; } + +template +detail::enable_if_t::value, T> move(object &&obj) { + if (obj.ref_count() > 1) +#if defined(NDEBUG) + throw cast_error("Unable to cast Python instance to C++ rvalue: instance has multiple references" + " (compile in debug mode for details)"); +#else + throw cast_error("Unable to move from Python " + (std::string) str(obj.get_type()) + + " instance to C++ " + type_id() + " instance: instance has multiple references"); +#endif + + // Move into a temporary and return that, because the reference may be a local value of `conv` + T ret = std::move(detail::load_type(obj).operator T&()); + return ret; +} + +// Calling cast() on an rvalue calls pybind::cast with the object rvalue, which does: +// - If we have to move (because T has no copy constructor), do it. This will fail if the moved +// object has multiple references, but trying to copy will fail to compile. +// - If both movable and copyable, check ref count: if 1, move; otherwise copy +// - Otherwise (not movable), copy. +template detail::enable_if_t::value, T> cast(object &&object) { + return move(std::move(object)); +} +template detail::enable_if_t::value, T> cast(object &&object) { + if (object.ref_count() > 1) + return cast(object); + else + return move(std::move(object)); +} +template detail::enable_if_t::value, T> cast(object &&object) { + return cast(object); +} + +template T object::cast() const & { return pybind11::cast(*this); } +template T object::cast() && { return pybind11::cast(std::move(*this)); } +template <> inline void object::cast() const & { return; } +template <> inline void object::cast() && { return; } + +NAMESPACE_BEGIN(detail) + +// Declared in pytypes.h: +template ::value, int>> +object object_or_cast(T &&o) { return pybind11::cast(std::forward(o)); } + +struct overload_unused {}; // Placeholder type for the unneeded (and dead code) static variable in the OVERLOAD_INT macro +template using overload_caster_t = conditional_t< + cast_is_temporary_value_reference::value, make_caster, overload_unused>; + +// Trampoline use: for reference/pointer types to value-converted values, we do a value cast, then +// store the result in the given variable. For other types, this is a no-op. +template enable_if_t::value, T> cast_ref(object &&o, make_caster &caster) { + return cast_op(load_type(caster, o)); +} +template enable_if_t::value, T> cast_ref(object &&, overload_unused &) { + pybind11_fail("Internal error: cast_ref fallback invoked"); } + +// Trampoline use: Having a pybind11::cast with an invalid reference type is going to static_assert, even +// though if it's in dead code, so we provide a "trampoline" to pybind11::cast that only does anything in +// cases where pybind11::cast is valid. +template enable_if_t::value, T> cast_safe(object &&o) { + return pybind11::cast(std::move(o)); } +template enable_if_t::value, T> cast_safe(object &&) { + pybind11_fail("Internal error: cast_safe fallback invoked"); } +template <> inline void cast_safe(object &&) {} + +NAMESPACE_END(detail) + +template +tuple make_tuple() { return tuple(0); } + +template tuple make_tuple(Args&&... args_) { + constexpr size_t size = sizeof...(Args); + std::array args { + { reinterpret_steal(detail::make_caster::cast( + std::forward(args_), policy, nullptr))... } + }; + for (size_t i = 0; i < args.size(); i++) { + if (!args[i]) { +#if defined(NDEBUG) + throw cast_error("make_tuple(): unable to convert arguments to Python object (compile in debug mode for details)"); +#else + std::array argtypes { {type_id()...} }; + throw cast_error("make_tuple(): unable to convert argument of type '" + + argtypes[i] + "' to Python object"); +#endif + } + } + tuple result(size); + int counter = 0; + for (auto &arg_value : args) + PyTuple_SET_ITEM(result.ptr(), counter++, arg_value.release().ptr()); + return result; +} + +/// \ingroup annotations +/// Annotation for arguments +struct arg { + /// Constructs an argument with the name of the argument; if null or omitted, this is a positional argument. + constexpr explicit arg(const char *name = nullptr) : name(name), flag_noconvert(false), flag_none(true) { } + /// Assign a value to this argument + template arg_v operator=(T &&value) const; + /// Indicate that the type should not be converted in the type caster + arg &noconvert(bool flag = true) { flag_noconvert = flag; return *this; } + /// Indicates that the argument should/shouldn't allow None (e.g. for nullable pointer args) + arg &none(bool flag = true) { flag_none = flag; return *this; } + + const char *name; ///< If non-null, this is a named kwargs argument + bool flag_noconvert : 1; ///< If set, do not allow conversion (requires a supporting type caster!) + bool flag_none : 1; ///< If set (the default), allow None to be passed to this argument +}; + +/// \ingroup annotations +/// Annotation for arguments with values +struct arg_v : arg { +private: + template + arg_v(arg &&base, T &&x, const char *descr = nullptr) + : arg(base), + value(reinterpret_steal( + detail::make_caster::cast(x, return_value_policy::automatic, {}) + )), + descr(descr) +#if !defined(NDEBUG) + , type(type_id()) +#endif + { } + +public: + /// Direct construction with name, default, and description + template + arg_v(const char *name, T &&x, const char *descr = nullptr) + : arg_v(arg(name), std::forward(x), descr) { } + + /// Called internally when invoking `py::arg("a") = value` + template + arg_v(const arg &base, T &&x, const char *descr = nullptr) + : arg_v(arg(base), std::forward(x), descr) { } + + /// Same as `arg::noconvert()`, but returns *this as arg_v&, not arg& + arg_v &noconvert(bool flag = true) { arg::noconvert(flag); return *this; } + + /// Same as `arg::nonone()`, but returns *this as arg_v&, not arg& + arg_v &none(bool flag = true) { arg::none(flag); return *this; } + + /// The default value + object value; + /// The (optional) description of the default value + const char *descr; +#if !defined(NDEBUG) + /// The C++ type name of the default value (only available when compiled in debug mode) + std::string type; +#endif +}; + +template +arg_v arg::operator=(T &&value) const { return {std::move(*this), std::forward(value)}; } + +/// Alias for backward compatibility -- to be removed in version 2.0 +template using arg_t = arg_v; + +inline namespace literals { +/** \rst + String literal version of `arg` + \endrst */ +constexpr arg operator"" _a(const char *name, size_t) { return arg(name); } +} + +NAMESPACE_BEGIN(detail) + +// forward declaration (definition in attr.h) +struct function_record; + +/// Internal data associated with a single function call +struct function_call { + function_call(const function_record &f, handle p); // Implementation in attr.h + + /// The function data: + const function_record &func; + + /// Arguments passed to the function: + std::vector args; + + /// The `convert` value the arguments should be loaded with + std::vector args_convert; + + /// Extra references for the optional `py::args` and/or `py::kwargs` arguments (which, if + /// present, are also in `args` but without a reference). + object args_ref, kwargs_ref; + + /// The parent, if any + handle parent; + + /// If this is a call to an initializer, this argument contains `self` + handle init_self; +}; + + +/// Helper class which loads arguments for C++ functions called from Python +template +class argument_loader { + using indices = make_index_sequence; + + template using argument_is_args = std::is_same, args>; + template using argument_is_kwargs = std::is_same, kwargs>; + // Get args/kwargs argument positions relative to the end of the argument list: + static constexpr auto args_pos = constexpr_first() - (int) sizeof...(Args), + kwargs_pos = constexpr_first() - (int) sizeof...(Args); + + static constexpr bool args_kwargs_are_last = kwargs_pos >= - 1 && args_pos >= kwargs_pos - 1; + + static_assert(args_kwargs_are_last, "py::args/py::kwargs are only permitted as the last argument(s) of a function"); + +public: + static constexpr bool has_kwargs = kwargs_pos < 0; + static constexpr bool has_args = args_pos < 0; + + static constexpr auto arg_names = concat(type_descr(make_caster::name)...); + + bool load_args(function_call &call) { + return load_impl_sequence(call, indices{}); + } + + template + enable_if_t::value, Return> call(Func &&f) && { + return std::move(*this).template call_impl(std::forward(f), indices{}, Guard{}); + } + + template + enable_if_t::value, void_type> call(Func &&f) && { + std::move(*this).template call_impl(std::forward(f), indices{}, Guard{}); + return void_type(); + } + +private: + + static bool load_impl_sequence(function_call &, index_sequence<>) { return true; } + + template + bool load_impl_sequence(function_call &call, index_sequence) { + for (bool r : {std::get(argcasters).load(call.args[Is], call.args_convert[Is])...}) + if (!r) + return false; + return true; + } + + template + Return call_impl(Func &&f, index_sequence, Guard &&) { + return std::forward(f)(cast_op(std::move(std::get(argcasters)))...); + } + + std::tuple...> argcasters; +}; + +/// Helper class which collects only positional arguments for a Python function call. +/// A fancier version below can collect any argument, but this one is optimal for simple calls. +template +class simple_collector { +public: + template + explicit simple_collector(Ts &&...values) + : m_args(pybind11::make_tuple(std::forward(values)...)) { } + + const tuple &args() const & { return m_args; } + dict kwargs() const { return {}; } + + tuple args() && { return std::move(m_args); } + + /// Call a Python function and pass the collected arguments + object call(PyObject *ptr) const { + PyObject *result = PyObject_CallObject(ptr, m_args.ptr()); + if (!result) + throw error_already_set(); + return reinterpret_steal(result); + } + +private: + tuple m_args; +}; + +/// Helper class which collects positional, keyword, * and ** arguments for a Python function call +template +class unpacking_collector { +public: + template + explicit unpacking_collector(Ts &&...values) { + // Tuples aren't (easily) resizable so a list is needed for collection, + // but the actual function call strictly requires a tuple. + auto args_list = list(); + int _[] = { 0, (process(args_list, std::forward(values)), 0)... }; + ignore_unused(_); + + m_args = std::move(args_list); + } + + const tuple &args() const & { return m_args; } + const dict &kwargs() const & { return m_kwargs; } + + tuple args() && { return std::move(m_args); } + dict kwargs() && { return std::move(m_kwargs); } + + /// Call a Python function and pass the collected arguments + object call(PyObject *ptr) const { + PyObject *result = PyObject_Call(ptr, m_args.ptr(), m_kwargs.ptr()); + if (!result) + throw error_already_set(); + return reinterpret_steal(result); + } + +private: + template + void process(list &args_list, T &&x) { + auto o = reinterpret_steal(detail::make_caster::cast(std::forward(x), policy, {})); + if (!o) { +#if defined(NDEBUG) + argument_cast_error(); +#else + argument_cast_error(std::to_string(args_list.size()), type_id()); +#endif + } + args_list.append(o); + } + + void process(list &args_list, detail::args_proxy ap) { + for (const auto &a : ap) + args_list.append(a); + } + + void process(list &/*args_list*/, arg_v a) { + if (!a.name) +#if defined(NDEBUG) + nameless_argument_error(); +#else + nameless_argument_error(a.type); +#endif + + if (m_kwargs.contains(a.name)) { +#if defined(NDEBUG) + multiple_values_error(); +#else + multiple_values_error(a.name); +#endif + } + if (!a.value) { +#if defined(NDEBUG) + argument_cast_error(); +#else + argument_cast_error(a.name, a.type); +#endif + } + m_kwargs[a.name] = a.value; + } + + void process(list &/*args_list*/, detail::kwargs_proxy kp) { + if (!kp) + return; + for (const auto &k : reinterpret_borrow(kp)) { + if (m_kwargs.contains(k.first)) { +#if defined(NDEBUG) + multiple_values_error(); +#else + multiple_values_error(str(k.first)); +#endif + } + m_kwargs[k.first] = k.second; + } + } + + [[noreturn]] static void nameless_argument_error() { + throw type_error("Got kwargs without a name; only named arguments " + "may be passed via py::arg() to a python function call. " + "(compile in debug mode for details)"); + } + [[noreturn]] static void nameless_argument_error(std::string type) { + throw type_error("Got kwargs without a name of type '" + type + "'; only named " + "arguments may be passed via py::arg() to a python function call. "); + } + [[noreturn]] static void multiple_values_error() { + throw type_error("Got multiple values for keyword argument " + "(compile in debug mode for details)"); + } + + [[noreturn]] static void multiple_values_error(std::string name) { + throw type_error("Got multiple values for keyword argument '" + name + "'"); + } + + [[noreturn]] static void argument_cast_error() { + throw cast_error("Unable to convert call argument to Python object " + "(compile in debug mode for details)"); + } + + [[noreturn]] static void argument_cast_error(std::string name, std::string type) { + throw cast_error("Unable to convert call argument '" + name + + "' of type '" + type + "' to Python object"); + } + +private: + tuple m_args; + dict m_kwargs; +}; + +/// Collect only positional arguments for a Python function call +template ...>::value>> +simple_collector collect_arguments(Args &&...args) { + return simple_collector(std::forward(args)...); +} + +/// Collect all arguments, including keywords and unpacking (only instantiated when needed) +template ...>::value>> +unpacking_collector collect_arguments(Args &&...args) { + // Following argument order rules for generalized unpacking according to PEP 448 + static_assert( + constexpr_last() < constexpr_first() + && constexpr_last() < constexpr_first(), + "Invalid function call: positional args must precede keywords and ** unpacking; " + "* unpacking must precede ** unpacking" + ); + return unpacking_collector(std::forward(args)...); +} + +template +template +object object_api::operator()(Args &&...args) const { + return detail::collect_arguments(std::forward(args)...).call(derived().ptr()); +} + +template +template +object object_api::call(Args &&...args) const { + return operator()(std::forward(args)...); +} + +NAMESPACE_END(detail) + +#define PYBIND11_MAKE_OPAQUE(...) \ + namespace pybind11 { namespace detail { \ + template<> class type_caster<__VA_ARGS__> : public type_caster_base<__VA_ARGS__> { }; \ + }} + +/// Lets you pass a type containing a `,` through a macro parameter without needing a separate +/// typedef, e.g.: `PYBIND11_OVERLOAD(PYBIND11_TYPE(ReturnType), PYBIND11_TYPE(Parent), f, arg)` +#define PYBIND11_TYPE(...) __VA_ARGS__ + +NAMESPACE_END(PYBIND11_NAMESPACE) diff --git a/wrap/python/pybind11/include/pybind11/chrono.h b/wrap/python/pybind11/include/pybind11/chrono.h new file mode 100644 index 000000000..2ace2329d --- /dev/null +++ b/wrap/python/pybind11/include/pybind11/chrono.h @@ -0,0 +1,162 @@ +/* + pybind11/chrono.h: Transparent conversion between std::chrono and python's datetime + + Copyright (c) 2016 Trent Houliston and + Wenzel Jakob + + All rights reserved. Use of this source code is governed by a + BSD-style license that can be found in the LICENSE file. +*/ + +#pragma once + +#include "pybind11.h" +#include +#include +#include +#include + +// Backport the PyDateTime_DELTA functions from Python3.3 if required +#ifndef PyDateTime_DELTA_GET_DAYS +#define PyDateTime_DELTA_GET_DAYS(o) (((PyDateTime_Delta*)o)->days) +#endif +#ifndef PyDateTime_DELTA_GET_SECONDS +#define PyDateTime_DELTA_GET_SECONDS(o) (((PyDateTime_Delta*)o)->seconds) +#endif +#ifndef PyDateTime_DELTA_GET_MICROSECONDS +#define PyDateTime_DELTA_GET_MICROSECONDS(o) (((PyDateTime_Delta*)o)->microseconds) +#endif + +NAMESPACE_BEGIN(PYBIND11_NAMESPACE) +NAMESPACE_BEGIN(detail) + +template class duration_caster { +public: + typedef typename type::rep rep; + typedef typename type::period period; + + typedef std::chrono::duration> days; + + bool load(handle src, bool) { + using namespace std::chrono; + + // Lazy initialise the PyDateTime import + if (!PyDateTimeAPI) { PyDateTime_IMPORT; } + + if (!src) return false; + // If invoked with datetime.delta object + if (PyDelta_Check(src.ptr())) { + value = type(duration_cast>( + days(PyDateTime_DELTA_GET_DAYS(src.ptr())) + + seconds(PyDateTime_DELTA_GET_SECONDS(src.ptr())) + + microseconds(PyDateTime_DELTA_GET_MICROSECONDS(src.ptr())))); + return true; + } + // If invoked with a float we assume it is seconds and convert + else if (PyFloat_Check(src.ptr())) { + value = type(duration_cast>(duration(PyFloat_AsDouble(src.ptr())))); + return true; + } + else return false; + } + + // If this is a duration just return it back + static const std::chrono::duration& get_duration(const std::chrono::duration &src) { + return src; + } + + // If this is a time_point get the time_since_epoch + template static std::chrono::duration get_duration(const std::chrono::time_point> &src) { + return src.time_since_epoch(); + } + + static handle cast(const type &src, return_value_policy /* policy */, handle /* parent */) { + using namespace std::chrono; + + // Use overloaded function to get our duration from our source + // Works out if it is a duration or time_point and get the duration + auto d = get_duration(src); + + // Lazy initialise the PyDateTime import + if (!PyDateTimeAPI) { PyDateTime_IMPORT; } + + // Declare these special duration types so the conversions happen with the correct primitive types (int) + using dd_t = duration>; + using ss_t = duration>; + using us_t = duration; + + auto dd = duration_cast(d); + auto subd = d - dd; + auto ss = duration_cast(subd); + auto us = duration_cast(subd - ss); + return PyDelta_FromDSU(dd.count(), ss.count(), us.count()); + } + + PYBIND11_TYPE_CASTER(type, _("datetime.timedelta")); +}; + +// This is for casting times on the system clock into datetime.datetime instances +template class type_caster> { +public: + typedef std::chrono::time_point type; + bool load(handle src, bool) { + using namespace std::chrono; + + // Lazy initialise the PyDateTime import + if (!PyDateTimeAPI) { PyDateTime_IMPORT; } + + if (!src) return false; + if (PyDateTime_Check(src.ptr())) { + std::tm cal; + cal.tm_sec = PyDateTime_DATE_GET_SECOND(src.ptr()); + cal.tm_min = PyDateTime_DATE_GET_MINUTE(src.ptr()); + cal.tm_hour = PyDateTime_DATE_GET_HOUR(src.ptr()); + cal.tm_mday = PyDateTime_GET_DAY(src.ptr()); + cal.tm_mon = PyDateTime_GET_MONTH(src.ptr()) - 1; + cal.tm_year = PyDateTime_GET_YEAR(src.ptr()) - 1900; + cal.tm_isdst = -1; + + value = system_clock::from_time_t(std::mktime(&cal)) + microseconds(PyDateTime_DATE_GET_MICROSECOND(src.ptr())); + return true; + } + else return false; + } + + static handle cast(const std::chrono::time_point &src, return_value_policy /* policy */, handle /* parent */) { + using namespace std::chrono; + + // Lazy initialise the PyDateTime import + if (!PyDateTimeAPI) { PyDateTime_IMPORT; } + + std::time_t tt = system_clock::to_time_t(time_point_cast(src)); + // this function uses static memory so it's best to copy it out asap just in case + // otherwise other code that is using localtime may break this (not just python code) + std::tm localtime = *std::localtime(&tt); + + // Declare these special duration types so the conversions happen with the correct primitive types (int) + using us_t = duration; + + return PyDateTime_FromDateAndTime(localtime.tm_year + 1900, + localtime.tm_mon + 1, + localtime.tm_mday, + localtime.tm_hour, + localtime.tm_min, + localtime.tm_sec, + (duration_cast(src.time_since_epoch() % seconds(1))).count()); + } + PYBIND11_TYPE_CASTER(type, _("datetime.datetime")); +}; + +// Other clocks that are not the system clock are not measured as datetime.datetime objects +// since they are not measured on calendar time. So instead we just make them timedeltas +// Or if they have passed us a time as a float we convert that +template class type_caster> +: public duration_caster> { +}; + +template class type_caster> +: public duration_caster> { +}; + +NAMESPACE_END(detail) +NAMESPACE_END(PYBIND11_NAMESPACE) diff --git a/wrap/python/pybind11/include/pybind11/common.h b/wrap/python/pybind11/include/pybind11/common.h new file mode 100644 index 000000000..6c8a4f1e8 --- /dev/null +++ b/wrap/python/pybind11/include/pybind11/common.h @@ -0,0 +1,2 @@ +#include "detail/common.h" +#warning "Including 'common.h' is deprecated. It will be removed in v3.0. Use 'pybind11.h'." diff --git a/wrap/python/pybind11/include/pybind11/complex.h b/wrap/python/pybind11/include/pybind11/complex.h new file mode 100644 index 000000000..3f8963857 --- /dev/null +++ b/wrap/python/pybind11/include/pybind11/complex.h @@ -0,0 +1,65 @@ +/* + pybind11/complex.h: Complex number support + + Copyright (c) 2016 Wenzel Jakob + + All rights reserved. Use of this source code is governed by a + BSD-style license that can be found in the LICENSE file. +*/ + +#pragma once + +#include "pybind11.h" +#include + +/// glibc defines I as a macro which breaks things, e.g., boost template names +#ifdef I +# undef I +#endif + +NAMESPACE_BEGIN(PYBIND11_NAMESPACE) + +template struct format_descriptor, detail::enable_if_t::value>> { + static constexpr const char c = format_descriptor::c; + static constexpr const char value[3] = { 'Z', c, '\0' }; + static std::string format() { return std::string(value); } +}; + +#ifndef PYBIND11_CPP17 + +template constexpr const char format_descriptor< + std::complex, detail::enable_if_t::value>>::value[3]; + +#endif + +NAMESPACE_BEGIN(detail) + +template struct is_fmt_numeric, detail::enable_if_t::value>> { + static constexpr bool value = true; + static constexpr int index = is_fmt_numeric::index + 3; +}; + +template class type_caster> { +public: + bool load(handle src, bool convert) { + if (!src) + return false; + if (!convert && !PyComplex_Check(src.ptr())) + return false; + Py_complex result = PyComplex_AsCComplex(src.ptr()); + if (result.real == -1.0 && PyErr_Occurred()) { + PyErr_Clear(); + return false; + } + value = std::complex((T) result.real, (T) result.imag); + return true; + } + + static handle cast(const std::complex &src, return_value_policy /* policy */, handle /* parent */) { + return PyComplex_FromDoubles((double) src.real(), (double) src.imag()); + } + + PYBIND11_TYPE_CASTER(std::complex, _("complex")); +}; +NAMESPACE_END(detail) +NAMESPACE_END(PYBIND11_NAMESPACE) diff --git a/wrap/python/pybind11/include/pybind11/detail/class.h b/wrap/python/pybind11/include/pybind11/detail/class.h new file mode 100644 index 000000000..b1916fcd0 --- /dev/null +++ b/wrap/python/pybind11/include/pybind11/detail/class.h @@ -0,0 +1,623 @@ +/* + pybind11/detail/class.h: Python C API implementation details for py::class_ + + Copyright (c) 2017 Wenzel Jakob + + All rights reserved. Use of this source code is governed by a + BSD-style license that can be found in the LICENSE file. +*/ + +#pragma once + +#include "../attr.h" +#include "../options.h" + +NAMESPACE_BEGIN(PYBIND11_NAMESPACE) +NAMESPACE_BEGIN(detail) + +#if PY_VERSION_HEX >= 0x03030000 +# define PYBIND11_BUILTIN_QUALNAME +# define PYBIND11_SET_OLDPY_QUALNAME(obj, nameobj) +#else +// In pre-3.3 Python, we still set __qualname__ so that we can produce reliable function type +// signatures; in 3.3+ this macro expands to nothing: +# define PYBIND11_SET_OLDPY_QUALNAME(obj, nameobj) setattr((PyObject *) obj, "__qualname__", nameobj) +#endif + +inline PyTypeObject *type_incref(PyTypeObject *type) { + Py_INCREF(type); + return type; +} + +#if !defined(PYPY_VERSION) + +/// `pybind11_static_property.__get__()`: Always pass the class instead of the instance. +extern "C" inline PyObject *pybind11_static_get(PyObject *self, PyObject * /*ob*/, PyObject *cls) { + return PyProperty_Type.tp_descr_get(self, cls, cls); +} + +/// `pybind11_static_property.__set__()`: Just like the above `__get__()`. +extern "C" inline int pybind11_static_set(PyObject *self, PyObject *obj, PyObject *value) { + PyObject *cls = PyType_Check(obj) ? obj : (PyObject *) Py_TYPE(obj); + return PyProperty_Type.tp_descr_set(self, cls, value); +} + +/** A `static_property` is the same as a `property` but the `__get__()` and `__set__()` + methods are modified to always use the object type instead of a concrete instance. + Return value: New reference. */ +inline PyTypeObject *make_static_property_type() { + constexpr auto *name = "pybind11_static_property"; + auto name_obj = reinterpret_steal(PYBIND11_FROM_STRING(name)); + + /* Danger zone: from now (and until PyType_Ready), make sure to + issue no Python C API calls which could potentially invoke the + garbage collector (the GC will call type_traverse(), which will in + turn find the newly constructed type in an invalid state) */ + auto heap_type = (PyHeapTypeObject *) PyType_Type.tp_alloc(&PyType_Type, 0); + if (!heap_type) + pybind11_fail("make_static_property_type(): error allocating type!"); + + heap_type->ht_name = name_obj.inc_ref().ptr(); +#ifdef PYBIND11_BUILTIN_QUALNAME + heap_type->ht_qualname = name_obj.inc_ref().ptr(); +#endif + + auto type = &heap_type->ht_type; + type->tp_name = name; + type->tp_base = type_incref(&PyProperty_Type); + type->tp_flags = Py_TPFLAGS_DEFAULT | Py_TPFLAGS_BASETYPE | Py_TPFLAGS_HEAPTYPE; + type->tp_descr_get = pybind11_static_get; + type->tp_descr_set = pybind11_static_set; + + if (PyType_Ready(type) < 0) + pybind11_fail("make_static_property_type(): failure in PyType_Ready()!"); + + setattr((PyObject *) type, "__module__", str("pybind11_builtins")); + PYBIND11_SET_OLDPY_QUALNAME(type, name_obj); + + return type; +} + +#else // PYPY + +/** PyPy has some issues with the above C API, so we evaluate Python code instead. + This function will only be called once so performance isn't really a concern. + Return value: New reference. */ +inline PyTypeObject *make_static_property_type() { + auto d = dict(); + PyObject *result = PyRun_String(R"(\ + class pybind11_static_property(property): + def __get__(self, obj, cls): + return property.__get__(self, cls, cls) + + def __set__(self, obj, value): + cls = obj if isinstance(obj, type) else type(obj) + property.__set__(self, cls, value) + )", Py_file_input, d.ptr(), d.ptr() + ); + if (result == nullptr) + throw error_already_set(); + Py_DECREF(result); + return (PyTypeObject *) d["pybind11_static_property"].cast().release().ptr(); +} + +#endif // PYPY + +/** Types with static properties need to handle `Type.static_prop = x` in a specific way. + By default, Python replaces the `static_property` itself, but for wrapped C++ types + we need to call `static_property.__set__()` in order to propagate the new value to + the underlying C++ data structure. */ +extern "C" inline int pybind11_meta_setattro(PyObject* obj, PyObject* name, PyObject* value) { + // Use `_PyType_Lookup()` instead of `PyObject_GetAttr()` in order to get the raw + // descriptor (`property`) instead of calling `tp_descr_get` (`property.__get__()`). + PyObject *descr = _PyType_Lookup((PyTypeObject *) obj, name); + + // The following assignment combinations are possible: + // 1. `Type.static_prop = value` --> descr_set: `Type.static_prop.__set__(value)` + // 2. `Type.static_prop = other_static_prop` --> setattro: replace existing `static_prop` + // 3. `Type.regular_attribute = value` --> setattro: regular attribute assignment + const auto static_prop = (PyObject *) get_internals().static_property_type; + const auto call_descr_set = descr && PyObject_IsInstance(descr, static_prop) + && !PyObject_IsInstance(value, static_prop); + if (call_descr_set) { + // Call `static_property.__set__()` instead of replacing the `static_property`. +#if !defined(PYPY_VERSION) + return Py_TYPE(descr)->tp_descr_set(descr, obj, value); +#else + if (PyObject *result = PyObject_CallMethod(descr, "__set__", "OO", obj, value)) { + Py_DECREF(result); + return 0; + } else { + return -1; + } +#endif + } else { + // Replace existing attribute. + return PyType_Type.tp_setattro(obj, name, value); + } +} + +#if PY_MAJOR_VERSION >= 3 +/** + * Python 3's PyInstanceMethod_Type hides itself via its tp_descr_get, which prevents aliasing + * methods via cls.attr("m2") = cls.attr("m1"): instead the tp_descr_get returns a plain function, + * when called on a class, or a PyMethod, when called on an instance. Override that behaviour here + * to do a special case bypass for PyInstanceMethod_Types. + */ +extern "C" inline PyObject *pybind11_meta_getattro(PyObject *obj, PyObject *name) { + PyObject *descr = _PyType_Lookup((PyTypeObject *) obj, name); + if (descr && PyInstanceMethod_Check(descr)) { + Py_INCREF(descr); + return descr; + } + else { + return PyType_Type.tp_getattro(obj, name); + } +} +#endif + +/** This metaclass is assigned by default to all pybind11 types and is required in order + for static properties to function correctly. Users may override this using `py::metaclass`. + Return value: New reference. */ +inline PyTypeObject* make_default_metaclass() { + constexpr auto *name = "pybind11_type"; + auto name_obj = reinterpret_steal(PYBIND11_FROM_STRING(name)); + + /* Danger zone: from now (and until PyType_Ready), make sure to + issue no Python C API calls which could potentially invoke the + garbage collector (the GC will call type_traverse(), which will in + turn find the newly constructed type in an invalid state) */ + auto heap_type = (PyHeapTypeObject *) PyType_Type.tp_alloc(&PyType_Type, 0); + if (!heap_type) + pybind11_fail("make_default_metaclass(): error allocating metaclass!"); + + heap_type->ht_name = name_obj.inc_ref().ptr(); +#ifdef PYBIND11_BUILTIN_QUALNAME + heap_type->ht_qualname = name_obj.inc_ref().ptr(); +#endif + + auto type = &heap_type->ht_type; + type->tp_name = name; + type->tp_base = type_incref(&PyType_Type); + type->tp_flags = Py_TPFLAGS_DEFAULT | Py_TPFLAGS_BASETYPE | Py_TPFLAGS_HEAPTYPE; + + type->tp_setattro = pybind11_meta_setattro; +#if PY_MAJOR_VERSION >= 3 + type->tp_getattro = pybind11_meta_getattro; +#endif + + if (PyType_Ready(type) < 0) + pybind11_fail("make_default_metaclass(): failure in PyType_Ready()!"); + + setattr((PyObject *) type, "__module__", str("pybind11_builtins")); + PYBIND11_SET_OLDPY_QUALNAME(type, name_obj); + + return type; +} + +/// For multiple inheritance types we need to recursively register/deregister base pointers for any +/// base classes with pointers that are difference from the instance value pointer so that we can +/// correctly recognize an offset base class pointer. This calls a function with any offset base ptrs. +inline void traverse_offset_bases(void *valueptr, const detail::type_info *tinfo, instance *self, + bool (*f)(void * /*parentptr*/, instance * /*self*/)) { + for (handle h : reinterpret_borrow(tinfo->type->tp_bases)) { + if (auto parent_tinfo = get_type_info((PyTypeObject *) h.ptr())) { + for (auto &c : parent_tinfo->implicit_casts) { + if (c.first == tinfo->cpptype) { + auto *parentptr = c.second(valueptr); + if (parentptr != valueptr) + f(parentptr, self); + traverse_offset_bases(parentptr, parent_tinfo, self, f); + break; + } + } + } + } +} + +inline bool register_instance_impl(void *ptr, instance *self) { + get_internals().registered_instances.emplace(ptr, self); + return true; // unused, but gives the same signature as the deregister func +} +inline bool deregister_instance_impl(void *ptr, instance *self) { + auto ®istered_instances = get_internals().registered_instances; + auto range = registered_instances.equal_range(ptr); + for (auto it = range.first; it != range.second; ++it) { + if (Py_TYPE(self) == Py_TYPE(it->second)) { + registered_instances.erase(it); + return true; + } + } + return false; +} + +inline void register_instance(instance *self, void *valptr, const type_info *tinfo) { + register_instance_impl(valptr, self); + if (!tinfo->simple_ancestors) + traverse_offset_bases(valptr, tinfo, self, register_instance_impl); +} + +inline bool deregister_instance(instance *self, void *valptr, const type_info *tinfo) { + bool ret = deregister_instance_impl(valptr, self); + if (!tinfo->simple_ancestors) + traverse_offset_bases(valptr, tinfo, self, deregister_instance_impl); + return ret; +} + +/// Instance creation function for all pybind11 types. It allocates the internal instance layout for +/// holding C++ objects and holders. Allocation is done lazily (the first time the instance is cast +/// to a reference or pointer), and initialization is done by an `__init__` function. +inline PyObject *make_new_instance(PyTypeObject *type) { +#if defined(PYPY_VERSION) + // PyPy gets tp_basicsize wrong (issue 2482) under multiple inheritance when the first inherited + // object is a a plain Python type (i.e. not derived from an extension type). Fix it. + ssize_t instance_size = static_cast(sizeof(instance)); + if (type->tp_basicsize < instance_size) { + type->tp_basicsize = instance_size; + } +#endif + PyObject *self = type->tp_alloc(type, 0); + auto inst = reinterpret_cast(self); + // Allocate the value/holder internals: + inst->allocate_layout(); + + inst->owned = true; + + return self; +} + +/// Instance creation function for all pybind11 types. It only allocates space for the +/// C++ object, but doesn't call the constructor -- an `__init__` function must do that. +extern "C" inline PyObject *pybind11_object_new(PyTypeObject *type, PyObject *, PyObject *) { + return make_new_instance(type); +} + +/// An `__init__` function constructs the C++ object. Users should provide at least one +/// of these using `py::init` or directly with `.def(__init__, ...)`. Otherwise, the +/// following default function will be used which simply throws an exception. +extern "C" inline int pybind11_object_init(PyObject *self, PyObject *, PyObject *) { + PyTypeObject *type = Py_TYPE(self); + std::string msg; +#if defined(PYPY_VERSION) + msg += handle((PyObject *) type).attr("__module__").cast() + "."; +#endif + msg += type->tp_name; + msg += ": No constructor defined!"; + PyErr_SetString(PyExc_TypeError, msg.c_str()); + return -1; +} + +inline void add_patient(PyObject *nurse, PyObject *patient) { + auto &internals = get_internals(); + auto instance = reinterpret_cast(nurse); + instance->has_patients = true; + Py_INCREF(patient); + internals.patients[nurse].push_back(patient); +} + +inline void clear_patients(PyObject *self) { + auto instance = reinterpret_cast(self); + auto &internals = get_internals(); + auto pos = internals.patients.find(self); + assert(pos != internals.patients.end()); + // Clearing the patients can cause more Python code to run, which + // can invalidate the iterator. Extract the vector of patients + // from the unordered_map first. + auto patients = std::move(pos->second); + internals.patients.erase(pos); + instance->has_patients = false; + for (PyObject *&patient : patients) + Py_CLEAR(patient); +} + +/// Clears all internal data from the instance and removes it from registered instances in +/// preparation for deallocation. +inline void clear_instance(PyObject *self) { + auto instance = reinterpret_cast(self); + + // Deallocate any values/holders, if present: + for (auto &v_h : values_and_holders(instance)) { + if (v_h) { + + // We have to deregister before we call dealloc because, for virtual MI types, we still + // need to be able to get the parent pointers. + if (v_h.instance_registered() && !deregister_instance(instance, v_h.value_ptr(), v_h.type)) + pybind11_fail("pybind11_object_dealloc(): Tried to deallocate unregistered instance!"); + + if (instance->owned || v_h.holder_constructed()) + v_h.type->dealloc(v_h); + } + } + // Deallocate the value/holder layout internals: + instance->deallocate_layout(); + + if (instance->weakrefs) + PyObject_ClearWeakRefs(self); + + PyObject **dict_ptr = _PyObject_GetDictPtr(self); + if (dict_ptr) + Py_CLEAR(*dict_ptr); + + if (instance->has_patients) + clear_patients(self); +} + +/// Instance destructor function for all pybind11 types. It calls `type_info.dealloc` +/// to destroy the C++ object itself, while the rest is Python bookkeeping. +extern "C" inline void pybind11_object_dealloc(PyObject *self) { + clear_instance(self); + + auto type = Py_TYPE(self); + type->tp_free(self); + + // `type->tp_dealloc != pybind11_object_dealloc` means that we're being called + // as part of a derived type's dealloc, in which case we're not allowed to decref + // the type here. For cross-module compatibility, we shouldn't compare directly + // with `pybind11_object_dealloc`, but with the common one stashed in internals. + auto pybind11_object_type = (PyTypeObject *) get_internals().instance_base; + if (type->tp_dealloc == pybind11_object_type->tp_dealloc) + Py_DECREF(type); +} + +/** Create the type which can be used as a common base for all classes. This is + needed in order to satisfy Python's requirements for multiple inheritance. + Return value: New reference. */ +inline PyObject *make_object_base_type(PyTypeObject *metaclass) { + constexpr auto *name = "pybind11_object"; + auto name_obj = reinterpret_steal(PYBIND11_FROM_STRING(name)); + + /* Danger zone: from now (and until PyType_Ready), make sure to + issue no Python C API calls which could potentially invoke the + garbage collector (the GC will call type_traverse(), which will in + turn find the newly constructed type in an invalid state) */ + auto heap_type = (PyHeapTypeObject *) metaclass->tp_alloc(metaclass, 0); + if (!heap_type) + pybind11_fail("make_object_base_type(): error allocating type!"); + + heap_type->ht_name = name_obj.inc_ref().ptr(); +#ifdef PYBIND11_BUILTIN_QUALNAME + heap_type->ht_qualname = name_obj.inc_ref().ptr(); +#endif + + auto type = &heap_type->ht_type; + type->tp_name = name; + type->tp_base = type_incref(&PyBaseObject_Type); + type->tp_basicsize = static_cast(sizeof(instance)); + type->tp_flags = Py_TPFLAGS_DEFAULT | Py_TPFLAGS_BASETYPE | Py_TPFLAGS_HEAPTYPE; + + type->tp_new = pybind11_object_new; + type->tp_init = pybind11_object_init; + type->tp_dealloc = pybind11_object_dealloc; + + /* Support weak references (needed for the keep_alive feature) */ + type->tp_weaklistoffset = offsetof(instance, weakrefs); + + if (PyType_Ready(type) < 0) + pybind11_fail("PyType_Ready failed in make_object_base_type():" + error_string()); + + setattr((PyObject *) type, "__module__", str("pybind11_builtins")); + PYBIND11_SET_OLDPY_QUALNAME(type, name_obj); + + assert(!PyType_HasFeature(type, Py_TPFLAGS_HAVE_GC)); + return (PyObject *) heap_type; +} + +/// dynamic_attr: Support for `d = instance.__dict__`. +extern "C" inline PyObject *pybind11_get_dict(PyObject *self, void *) { + PyObject *&dict = *_PyObject_GetDictPtr(self); + if (!dict) + dict = PyDict_New(); + Py_XINCREF(dict); + return dict; +} + +/// dynamic_attr: Support for `instance.__dict__ = dict()`. +extern "C" inline int pybind11_set_dict(PyObject *self, PyObject *new_dict, void *) { + if (!PyDict_Check(new_dict)) { + PyErr_Format(PyExc_TypeError, "__dict__ must be set to a dictionary, not a '%.200s'", + Py_TYPE(new_dict)->tp_name); + return -1; + } + PyObject *&dict = *_PyObject_GetDictPtr(self); + Py_INCREF(new_dict); + Py_CLEAR(dict); + dict = new_dict; + return 0; +} + +/// dynamic_attr: Allow the garbage collector to traverse the internal instance `__dict__`. +extern "C" inline int pybind11_traverse(PyObject *self, visitproc visit, void *arg) { + PyObject *&dict = *_PyObject_GetDictPtr(self); + Py_VISIT(dict); + return 0; +} + +/// dynamic_attr: Allow the GC to clear the dictionary. +extern "C" inline int pybind11_clear(PyObject *self) { + PyObject *&dict = *_PyObject_GetDictPtr(self); + Py_CLEAR(dict); + return 0; +} + +/// Give instances of this type a `__dict__` and opt into garbage collection. +inline void enable_dynamic_attributes(PyHeapTypeObject *heap_type) { + auto type = &heap_type->ht_type; +#if defined(PYPY_VERSION) + pybind11_fail(std::string(type->tp_name) + ": dynamic attributes are " + "currently not supported in " + "conjunction with PyPy!"); +#endif + type->tp_flags |= Py_TPFLAGS_HAVE_GC; + type->tp_dictoffset = type->tp_basicsize; // place dict at the end + type->tp_basicsize += (ssize_t)sizeof(PyObject *); // and allocate enough space for it + type->tp_traverse = pybind11_traverse; + type->tp_clear = pybind11_clear; + + static PyGetSetDef getset[] = { + {const_cast("__dict__"), pybind11_get_dict, pybind11_set_dict, nullptr, nullptr}, + {nullptr, nullptr, nullptr, nullptr, nullptr} + }; + type->tp_getset = getset; +} + +/// buffer_protocol: Fill in the view as specified by flags. +extern "C" inline int pybind11_getbuffer(PyObject *obj, Py_buffer *view, int flags) { + // Look for a `get_buffer` implementation in this type's info or any bases (following MRO). + type_info *tinfo = nullptr; + for (auto type : reinterpret_borrow(Py_TYPE(obj)->tp_mro)) { + tinfo = get_type_info((PyTypeObject *) type.ptr()); + if (tinfo && tinfo->get_buffer) + break; + } + if (view == nullptr || !tinfo || !tinfo->get_buffer) { + if (view) + view->obj = nullptr; + PyErr_SetString(PyExc_BufferError, "pybind11_getbuffer(): Internal error"); + return -1; + } + std::memset(view, 0, sizeof(Py_buffer)); + buffer_info *info = tinfo->get_buffer(obj, tinfo->get_buffer_data); + view->obj = obj; + view->ndim = 1; + view->internal = info; + view->buf = info->ptr; + view->itemsize = info->itemsize; + view->len = view->itemsize; + for (auto s : info->shape) + view->len *= s; + if ((flags & PyBUF_FORMAT) == PyBUF_FORMAT) + view->format = const_cast(info->format.c_str()); + if ((flags & PyBUF_STRIDES) == PyBUF_STRIDES) { + view->ndim = (int) info->ndim; + view->strides = &info->strides[0]; + view->shape = &info->shape[0]; + } + Py_INCREF(view->obj); + return 0; +} + +/// buffer_protocol: Release the resources of the buffer. +extern "C" inline void pybind11_releasebuffer(PyObject *, Py_buffer *view) { + delete (buffer_info *) view->internal; +} + +/// Give this type a buffer interface. +inline void enable_buffer_protocol(PyHeapTypeObject *heap_type) { + heap_type->ht_type.tp_as_buffer = &heap_type->as_buffer; +#if PY_MAJOR_VERSION < 3 + heap_type->ht_type.tp_flags |= Py_TPFLAGS_HAVE_NEWBUFFER; +#endif + + heap_type->as_buffer.bf_getbuffer = pybind11_getbuffer; + heap_type->as_buffer.bf_releasebuffer = pybind11_releasebuffer; +} + +/** Create a brand new Python type according to the `type_record` specification. + Return value: New reference. */ +inline PyObject* make_new_python_type(const type_record &rec) { + auto name = reinterpret_steal(PYBIND11_FROM_STRING(rec.name)); + + auto qualname = name; + if (rec.scope && !PyModule_Check(rec.scope.ptr()) && hasattr(rec.scope, "__qualname__")) { +#if PY_MAJOR_VERSION >= 3 + qualname = reinterpret_steal( + PyUnicode_FromFormat("%U.%U", rec.scope.attr("__qualname__").ptr(), name.ptr())); +#else + qualname = str(rec.scope.attr("__qualname__").cast() + "." + rec.name); +#endif + } + + object module; + if (rec.scope) { + if (hasattr(rec.scope, "__module__")) + module = rec.scope.attr("__module__"); + else if (hasattr(rec.scope, "__name__")) + module = rec.scope.attr("__name__"); + } + + auto full_name = c_str( +#if !defined(PYPY_VERSION) + module ? str(module).cast() + "." + rec.name : +#endif + rec.name); + + char *tp_doc = nullptr; + if (rec.doc && options::show_user_defined_docstrings()) { + /* Allocate memory for docstring (using PyObject_MALLOC, since + Python will free this later on) */ + size_t size = strlen(rec.doc) + 1; + tp_doc = (char *) PyObject_MALLOC(size); + memcpy((void *) tp_doc, rec.doc, size); + } + + auto &internals = get_internals(); + auto bases = tuple(rec.bases); + auto base = (bases.size() == 0) ? internals.instance_base + : bases[0].ptr(); + + /* Danger zone: from now (and until PyType_Ready), make sure to + issue no Python C API calls which could potentially invoke the + garbage collector (the GC will call type_traverse(), which will in + turn find the newly constructed type in an invalid state) */ + auto metaclass = rec.metaclass.ptr() ? (PyTypeObject *) rec.metaclass.ptr() + : internals.default_metaclass; + + auto heap_type = (PyHeapTypeObject *) metaclass->tp_alloc(metaclass, 0); + if (!heap_type) + pybind11_fail(std::string(rec.name) + ": Unable to create type object!"); + + heap_type->ht_name = name.release().ptr(); +#ifdef PYBIND11_BUILTIN_QUALNAME + heap_type->ht_qualname = qualname.inc_ref().ptr(); +#endif + + auto type = &heap_type->ht_type; + type->tp_name = full_name; + type->tp_doc = tp_doc; + type->tp_base = type_incref((PyTypeObject *)base); + type->tp_basicsize = static_cast(sizeof(instance)); + if (bases.size() > 0) + type->tp_bases = bases.release().ptr(); + + /* Don't inherit base __init__ */ + type->tp_init = pybind11_object_init; + + /* Supported protocols */ + type->tp_as_number = &heap_type->as_number; + type->tp_as_sequence = &heap_type->as_sequence; + type->tp_as_mapping = &heap_type->as_mapping; + + /* Flags */ + type->tp_flags |= Py_TPFLAGS_DEFAULT | Py_TPFLAGS_BASETYPE | Py_TPFLAGS_HEAPTYPE; +#if PY_MAJOR_VERSION < 3 + type->tp_flags |= Py_TPFLAGS_CHECKTYPES; +#endif + + if (rec.dynamic_attr) + enable_dynamic_attributes(heap_type); + + if (rec.buffer_protocol) + enable_buffer_protocol(heap_type); + + if (PyType_Ready(type) < 0) + pybind11_fail(std::string(rec.name) + ": PyType_Ready failed (" + error_string() + ")!"); + + assert(rec.dynamic_attr ? PyType_HasFeature(type, Py_TPFLAGS_HAVE_GC) + : !PyType_HasFeature(type, Py_TPFLAGS_HAVE_GC)); + + /* Register type with the parent scope */ + if (rec.scope) + setattr(rec.scope, rec.name, (PyObject *) type); + else + Py_INCREF(type); // Keep it alive forever (reference leak) + + if (module) // Needed by pydoc + setattr((PyObject *) type, "__module__", module); + + PYBIND11_SET_OLDPY_QUALNAME(type, qualname); + + return (PyObject *) type; +} + +NAMESPACE_END(detail) +NAMESPACE_END(PYBIND11_NAMESPACE) diff --git a/wrap/python/pybind11/include/pybind11/detail/common.h b/wrap/python/pybind11/include/pybind11/detail/common.h new file mode 100644 index 000000000..300c2b23d --- /dev/null +++ b/wrap/python/pybind11/include/pybind11/detail/common.h @@ -0,0 +1,807 @@ +/* + pybind11/detail/common.h -- Basic macros + + Copyright (c) 2016 Wenzel Jakob + + All rights reserved. Use of this source code is governed by a + BSD-style license that can be found in the LICENSE file. +*/ + +#pragma once + +#if !defined(NAMESPACE_BEGIN) +# define NAMESPACE_BEGIN(name) namespace name { +#endif +#if !defined(NAMESPACE_END) +# define NAMESPACE_END(name) } +#endif + +// Robust support for some features and loading modules compiled against different pybind versions +// requires forcing hidden visibility on pybind code, so we enforce this by setting the attribute on +// the main `pybind11` namespace. +#if !defined(PYBIND11_NAMESPACE) +# ifdef __GNUG__ +# define PYBIND11_NAMESPACE pybind11 __attribute__((visibility("hidden"))) +# else +# define PYBIND11_NAMESPACE pybind11 +# endif +#endif + +#if !(defined(_MSC_VER) && __cplusplus == 199711L) && !defined(__INTEL_COMPILER) +# if __cplusplus >= 201402L +# define PYBIND11_CPP14 +# if __cplusplus >= 201703L +# define PYBIND11_CPP17 +# endif +# endif +#elif defined(_MSC_VER) && __cplusplus == 199711L +// MSVC sets _MSVC_LANG rather than __cplusplus (supposedly until the standard is fully implemented) +// Unless you use the /Zc:__cplusplus flag on Visual Studio 2017 15.7 Preview 3 or newer +# if _MSVC_LANG >= 201402L +# define PYBIND11_CPP14 +# if _MSVC_LANG > 201402L && _MSC_VER >= 1910 +# define PYBIND11_CPP17 +# endif +# endif +#endif + +// Compiler version assertions +#if defined(__INTEL_COMPILER) +# if __INTEL_COMPILER < 1700 +# error pybind11 requires Intel C++ compiler v17 or newer +# endif +#elif defined(__clang__) && !defined(__apple_build_version__) +# if __clang_major__ < 3 || (__clang_major__ == 3 && __clang_minor__ < 3) +# error pybind11 requires clang 3.3 or newer +# endif +#elif defined(__clang__) +// Apple changes clang version macros to its Xcode version; the first Xcode release based on +// (upstream) clang 3.3 was Xcode 5: +# if __clang_major__ < 5 +# error pybind11 requires Xcode/clang 5.0 or newer +# endif +#elif defined(__GNUG__) +# if __GNUC__ < 4 || (__GNUC__ == 4 && __GNUC_MINOR__ < 8) +# error pybind11 requires gcc 4.8 or newer +# endif +#elif defined(_MSC_VER) +// Pybind hits various compiler bugs in 2015u2 and earlier, and also makes use of some stl features +// (e.g. std::negation) added in 2015u3: +# if _MSC_FULL_VER < 190024210 +# error pybind11 requires MSVC 2015 update 3 or newer +# endif +#endif + +#if !defined(PYBIND11_EXPORT) +# if defined(WIN32) || defined(_WIN32) +# define PYBIND11_EXPORT __declspec(dllexport) +# else +# define PYBIND11_EXPORT __attribute__ ((visibility("default"))) +# endif +#endif + +#if defined(_MSC_VER) +# define PYBIND11_NOINLINE __declspec(noinline) +#else +# define PYBIND11_NOINLINE __attribute__ ((noinline)) +#endif + +#if defined(PYBIND11_CPP14) +# define PYBIND11_DEPRECATED(reason) [[deprecated(reason)]] +#else +# define PYBIND11_DEPRECATED(reason) __attribute__((deprecated(reason))) +#endif + +#define PYBIND11_VERSION_MAJOR 2 +#define PYBIND11_VERSION_MINOR 3 +#define PYBIND11_VERSION_PATCH dev1 + +/// Include Python header, disable linking to pythonX_d.lib on Windows in debug mode +#if defined(_MSC_VER) +# if (PY_MAJOR_VERSION == 3 && PY_MINOR_VERSION < 4) +# define HAVE_ROUND 1 +# endif +# pragma warning(push) +# pragma warning(disable: 4510 4610 4512 4005) +# if defined(_DEBUG) +# define PYBIND11_DEBUG_MARKER +# undef _DEBUG +# endif +#endif + +#include +#include +#include + +#if defined(_WIN32) && (defined(min) || defined(max)) +# error Macro clash with min and max -- define NOMINMAX when compiling your program on Windows +#endif + +#if defined(isalnum) +# undef isalnum +# undef isalpha +# undef islower +# undef isspace +# undef isupper +# undef tolower +# undef toupper +#endif + +#if defined(_MSC_VER) +# if defined(PYBIND11_DEBUG_MARKER) +# define _DEBUG +# undef PYBIND11_DEBUG_MARKER +# endif +# pragma warning(pop) +#endif + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#if PY_MAJOR_VERSION >= 3 /// Compatibility macros for various Python versions +#define PYBIND11_INSTANCE_METHOD_NEW(ptr, class_) PyInstanceMethod_New(ptr) +#define PYBIND11_INSTANCE_METHOD_CHECK PyInstanceMethod_Check +#define PYBIND11_INSTANCE_METHOD_GET_FUNCTION PyInstanceMethod_GET_FUNCTION +#define PYBIND11_BYTES_CHECK PyBytes_Check +#define PYBIND11_BYTES_FROM_STRING PyBytes_FromString +#define PYBIND11_BYTES_FROM_STRING_AND_SIZE PyBytes_FromStringAndSize +#define PYBIND11_BYTES_AS_STRING_AND_SIZE PyBytes_AsStringAndSize +#define PYBIND11_BYTES_AS_STRING PyBytes_AsString +#define PYBIND11_BYTES_SIZE PyBytes_Size +#define PYBIND11_LONG_CHECK(o) PyLong_Check(o) +#define PYBIND11_LONG_AS_LONGLONG(o) PyLong_AsLongLong(o) +#define PYBIND11_LONG_FROM_SIGNED(o) PyLong_FromSsize_t((ssize_t) o) +#define PYBIND11_LONG_FROM_UNSIGNED(o) PyLong_FromSize_t((size_t) o) +#define PYBIND11_BYTES_NAME "bytes" +#define PYBIND11_STRING_NAME "str" +#define PYBIND11_SLICE_OBJECT PyObject +#define PYBIND11_FROM_STRING PyUnicode_FromString +#define PYBIND11_STR_TYPE ::pybind11::str +#define PYBIND11_BOOL_ATTR "__bool__" +#define PYBIND11_NB_BOOL(ptr) ((ptr)->nb_bool) +#define PYBIND11_PLUGIN_IMPL(name) \ + extern "C" PYBIND11_EXPORT PyObject *PyInit_##name() + +#else +#define PYBIND11_INSTANCE_METHOD_NEW(ptr, class_) PyMethod_New(ptr, nullptr, class_) +#define PYBIND11_INSTANCE_METHOD_CHECK PyMethod_Check +#define PYBIND11_INSTANCE_METHOD_GET_FUNCTION PyMethod_GET_FUNCTION +#define PYBIND11_BYTES_CHECK PyString_Check +#define PYBIND11_BYTES_FROM_STRING PyString_FromString +#define PYBIND11_BYTES_FROM_STRING_AND_SIZE PyString_FromStringAndSize +#define PYBIND11_BYTES_AS_STRING_AND_SIZE PyString_AsStringAndSize +#define PYBIND11_BYTES_AS_STRING PyString_AsString +#define PYBIND11_BYTES_SIZE PyString_Size +#define PYBIND11_LONG_CHECK(o) (PyInt_Check(o) || PyLong_Check(o)) +#define PYBIND11_LONG_AS_LONGLONG(o) (PyInt_Check(o) ? (long long) PyLong_AsLong(o) : PyLong_AsLongLong(o)) +#define PYBIND11_LONG_FROM_SIGNED(o) PyInt_FromSsize_t((ssize_t) o) // Returns long if needed. +#define PYBIND11_LONG_FROM_UNSIGNED(o) PyInt_FromSize_t((size_t) o) // Returns long if needed. +#define PYBIND11_BYTES_NAME "str" +#define PYBIND11_STRING_NAME "unicode" +#define PYBIND11_SLICE_OBJECT PySliceObject +#define PYBIND11_FROM_STRING PyString_FromString +#define PYBIND11_STR_TYPE ::pybind11::bytes +#define PYBIND11_BOOL_ATTR "__nonzero__" +#define PYBIND11_NB_BOOL(ptr) ((ptr)->nb_nonzero) +#define PYBIND11_PLUGIN_IMPL(name) \ + static PyObject *pybind11_init_wrapper(); \ + extern "C" PYBIND11_EXPORT void init##name() { \ + (void)pybind11_init_wrapper(); \ + } \ + PyObject *pybind11_init_wrapper() +#endif + +#if PY_VERSION_HEX >= 0x03050000 && PY_VERSION_HEX < 0x03050200 +extern "C" { + struct _Py_atomic_address { void *value; }; + PyAPI_DATA(_Py_atomic_address) _PyThreadState_Current; +} +#endif + +#define PYBIND11_TRY_NEXT_OVERLOAD ((PyObject *) 1) // special failure return code +#define PYBIND11_STRINGIFY(x) #x +#define PYBIND11_TOSTRING(x) PYBIND11_STRINGIFY(x) +#define PYBIND11_CONCAT(first, second) first##second + +#define PYBIND11_CHECK_PYTHON_VERSION \ + { \ + const char *compiled_ver = PYBIND11_TOSTRING(PY_MAJOR_VERSION) \ + "." PYBIND11_TOSTRING(PY_MINOR_VERSION); \ + const char *runtime_ver = Py_GetVersion(); \ + size_t len = std::strlen(compiled_ver); \ + if (std::strncmp(runtime_ver, compiled_ver, len) != 0 \ + || (runtime_ver[len] >= '0' && runtime_ver[len] <= '9')) { \ + PyErr_Format(PyExc_ImportError, \ + "Python version mismatch: module was compiled for Python %s, " \ + "but the interpreter version is incompatible: %s.", \ + compiled_ver, runtime_ver); \ + return nullptr; \ + } \ + } + +#define PYBIND11_CATCH_INIT_EXCEPTIONS \ + catch (pybind11::error_already_set &e) { \ + PyErr_SetString(PyExc_ImportError, e.what()); \ + return nullptr; \ + } catch (const std::exception &e) { \ + PyErr_SetString(PyExc_ImportError, e.what()); \ + return nullptr; \ + } \ + +/** \rst + ***Deprecated in favor of PYBIND11_MODULE*** + + This macro creates the entry point that will be invoked when the Python interpreter + imports a plugin library. Please create a `module` in the function body and return + the pointer to its underlying Python object at the end. + + .. code-block:: cpp + + PYBIND11_PLUGIN(example) { + pybind11::module m("example", "pybind11 example plugin"); + /// Set up bindings here + return m.ptr(); + } +\endrst */ +#define PYBIND11_PLUGIN(name) \ + PYBIND11_DEPRECATED("PYBIND11_PLUGIN is deprecated, use PYBIND11_MODULE") \ + static PyObject *pybind11_init(); \ + PYBIND11_PLUGIN_IMPL(name) { \ + PYBIND11_CHECK_PYTHON_VERSION \ + try { \ + return pybind11_init(); \ + } PYBIND11_CATCH_INIT_EXCEPTIONS \ + } \ + PyObject *pybind11_init() + +/** \rst + This macro creates the entry point that will be invoked when the Python interpreter + imports an extension module. The module name is given as the fist argument and it + should not be in quotes. The second macro argument defines a variable of type + `py::module` which can be used to initialize the module. + + .. code-block:: cpp + + PYBIND11_MODULE(example, m) { + m.doc() = "pybind11 example module"; + + // Add bindings here + m.def("foo", []() { + return "Hello, World!"; + }); + } +\endrst */ +#define PYBIND11_MODULE(name, variable) \ + static void PYBIND11_CONCAT(pybind11_init_, name)(pybind11::module &); \ + PYBIND11_PLUGIN_IMPL(name) { \ + PYBIND11_CHECK_PYTHON_VERSION \ + auto m = pybind11::module(PYBIND11_TOSTRING(name)); \ + try { \ + PYBIND11_CONCAT(pybind11_init_, name)(m); \ + return m.ptr(); \ + } PYBIND11_CATCH_INIT_EXCEPTIONS \ + } \ + void PYBIND11_CONCAT(pybind11_init_, name)(pybind11::module &variable) + + +NAMESPACE_BEGIN(PYBIND11_NAMESPACE) + +using ssize_t = Py_ssize_t; +using size_t = std::size_t; + +/// Approach used to cast a previously unknown C++ instance into a Python object +enum class return_value_policy : uint8_t { + /** This is the default return value policy, which falls back to the policy + return_value_policy::take_ownership when the return value is a pointer. + Otherwise, it uses return_value::move or return_value::copy for rvalue + and lvalue references, respectively. See below for a description of what + all of these different policies do. */ + automatic = 0, + + /** As above, but use policy return_value_policy::reference when the return + value is a pointer. This is the default conversion policy for function + arguments when calling Python functions manually from C++ code (i.e. via + handle::operator()). You probably won't need to use this. */ + automatic_reference, + + /** Reference an existing object (i.e. do not create a new copy) and take + ownership. Python will call the destructor and delete operator when the + object’s reference count reaches zero. Undefined behavior ensues when + the C++ side does the same.. */ + take_ownership, + + /** Create a new copy of the returned object, which will be owned by + Python. This policy is comparably safe because the lifetimes of the two + instances are decoupled. */ + copy, + + /** Use std::move to move the return value contents into a new instance + that will be owned by Python. This policy is comparably safe because the + lifetimes of the two instances (move source and destination) are + decoupled. */ + move, + + /** Reference an existing object, but do not take ownership. The C++ side + is responsible for managing the object’s lifetime and deallocating it + when it is no longer used. Warning: undefined behavior will ensue when + the C++ side deletes an object that is still referenced and used by + Python. */ + reference, + + /** This policy only applies to methods and properties. It references the + object without taking ownership similar to the above + return_value_policy::reference policy. In contrast to that policy, the + function or property’s implicit this argument (called the parent) is + considered to be the the owner of the return value (the child). + pybind11 then couples the lifetime of the parent to the child via a + reference relationship that ensures that the parent cannot be garbage + collected while Python is still using the child. More advanced + variations of this scheme are also possible using combinations of + return_value_policy::reference and the keep_alive call policy */ + reference_internal +}; + +NAMESPACE_BEGIN(detail) + +inline static constexpr int log2(size_t n, int k = 0) { return (n <= 1) ? k : log2(n >> 1, k + 1); } + +// Returns the size as a multiple of sizeof(void *), rounded up. +inline static constexpr size_t size_in_ptrs(size_t s) { return 1 + ((s - 1) >> log2(sizeof(void *))); } + +/** + * The space to allocate for simple layout instance holders (see below) in multiple of the size of + * a pointer (e.g. 2 means 16 bytes on 64-bit architectures). The default is the minimum required + * to holder either a std::unique_ptr or std::shared_ptr (which is almost always + * sizeof(std::shared_ptr)). + */ +constexpr size_t instance_simple_holder_in_ptrs() { + static_assert(sizeof(std::shared_ptr) >= sizeof(std::unique_ptr), + "pybind assumes std::shared_ptrs are at least as big as std::unique_ptrs"); + return size_in_ptrs(sizeof(std::shared_ptr)); +} + +// Forward declarations +struct type_info; +struct value_and_holder; + +struct nonsimple_values_and_holders { + void **values_and_holders; + uint8_t *status; +}; + +/// The 'instance' type which needs to be standard layout (need to be able to use 'offsetof') +struct instance { + PyObject_HEAD + /// Storage for pointers and holder; see simple_layout, below, for a description + union { + void *simple_value_holder[1 + instance_simple_holder_in_ptrs()]; + nonsimple_values_and_holders nonsimple; + }; + /// Weak references + PyObject *weakrefs; + /// If true, the pointer is owned which means we're free to manage it with a holder. + bool owned : 1; + /** + * An instance has two possible value/holder layouts. + * + * Simple layout (when this flag is true), means the `simple_value_holder` is set with a pointer + * and the holder object governing that pointer, i.e. [val1*][holder]. This layout is applied + * whenever there is no python-side multiple inheritance of bound C++ types *and* the type's + * holder will fit in the default space (which is large enough to hold either a std::unique_ptr + * or std::shared_ptr). + * + * Non-simple layout applies when using custom holders that require more space than `shared_ptr` + * (which is typically the size of two pointers), or when multiple inheritance is used on the + * python side. Non-simple layout allocates the required amount of memory to have multiple + * bound C++ classes as parents. Under this layout, `nonsimple.values_and_holders` is set to a + * pointer to allocated space of the required space to hold a sequence of value pointers and + * holders followed `status`, a set of bit flags (1 byte each), i.e. + * [val1*][holder1][val2*][holder2]...[bb...] where each [block] is rounded up to a multiple of + * `sizeof(void *)`. `nonsimple.status` is, for convenience, a pointer to the + * beginning of the [bb...] block (but not independently allocated). + * + * Status bits indicate whether the associated holder is constructed (& + * status_holder_constructed) and whether the value pointer is registered (& + * status_instance_registered) in `registered_instances`. + */ + bool simple_layout : 1; + /// For simple layout, tracks whether the holder has been constructed + bool simple_holder_constructed : 1; + /// For simple layout, tracks whether the instance is registered in `registered_instances` + bool simple_instance_registered : 1; + /// If true, get_internals().patients has an entry for this object + bool has_patients : 1; + + /// Initializes all of the above type/values/holders data (but not the instance values themselves) + void allocate_layout(); + + /// Destroys/deallocates all of the above + void deallocate_layout(); + + /// Returns the value_and_holder wrapper for the given type (or the first, if `find_type` + /// omitted). Returns a default-constructed (with `.inst = nullptr`) object on failure if + /// `throw_if_missing` is false. + value_and_holder get_value_and_holder(const type_info *find_type = nullptr, bool throw_if_missing = true); + + /// Bit values for the non-simple status flags + static constexpr uint8_t status_holder_constructed = 1; + static constexpr uint8_t status_instance_registered = 2; +}; + +static_assert(std::is_standard_layout::value, "Internal error: `pybind11::detail::instance` is not standard layout!"); + +/// from __cpp_future__ import (convenient aliases from C++14/17) +#if defined(PYBIND11_CPP14) && (!defined(_MSC_VER) || _MSC_VER >= 1910) +using std::enable_if_t; +using std::conditional_t; +using std::remove_cv_t; +using std::remove_reference_t; +#else +template using enable_if_t = typename std::enable_if::type; +template using conditional_t = typename std::conditional::type; +template using remove_cv_t = typename std::remove_cv::type; +template using remove_reference_t = typename std::remove_reference::type; +#endif + +/// Index sequences +#if defined(PYBIND11_CPP14) +using std::index_sequence; +using std::make_index_sequence; +#else +template struct index_sequence { }; +template struct make_index_sequence_impl : make_index_sequence_impl { }; +template struct make_index_sequence_impl <0, S...> { typedef index_sequence type; }; +template using make_index_sequence = typename make_index_sequence_impl::type; +#endif + +/// Make an index sequence of the indices of true arguments +template struct select_indices_impl { using type = ISeq; }; +template struct select_indices_impl, I, B, Bs...> + : select_indices_impl, index_sequence>, I + 1, Bs...> {}; +template using select_indices = typename select_indices_impl, 0, Bs...>::type; + +/// Backports of std::bool_constant and std::negation to accommodate older compilers +template using bool_constant = std::integral_constant; +template struct negation : bool_constant { }; + +template struct void_t_impl { using type = void; }; +template using void_t = typename void_t_impl::type; + +/// Compile-time all/any/none of that check the boolean value of all template types +#if defined(__cpp_fold_expressions) && !(defined(_MSC_VER) && (_MSC_VER < 1916)) +template using all_of = bool_constant<(Ts::value && ...)>; +template using any_of = bool_constant<(Ts::value || ...)>; +#elif !defined(_MSC_VER) +template struct bools {}; +template using all_of = std::is_same< + bools, + bools>; +template using any_of = negation...>>; +#else +// MSVC has trouble with the above, but supports std::conjunction, which we can use instead (albeit +// at a slight loss of compilation efficiency). +template using all_of = std::conjunction; +template using any_of = std::disjunction; +#endif +template using none_of = negation>; + +template class... Predicates> using satisfies_all_of = all_of...>; +template class... Predicates> using satisfies_any_of = any_of...>; +template class... Predicates> using satisfies_none_of = none_of...>; + +/// Strip the class from a method type +template struct remove_class { }; +template struct remove_class { typedef R type(A...); }; +template struct remove_class { typedef R type(A...); }; + +/// Helper template to strip away type modifiers +template struct intrinsic_type { typedef T type; }; +template struct intrinsic_type { typedef typename intrinsic_type::type type; }; +template struct intrinsic_type { typedef typename intrinsic_type::type type; }; +template struct intrinsic_type { typedef typename intrinsic_type::type type; }; +template struct intrinsic_type { typedef typename intrinsic_type::type type; }; +template struct intrinsic_type { typedef typename intrinsic_type::type type; }; +template struct intrinsic_type { typedef typename intrinsic_type::type type; }; +template using intrinsic_t = typename intrinsic_type::type; + +/// Helper type to replace 'void' in some expressions +struct void_type { }; + +/// Helper template which holds a list of types +template struct type_list { }; + +/// Compile-time integer sum +#ifdef __cpp_fold_expressions +template constexpr size_t constexpr_sum(Ts... ns) { return (0 + ... + size_t{ns}); } +#else +constexpr size_t constexpr_sum() { return 0; } +template +constexpr size_t constexpr_sum(T n, Ts... ns) { return size_t{n} + constexpr_sum(ns...); } +#endif + +NAMESPACE_BEGIN(constexpr_impl) +/// Implementation details for constexpr functions +constexpr int first(int i) { return i; } +template +constexpr int first(int i, T v, Ts... vs) { return v ? i : first(i + 1, vs...); } + +constexpr int last(int /*i*/, int result) { return result; } +template +constexpr int last(int i, int result, T v, Ts... vs) { return last(i + 1, v ? i : result, vs...); } +NAMESPACE_END(constexpr_impl) + +/// Return the index of the first type in Ts which satisfies Predicate. Returns sizeof...(Ts) if +/// none match. +template class Predicate, typename... Ts> +constexpr int constexpr_first() { return constexpr_impl::first(0, Predicate::value...); } + +/// Return the index of the last type in Ts which satisfies Predicate, or -1 if none match. +template class Predicate, typename... Ts> +constexpr int constexpr_last() { return constexpr_impl::last(0, -1, Predicate::value...); } + +/// Return the Nth element from the parameter pack +template +struct pack_element { using type = typename pack_element::type; }; +template +struct pack_element<0, T, Ts...> { using type = T; }; + +/// Return the one and only type which matches the predicate, or Default if none match. +/// If more than one type matches the predicate, fail at compile-time. +template class Predicate, typename Default, typename... Ts> +struct exactly_one { + static constexpr auto found = constexpr_sum(Predicate::value...); + static_assert(found <= 1, "Found more than one type matching the predicate"); + + static constexpr auto index = found ? constexpr_first() : 0; + using type = conditional_t::type, Default>; +}; +template class P, typename Default> +struct exactly_one { using type = Default; }; + +template class Predicate, typename Default, typename... Ts> +using exactly_one_t = typename exactly_one::type; + +/// Defer the evaluation of type T until types Us are instantiated +template struct deferred_type { using type = T; }; +template using deferred_t = typename deferred_type::type; + +/// Like is_base_of, but requires a strict base (i.e. `is_strict_base_of::value == false`, +/// unlike `std::is_base_of`) +template using is_strict_base_of = bool_constant< + std::is_base_of::value && !std::is_same::value>; + +/// Like is_base_of, but also requires that the base type is accessible (i.e. that a Derived pointer +/// can be converted to a Base pointer) +template using is_accessible_base_of = bool_constant< + std::is_base_of::value && std::is_convertible::value>; + +template class Base> +struct is_template_base_of_impl { + template static std::true_type check(Base *); + static std::false_type check(...); +}; + +/// Check if a template is the base of a type. For example: +/// `is_template_base_of` is true if `struct T : Base {}` where U can be anything +template class Base, typename T> +#if !defined(_MSC_VER) +using is_template_base_of = decltype(is_template_base_of_impl::check((intrinsic_t*)nullptr)); +#else // MSVC2015 has trouble with decltype in template aliases +struct is_template_base_of : decltype(is_template_base_of_impl::check((intrinsic_t*)nullptr)) { }; +#endif + +/// Check if T is an instantiation of the template `Class`. For example: +/// `is_instantiation` is true if `T == shared_ptr` where U can be anything. +template class Class, typename T> +struct is_instantiation : std::false_type { }; +template class Class, typename... Us> +struct is_instantiation> : std::true_type { }; + +/// Check if T is std::shared_ptr where U can be anything +template using is_shared_ptr = is_instantiation; + +/// Check if T looks like an input iterator +template struct is_input_iterator : std::false_type {}; +template +struct is_input_iterator()), decltype(++std::declval())>> + : std::true_type {}; + +template using is_function_pointer = bool_constant< + std::is_pointer::value && std::is_function::type>::value>; + +template struct strip_function_object { + using type = typename remove_class::type; +}; + +// Extracts the function signature from a function, function pointer or lambda. +template > +using function_signature_t = conditional_t< + std::is_function::value, + F, + typename conditional_t< + std::is_pointer::value || std::is_member_pointer::value, + std::remove_pointer, + strip_function_object + >::type +>; + +/// Returns true if the type looks like a lambda: that is, isn't a function, pointer or member +/// pointer. Note that this can catch all sorts of other things, too; this is intended to be used +/// in a place where passing a lambda makes sense. +template using is_lambda = satisfies_none_of, + std::is_function, std::is_pointer, std::is_member_pointer>; + +/// Ignore that a variable is unused in compiler warnings +inline void ignore_unused(const int *) { } + +/// Apply a function over each element of a parameter pack +#ifdef __cpp_fold_expressions +#define PYBIND11_EXPAND_SIDE_EFFECTS(PATTERN) (((PATTERN), void()), ...) +#else +using expand_side_effects = bool[]; +#define PYBIND11_EXPAND_SIDE_EFFECTS(PATTERN) pybind11::detail::expand_side_effects{ ((PATTERN), void(), false)..., false } +#endif + +NAMESPACE_END(detail) + +/// C++ bindings of builtin Python exceptions +class builtin_exception : public std::runtime_error { +public: + using std::runtime_error::runtime_error; + /// Set the error using the Python C API + virtual void set_error() const = 0; +}; + +#define PYBIND11_RUNTIME_EXCEPTION(name, type) \ + class name : public builtin_exception { public: \ + using builtin_exception::builtin_exception; \ + name() : name("") { } \ + void set_error() const override { PyErr_SetString(type, what()); } \ + }; + +PYBIND11_RUNTIME_EXCEPTION(stop_iteration, PyExc_StopIteration) +PYBIND11_RUNTIME_EXCEPTION(index_error, PyExc_IndexError) +PYBIND11_RUNTIME_EXCEPTION(key_error, PyExc_KeyError) +PYBIND11_RUNTIME_EXCEPTION(value_error, PyExc_ValueError) +PYBIND11_RUNTIME_EXCEPTION(type_error, PyExc_TypeError) +PYBIND11_RUNTIME_EXCEPTION(cast_error, PyExc_RuntimeError) /// Thrown when pybind11::cast or handle::call fail due to a type casting error +PYBIND11_RUNTIME_EXCEPTION(reference_cast_error, PyExc_RuntimeError) /// Used internally + +[[noreturn]] PYBIND11_NOINLINE inline void pybind11_fail(const char *reason) { throw std::runtime_error(reason); } +[[noreturn]] PYBIND11_NOINLINE inline void pybind11_fail(const std::string &reason) { throw std::runtime_error(reason); } + +template struct format_descriptor { }; + +NAMESPACE_BEGIN(detail) +// Returns the index of the given type in the type char array below, and in the list in numpy.h +// The order here is: bool; 8 ints ((signed,unsigned)x(8,16,32,64)bits); float,double,long double; +// complex float,double,long double. Note that the long double types only participate when long +// double is actually longer than double (it isn't under MSVC). +// NB: not only the string below but also complex.h and numpy.h rely on this order. +template struct is_fmt_numeric { static constexpr bool value = false; }; +template struct is_fmt_numeric::value>> { + static constexpr bool value = true; + static constexpr int index = std::is_same::value ? 0 : 1 + ( + std::is_integral::value ? detail::log2(sizeof(T))*2 + std::is_unsigned::value : 8 + ( + std::is_same::value ? 1 : std::is_same::value ? 2 : 0)); +}; +NAMESPACE_END(detail) + +template struct format_descriptor::value>> { + static constexpr const char c = "?bBhHiIqQfdg"[detail::is_fmt_numeric::index]; + static constexpr const char value[2] = { c, '\0' }; + static std::string format() { return std::string(1, c); } +}; + +#if !defined(PYBIND11_CPP17) + +template constexpr const char format_descriptor< + T, detail::enable_if_t::value>>::value[2]; + +#endif + +/// RAII wrapper that temporarily clears any Python error state +struct error_scope { + PyObject *type, *value, *trace; + error_scope() { PyErr_Fetch(&type, &value, &trace); } + ~error_scope() { PyErr_Restore(type, value, trace); } +}; + +/// Dummy destructor wrapper that can be used to expose classes with a private destructor +struct nodelete { template void operator()(T*) { } }; + +// overload_cast requires variable templates: C++14 +#if defined(PYBIND11_CPP14) +#define PYBIND11_OVERLOAD_CAST 1 + +NAMESPACE_BEGIN(detail) +template +struct overload_cast_impl { + constexpr overload_cast_impl() {} // MSVC 2015 needs this + + template + constexpr auto operator()(Return (*pf)(Args...)) const noexcept + -> decltype(pf) { return pf; } + + template + constexpr auto operator()(Return (Class::*pmf)(Args...), std::false_type = {}) const noexcept + -> decltype(pmf) { return pmf; } + + template + constexpr auto operator()(Return (Class::*pmf)(Args...) const, std::true_type) const noexcept + -> decltype(pmf) { return pmf; } +}; +NAMESPACE_END(detail) + +/// Syntax sugar for resolving overloaded function pointers: +/// - regular: static_cast(&Class::func) +/// - sweet: overload_cast(&Class::func) +template +static constexpr detail::overload_cast_impl overload_cast = {}; +// MSVC 2015 only accepts this particular initialization syntax for this variable template. + +/// Const member function selector for overload_cast +/// - regular: static_cast(&Class::func) +/// - sweet: overload_cast(&Class::func, const_) +static constexpr auto const_ = std::true_type{}; + +#else // no overload_cast: providing something that static_assert-fails: +template struct overload_cast { + static_assert(detail::deferred_t::value, + "pybind11::overload_cast<...> requires compiling in C++14 mode"); +}; +#endif // overload_cast + +NAMESPACE_BEGIN(detail) + +// Adaptor for converting arbitrary container arguments into a vector; implicitly convertible from +// any standard container (or C-style array) supporting std::begin/std::end, any singleton +// arithmetic type (if T is arithmetic), or explicitly constructible from an iterator pair. +template +class any_container { + std::vector v; +public: + any_container() = default; + + // Can construct from a pair of iterators + template ::value>> + any_container(It first, It last) : v(first, last) { } + + // Implicit conversion constructor from any arbitrary container type with values convertible to T + template ())), T>::value>> + any_container(const Container &c) : any_container(std::begin(c), std::end(c)) { } + + // initializer_list's aren't deducible, so don't get matched by the above template; we need this + // to explicitly allow implicit conversion from one: + template ::value>> + any_container(const std::initializer_list &c) : any_container(c.begin(), c.end()) { } + + // Avoid copying if given an rvalue vector of the correct type. + any_container(std::vector &&v) : v(std::move(v)) { } + + // Moves the vector out of an rvalue any_container + operator std::vector &&() && { return std::move(v); } + + // Dereferencing obtains a reference to the underlying vector + std::vector &operator*() { return v; } + const std::vector &operator*() const { return v; } + + // -> lets you call methods on the underlying vector + std::vector *operator->() { return &v; } + const std::vector *operator->() const { return &v; } +}; + +NAMESPACE_END(detail) + + + +NAMESPACE_END(PYBIND11_NAMESPACE) diff --git a/wrap/python/pybind11/include/pybind11/detail/descr.h b/wrap/python/pybind11/include/pybind11/detail/descr.h new file mode 100644 index 000000000..8d404e534 --- /dev/null +++ b/wrap/python/pybind11/include/pybind11/detail/descr.h @@ -0,0 +1,100 @@ +/* + pybind11/detail/descr.h: Helper type for concatenating type signatures at compile time + + Copyright (c) 2016 Wenzel Jakob + + All rights reserved. Use of this source code is governed by a + BSD-style license that can be found in the LICENSE file. +*/ + +#pragma once + +#include "common.h" + +NAMESPACE_BEGIN(PYBIND11_NAMESPACE) +NAMESPACE_BEGIN(detail) + +#if !defined(_MSC_VER) +# define PYBIND11_DESCR_CONSTEXPR static constexpr +#else +# define PYBIND11_DESCR_CONSTEXPR const +#endif + +/* Concatenate type signatures at compile time */ +template +struct descr { + char text[N + 1]; + + constexpr descr() : text{'\0'} { } + constexpr descr(char const (&s)[N+1]) : descr(s, make_index_sequence()) { } + + template + constexpr descr(char const (&s)[N+1], index_sequence) : text{s[Is]..., '\0'} { } + + template + constexpr descr(char c, Chars... cs) : text{c, static_cast(cs)..., '\0'} { } + + static constexpr std::array types() { + return {{&typeid(Ts)..., nullptr}}; + } +}; + +template +constexpr descr plus_impl(const descr &a, const descr &b, + index_sequence, index_sequence) { + return {a.text[Is1]..., b.text[Is2]...}; +} + +template +constexpr descr operator+(const descr &a, const descr &b) { + return plus_impl(a, b, make_index_sequence(), make_index_sequence()); +} + +template +constexpr descr _(char const(&text)[N]) { return descr(text); } +constexpr descr<0> _(char const(&)[1]) { return {}; } + +template struct int_to_str : int_to_str { }; +template struct int_to_str<0, Digits...> { + static constexpr auto digits = descr(('0' + Digits)...); +}; + +// Ternary description (like std::conditional) +template +constexpr enable_if_t> _(char const(&text1)[N1], char const(&)[N2]) { + return _(text1); +} +template +constexpr enable_if_t> _(char const(&)[N1], char const(&text2)[N2]) { + return _(text2); +} + +template +constexpr enable_if_t _(const T1 &d, const T2 &) { return d; } +template +constexpr enable_if_t _(const T1 &, const T2 &d) { return d; } + +template auto constexpr _() -> decltype(int_to_str::digits) { + return int_to_str::digits; +} + +template constexpr descr<1, Type> _() { return {'%'}; } + +constexpr descr<0> concat() { return {}; } + +template +constexpr descr concat(const descr &descr) { return descr; } + +template +constexpr auto concat(const descr &d, const Args &...args) + -> decltype(std::declval>() + concat(args...)) { + return d + _(", ") + concat(args...); +} + +template +constexpr descr type_descr(const descr &descr) { + return _("{") + descr + _("}"); +} + +NAMESPACE_END(detail) +NAMESPACE_END(PYBIND11_NAMESPACE) diff --git a/wrap/python/pybind11/include/pybind11/detail/init.h b/wrap/python/pybind11/include/pybind11/detail/init.h new file mode 100644 index 000000000..acfe00bdb --- /dev/null +++ b/wrap/python/pybind11/include/pybind11/detail/init.h @@ -0,0 +1,335 @@ +/* + pybind11/detail/init.h: init factory function implementation and support code. + + Copyright (c) 2017 Jason Rhinelander + + All rights reserved. Use of this source code is governed by a + BSD-style license that can be found in the LICENSE file. +*/ + +#pragma once + +#include "class.h" + +NAMESPACE_BEGIN(PYBIND11_NAMESPACE) +NAMESPACE_BEGIN(detail) + +template <> +class type_caster { +public: + bool load(handle h, bool) { + value = reinterpret_cast(h.ptr()); + return true; + } + + template using cast_op_type = value_and_holder &; + operator value_and_holder &() { return *value; } + static constexpr auto name = _(); + +private: + value_and_holder *value = nullptr; +}; + +NAMESPACE_BEGIN(initimpl) + +inline void no_nullptr(void *ptr) { + if (!ptr) throw type_error("pybind11::init(): factory function returned nullptr"); +} + +// Implementing functions for all forms of py::init<...> and py::init(...) +template using Cpp = typename Class::type; +template using Alias = typename Class::type_alias; +template using Holder = typename Class::holder_type; + +template using is_alias_constructible = std::is_constructible, Cpp &&>; + +// Takes a Cpp pointer and returns true if it actually is a polymorphic Alias instance. +template = 0> +bool is_alias(Cpp *ptr) { + return dynamic_cast *>(ptr) != nullptr; +} +// Failing fallback version of the above for a no-alias class (always returns false) +template +constexpr bool is_alias(void *) { return false; } + +// Constructs and returns a new object; if the given arguments don't map to a constructor, we fall +// back to brace aggregate initiailization so that for aggregate initialization can be used with +// py::init, e.g. `py::init` to initialize a `struct T { int a; int b; }`. For +// non-aggregate types, we need to use an ordinary T(...) constructor (invoking as `T{...}` usually +// works, but will not do the expected thing when `T` has an `initializer_list` constructor). +template ::value, int> = 0> +inline Class *construct_or_initialize(Args &&...args) { return new Class(std::forward(args)...); } +template ::value, int> = 0> +inline Class *construct_or_initialize(Args &&...args) { return new Class{std::forward(args)...}; } + +// Attempts to constructs an alias using a `Alias(Cpp &&)` constructor. This allows types with +// an alias to provide only a single Cpp factory function as long as the Alias can be +// constructed from an rvalue reference of the base Cpp type. This means that Alias classes +// can, when appropriate, simply define a `Alias(Cpp &&)` constructor rather than needing to +// inherit all the base class constructors. +template +void construct_alias_from_cpp(std::true_type /*is_alias_constructible*/, + value_and_holder &v_h, Cpp &&base) { + v_h.value_ptr() = new Alias(std::move(base)); +} +template +[[noreturn]] void construct_alias_from_cpp(std::false_type /*!is_alias_constructible*/, + value_and_holder &, Cpp &&) { + throw type_error("pybind11::init(): unable to convert returned instance to required " + "alias class: no `Alias(Class &&)` constructor available"); +} + +// Error-generating fallback for factories that don't match one of the below construction +// mechanisms. +template +void construct(...) { + static_assert(!std::is_same::value /* always false */, + "pybind11::init(): init function must return a compatible pointer, " + "holder, or value"); +} + +// Pointer return v1: the factory function returns a class pointer for a registered class. +// If we don't need an alias (because this class doesn't have one, or because the final type is +// inherited on the Python side) we can simply take over ownership. Otherwise we need to try to +// construct an Alias from the returned base instance. +template +void construct(value_and_holder &v_h, Cpp *ptr, bool need_alias) { + no_nullptr(ptr); + if (Class::has_alias && need_alias && !is_alias(ptr)) { + // We're going to try to construct an alias by moving the cpp type. Whether or not + // that succeeds, we still need to destroy the original cpp pointer (either the + // moved away leftover, if the alias construction works, or the value itself if we + // throw an error), but we can't just call `delete ptr`: it might have a special + // deleter, or might be shared_from_this. So we construct a holder around it as if + // it was a normal instance, then steal the holder away into a local variable; thus + // the holder and destruction happens when we leave the C++ scope, and the holder + // class gets to handle the destruction however it likes. + v_h.value_ptr() = ptr; + v_h.set_instance_registered(true); // To prevent init_instance from registering it + v_h.type->init_instance(v_h.inst, nullptr); // Set up the holder + Holder temp_holder(std::move(v_h.holder>())); // Steal the holder + v_h.type->dealloc(v_h); // Destroys the moved-out holder remains, resets value ptr to null + v_h.set_instance_registered(false); + + construct_alias_from_cpp(is_alias_constructible{}, v_h, std::move(*ptr)); + } else { + // Otherwise the type isn't inherited, so we don't need an Alias + v_h.value_ptr() = ptr; + } +} + +// Pointer return v2: a factory that always returns an alias instance ptr. We simply take over +// ownership of the pointer. +template = 0> +void construct(value_and_holder &v_h, Alias *alias_ptr, bool) { + no_nullptr(alias_ptr); + v_h.value_ptr() = static_cast *>(alias_ptr); +} + +// Holder return: copy its pointer, and move or copy the returned holder into the new instance's +// holder. This also handles types like std::shared_ptr and std::unique_ptr where T is a +// derived type (through those holder's implicit conversion from derived class holder constructors). +template +void construct(value_and_holder &v_h, Holder holder, bool need_alias) { + auto *ptr = holder_helper>::get(holder); + // If we need an alias, check that the held pointer is actually an alias instance + if (Class::has_alias && need_alias && !is_alias(ptr)) + throw type_error("pybind11::init(): construction failed: returned holder-wrapped instance " + "is not an alias instance"); + + v_h.value_ptr() = ptr; + v_h.type->init_instance(v_h.inst, &holder); +} + +// return-by-value version 1: returning a cpp class by value. If the class has an alias and an +// alias is required the alias must have an `Alias(Cpp &&)` constructor so that we can construct +// the alias from the base when needed (i.e. because of Python-side inheritance). When we don't +// need it, we simply move-construct the cpp value into a new instance. +template +void construct(value_and_holder &v_h, Cpp &&result, bool need_alias) { + static_assert(std::is_move_constructible>::value, + "pybind11::init() return-by-value factory function requires a movable class"); + if (Class::has_alias && need_alias) + construct_alias_from_cpp(is_alias_constructible{}, v_h, std::move(result)); + else + v_h.value_ptr() = new Cpp(std::move(result)); +} + +// return-by-value version 2: returning a value of the alias type itself. We move-construct an +// Alias instance (even if no the python-side inheritance is involved). The is intended for +// cases where Alias initialization is always desired. +template +void construct(value_and_holder &v_h, Alias &&result, bool) { + static_assert(std::is_move_constructible>::value, + "pybind11::init() return-by-alias-value factory function requires a movable alias class"); + v_h.value_ptr() = new Alias(std::move(result)); +} + +// Implementing class for py::init<...>() +template +struct constructor { + template = 0> + static void execute(Class &cl, const Extra&... extra) { + cl.def("__init__", [](value_and_holder &v_h, Args... args) { + v_h.value_ptr() = construct_or_initialize>(std::forward(args)...); + }, is_new_style_constructor(), extra...); + } + + template , Args...>::value, int> = 0> + static void execute(Class &cl, const Extra&... extra) { + cl.def("__init__", [](value_and_holder &v_h, Args... args) { + if (Py_TYPE(v_h.inst) == v_h.type->type) + v_h.value_ptr() = construct_or_initialize>(std::forward(args)...); + else + v_h.value_ptr() = construct_or_initialize>(std::forward(args)...); + }, is_new_style_constructor(), extra...); + } + + template , Args...>::value, int> = 0> + static void execute(Class &cl, const Extra&... extra) { + cl.def("__init__", [](value_and_holder &v_h, Args... args) { + v_h.value_ptr() = construct_or_initialize>(std::forward(args)...); + }, is_new_style_constructor(), extra...); + } +}; + +// Implementing class for py::init_alias<...>() +template struct alias_constructor { + template , Args...>::value, int> = 0> + static void execute(Class &cl, const Extra&... extra) { + cl.def("__init__", [](value_and_holder &v_h, Args... args) { + v_h.value_ptr() = construct_or_initialize>(std::forward(args)...); + }, is_new_style_constructor(), extra...); + } +}; + +// Implementation class for py::init(Func) and py::init(Func, AliasFunc) +template , typename = function_signature_t> +struct factory; + +// Specialization for py::init(Func) +template +struct factory { + remove_reference_t class_factory; + + factory(Func &&f) : class_factory(std::forward(f)) { } + + // The given class either has no alias or has no separate alias factory; + // this always constructs the class itself. If the class is registered with an alias + // type and an alias instance is needed (i.e. because the final type is a Python class + // inheriting from the C++ type) the returned value needs to either already be an alias + // instance, or the alias needs to be constructible from a `Class &&` argument. + template + void execute(Class &cl, const Extra &...extra) && { + #if defined(PYBIND11_CPP14) + cl.def("__init__", [func = std::move(class_factory)] + #else + auto &func = class_factory; + cl.def("__init__", [func] + #endif + (value_and_holder &v_h, Args... args) { + construct(v_h, func(std::forward(args)...), + Py_TYPE(v_h.inst) != v_h.type->type); + }, is_new_style_constructor(), extra...); + } +}; + +// Specialization for py::init(Func, AliasFunc) +template +struct factory { + static_assert(sizeof...(CArgs) == sizeof...(AArgs), + "pybind11::init(class_factory, alias_factory): class and alias factories " + "must have identical argument signatures"); + static_assert(all_of...>::value, + "pybind11::init(class_factory, alias_factory): class and alias factories " + "must have identical argument signatures"); + + remove_reference_t class_factory; + remove_reference_t alias_factory; + + factory(CFunc &&c, AFunc &&a) + : class_factory(std::forward(c)), alias_factory(std::forward(a)) { } + + // The class factory is called when the `self` type passed to `__init__` is the direct + // class (i.e. not inherited), the alias factory when `self` is a Python-side subtype. + template + void execute(Class &cl, const Extra&... extra) && { + static_assert(Class::has_alias, "The two-argument version of `py::init()` can " + "only be used if the class has an alias"); + #if defined(PYBIND11_CPP14) + cl.def("__init__", [class_func = std::move(class_factory), alias_func = std::move(alias_factory)] + #else + auto &class_func = class_factory; + auto &alias_func = alias_factory; + cl.def("__init__", [class_func, alias_func] + #endif + (value_and_holder &v_h, CArgs... args) { + if (Py_TYPE(v_h.inst) == v_h.type->type) + // If the instance type equals the registered type we don't have inheritance, so + // don't need the alias and can construct using the class function: + construct(v_h, class_func(std::forward(args)...), false); + else + construct(v_h, alias_func(std::forward(args)...), true); + }, is_new_style_constructor(), extra...); + } +}; + +/// Set just the C++ state. Same as `__init__`. +template +void setstate(value_and_holder &v_h, T &&result, bool need_alias) { + construct(v_h, std::forward(result), need_alias); +} + +/// Set both the C++ and Python states +template ::value, int> = 0> +void setstate(value_and_holder &v_h, std::pair &&result, bool need_alias) { + construct(v_h, std::move(result.first), need_alias); + setattr((PyObject *) v_h.inst, "__dict__", result.second); +} + +/// Implementation for py::pickle(GetState, SetState) +template , typename = function_signature_t> +struct pickle_factory; + +template +struct pickle_factory { + static_assert(std::is_same, intrinsic_t>::value, + "The type returned by `__getstate__` must be the same " + "as the argument accepted by `__setstate__`"); + + remove_reference_t get; + remove_reference_t set; + + pickle_factory(Get get, Set set) + : get(std::forward(get)), set(std::forward(set)) { } + + template + void execute(Class &cl, const Extra &...extra) && { + cl.def("__getstate__", std::move(get)); + +#if defined(PYBIND11_CPP14) + cl.def("__setstate__", [func = std::move(set)] +#else + auto &func = set; + cl.def("__setstate__", [func] +#endif + (value_and_holder &v_h, ArgState state) { + setstate(v_h, func(std::forward(state)), + Py_TYPE(v_h.inst) != v_h.type->type); + }, is_new_style_constructor(), extra...); + } +}; + +NAMESPACE_END(initimpl) +NAMESPACE_END(detail) +NAMESPACE_END(pybind11) diff --git a/wrap/python/pybind11/include/pybind11/detail/internals.h b/wrap/python/pybind11/include/pybind11/detail/internals.h new file mode 100644 index 000000000..f1dd38764 --- /dev/null +++ b/wrap/python/pybind11/include/pybind11/detail/internals.h @@ -0,0 +1,291 @@ +/* + pybind11/detail/internals.h: Internal data structure and related functions + + Copyright (c) 2017 Wenzel Jakob + + All rights reserved. Use of this source code is governed by a + BSD-style license that can be found in the LICENSE file. +*/ + +#pragma once + +#include "../pytypes.h" + +NAMESPACE_BEGIN(PYBIND11_NAMESPACE) +NAMESPACE_BEGIN(detail) +// Forward declarations +inline PyTypeObject *make_static_property_type(); +inline PyTypeObject *make_default_metaclass(); +inline PyObject *make_object_base_type(PyTypeObject *metaclass); + +// The old Python Thread Local Storage (TLS) API is deprecated in Python 3.7 in favor of the new +// Thread Specific Storage (TSS) API. +#if PY_VERSION_HEX >= 0x03070000 +# define PYBIND11_TLS_KEY_INIT(var) Py_tss_t *var = nullptr +# define PYBIND11_TLS_GET_VALUE(key) PyThread_tss_get((key)) +# define PYBIND11_TLS_REPLACE_VALUE(key, value) PyThread_tss_set((key), (value)) +# define PYBIND11_TLS_DELETE_VALUE(key) PyThread_tss_set((key), nullptr) +#else + // Usually an int but a long on Cygwin64 with Python 3.x +# define PYBIND11_TLS_KEY_INIT(var) decltype(PyThread_create_key()) var = 0 +# define PYBIND11_TLS_GET_VALUE(key) PyThread_get_key_value((key)) +# if PY_MAJOR_VERSION < 3 +# define PYBIND11_TLS_DELETE_VALUE(key) \ + PyThread_delete_key_value(key) +# define PYBIND11_TLS_REPLACE_VALUE(key, value) \ + do { \ + PyThread_delete_key_value((key)); \ + PyThread_set_key_value((key), (value)); \ + } while (false) +# else +# define PYBIND11_TLS_DELETE_VALUE(key) \ + PyThread_set_key_value((key), nullptr) +# define PYBIND11_TLS_REPLACE_VALUE(key, value) \ + PyThread_set_key_value((key), (value)) +# endif +#endif + +// Python loads modules by default with dlopen with the RTLD_LOCAL flag; under libc++ and possibly +// other STLs, this means `typeid(A)` from one module won't equal `typeid(A)` from another module +// even when `A` is the same, non-hidden-visibility type (e.g. from a common include). Under +// libstdc++, this doesn't happen: equality and the type_index hash are based on the type name, +// which works. If not under a known-good stl, provide our own name-based hash and equality +// functions that use the type name. +#if defined(__GLIBCXX__) +inline bool same_type(const std::type_info &lhs, const std::type_info &rhs) { return lhs == rhs; } +using type_hash = std::hash; +using type_equal_to = std::equal_to; +#else +inline bool same_type(const std::type_info &lhs, const std::type_info &rhs) { + return lhs.name() == rhs.name() || std::strcmp(lhs.name(), rhs.name()) == 0; +} + +struct type_hash { + size_t operator()(const std::type_index &t) const { + size_t hash = 5381; + const char *ptr = t.name(); + while (auto c = static_cast(*ptr++)) + hash = (hash * 33) ^ c; + return hash; + } +}; + +struct type_equal_to { + bool operator()(const std::type_index &lhs, const std::type_index &rhs) const { + return lhs.name() == rhs.name() || std::strcmp(lhs.name(), rhs.name()) == 0; + } +}; +#endif + +template +using type_map = std::unordered_map; + +struct overload_hash { + inline size_t operator()(const std::pair& v) const { + size_t value = std::hash()(v.first); + value ^= std::hash()(v.second) + 0x9e3779b9 + (value<<6) + (value>>2); + return value; + } +}; + +/// Internal data structure used to track registered instances and types. +/// Whenever binary incompatible changes are made to this structure, +/// `PYBIND11_INTERNALS_VERSION` must be incremented. +struct internals { + type_map registered_types_cpp; // std::type_index -> pybind11's type information + std::unordered_map> registered_types_py; // PyTypeObject* -> base type_info(s) + std::unordered_multimap registered_instances; // void * -> instance* + std::unordered_set, overload_hash> inactive_overload_cache; + type_map> direct_conversions; + std::unordered_map> patients; + std::forward_list registered_exception_translators; + std::unordered_map shared_data; // Custom data to be shared across extensions + std::vector loader_patient_stack; // Used by `loader_life_support` + std::forward_list static_strings; // Stores the std::strings backing detail::c_str() + PyTypeObject *static_property_type; + PyTypeObject *default_metaclass; + PyObject *instance_base; +#if defined(WITH_THREAD) + PYBIND11_TLS_KEY_INIT(tstate); + PyInterpreterState *istate = nullptr; +#endif +}; + +/// Additional type information which does not fit into the PyTypeObject. +/// Changes to this struct also require bumping `PYBIND11_INTERNALS_VERSION`. +struct type_info { + PyTypeObject *type; + const std::type_info *cpptype; + size_t type_size, type_align, holder_size_in_ptrs; + void *(*operator_new)(size_t); + void (*init_instance)(instance *, const void *); + void (*dealloc)(value_and_holder &v_h); + std::vector implicit_conversions; + std::vector> implicit_casts; + std::vector *direct_conversions; + buffer_info *(*get_buffer)(PyObject *, void *) = nullptr; + void *get_buffer_data = nullptr; + void *(*module_local_load)(PyObject *, const type_info *) = nullptr; + /* A simple type never occurs as a (direct or indirect) parent + * of a class that makes use of multiple inheritance */ + bool simple_type : 1; + /* True if there is no multiple inheritance in this type's inheritance tree */ + bool simple_ancestors : 1; + /* for base vs derived holder_type checks */ + bool default_holder : 1; + /* true if this is a type registered with py::module_local */ + bool module_local : 1; +}; + +/// Tracks the `internals` and `type_info` ABI version independent of the main library version +#define PYBIND11_INTERNALS_VERSION 3 + +#if defined(_DEBUG) +# define PYBIND11_BUILD_TYPE "_debug" +#else +# define PYBIND11_BUILD_TYPE "" +#endif + +#if defined(WITH_THREAD) +# define PYBIND11_INTERNALS_KIND "" +#else +# define PYBIND11_INTERNALS_KIND "_without_thread" +#endif + +#define PYBIND11_INTERNALS_ID "__pybind11_internals_v" \ + PYBIND11_TOSTRING(PYBIND11_INTERNALS_VERSION) PYBIND11_INTERNALS_KIND PYBIND11_BUILD_TYPE "__" + +#define PYBIND11_MODULE_LOCAL_ID "__pybind11_module_local_v" \ + PYBIND11_TOSTRING(PYBIND11_INTERNALS_VERSION) PYBIND11_INTERNALS_KIND PYBIND11_BUILD_TYPE "__" + +/// Each module locally stores a pointer to the `internals` data. The data +/// itself is shared among modules with the same `PYBIND11_INTERNALS_ID`. +inline internals **&get_internals_pp() { + static internals **internals_pp = nullptr; + return internals_pp; +} + +/// Return a reference to the current `internals` data +PYBIND11_NOINLINE inline internals &get_internals() { + auto **&internals_pp = get_internals_pp(); + if (internals_pp && *internals_pp) + return **internals_pp; + + constexpr auto *id = PYBIND11_INTERNALS_ID; + auto builtins = handle(PyEval_GetBuiltins()); + if (builtins.contains(id) && isinstance(builtins[id])) { + internals_pp = static_cast(capsule(builtins[id])); + + // We loaded builtins through python's builtins, which means that our `error_already_set` + // and `builtin_exception` may be different local classes than the ones set up in the + // initial exception translator, below, so add another for our local exception classes. + // + // libstdc++ doesn't require this (types there are identified only by name) +#if !defined(__GLIBCXX__) + (*internals_pp)->registered_exception_translators.push_front( + [](std::exception_ptr p) -> void { + try { + if (p) std::rethrow_exception(p); + } catch (error_already_set &e) { e.restore(); return; + } catch (const builtin_exception &e) { e.set_error(); return; + } + } + ); +#endif + } else { + if (!internals_pp) internals_pp = new internals*(); + auto *&internals_ptr = *internals_pp; + internals_ptr = new internals(); +#if defined(WITH_THREAD) + PyEval_InitThreads(); + PyThreadState *tstate = PyThreadState_Get(); + #if PY_VERSION_HEX >= 0x03070000 + internals_ptr->tstate = PyThread_tss_alloc(); + if (!internals_ptr->tstate || PyThread_tss_create(internals_ptr->tstate)) + pybind11_fail("get_internals: could not successfully initialize the TSS key!"); + PyThread_tss_set(internals_ptr->tstate, tstate); + #else + internals_ptr->tstate = PyThread_create_key(); + if (internals_ptr->tstate == -1) + pybind11_fail("get_internals: could not successfully initialize the TLS key!"); + PyThread_set_key_value(internals_ptr->tstate, tstate); + #endif + internals_ptr->istate = tstate->interp; +#endif + builtins[id] = capsule(internals_pp); + internals_ptr->registered_exception_translators.push_front( + [](std::exception_ptr p) -> void { + try { + if (p) std::rethrow_exception(p); + } catch (error_already_set &e) { e.restore(); return; + } catch (const builtin_exception &e) { e.set_error(); return; + } catch (const std::bad_alloc &e) { PyErr_SetString(PyExc_MemoryError, e.what()); return; + } catch (const std::domain_error &e) { PyErr_SetString(PyExc_ValueError, e.what()); return; + } catch (const std::invalid_argument &e) { PyErr_SetString(PyExc_ValueError, e.what()); return; + } catch (const std::length_error &e) { PyErr_SetString(PyExc_ValueError, e.what()); return; + } catch (const std::out_of_range &e) { PyErr_SetString(PyExc_IndexError, e.what()); return; + } catch (const std::range_error &e) { PyErr_SetString(PyExc_ValueError, e.what()); return; + } catch (const std::exception &e) { PyErr_SetString(PyExc_RuntimeError, e.what()); return; + } catch (...) { + PyErr_SetString(PyExc_RuntimeError, "Caught an unknown exception!"); + return; + } + } + ); + internals_ptr->static_property_type = make_static_property_type(); + internals_ptr->default_metaclass = make_default_metaclass(); + internals_ptr->instance_base = make_object_base_type(internals_ptr->default_metaclass); + } + return **internals_pp; +} + +/// Works like `internals.registered_types_cpp`, but for module-local registered types: +inline type_map ®istered_local_types_cpp() { + static type_map locals{}; + return locals; +} + +/// Constructs a std::string with the given arguments, stores it in `internals`, and returns its +/// `c_str()`. Such strings objects have a long storage duration -- the internal strings are only +/// cleared when the program exits or after interpreter shutdown (when embedding), and so are +/// suitable for c-style strings needed by Python internals (such as PyTypeObject's tp_name). +template +const char *c_str(Args &&...args) { + auto &strings = get_internals().static_strings; + strings.emplace_front(std::forward(args)...); + return strings.front().c_str(); +} + +NAMESPACE_END(detail) + +/// Returns a named pointer that is shared among all extension modules (using the same +/// pybind11 version) running in the current interpreter. Names starting with underscores +/// are reserved for internal usage. Returns `nullptr` if no matching entry was found. +inline PYBIND11_NOINLINE void *get_shared_data(const std::string &name) { + auto &internals = detail::get_internals(); + auto it = internals.shared_data.find(name); + return it != internals.shared_data.end() ? it->second : nullptr; +} + +/// Set the shared data that can be later recovered by `get_shared_data()`. +inline PYBIND11_NOINLINE void *set_shared_data(const std::string &name, void *data) { + detail::get_internals().shared_data[name] = data; + return data; +} + +/// Returns a typed reference to a shared data entry (by using `get_shared_data()`) if +/// such entry exists. Otherwise, a new object of default-constructible type `T` is +/// added to the shared data under the given name and a reference to it is returned. +template +T &get_or_create_shared_data(const std::string &name) { + auto &internals = detail::get_internals(); + auto it = internals.shared_data.find(name); + T *ptr = (T *) (it != internals.shared_data.end() ? it->second : nullptr); + if (!ptr) { + ptr = new T(); + internals.shared_data[name] = ptr; + } + return *ptr; +} + +NAMESPACE_END(PYBIND11_NAMESPACE) diff --git a/wrap/python/pybind11/include/pybind11/detail/typeid.h b/wrap/python/pybind11/include/pybind11/detail/typeid.h new file mode 100644 index 000000000..9c8a4fc69 --- /dev/null +++ b/wrap/python/pybind11/include/pybind11/detail/typeid.h @@ -0,0 +1,55 @@ +/* + pybind11/detail/typeid.h: Compiler-independent access to type identifiers + + Copyright (c) 2016 Wenzel Jakob + + All rights reserved. Use of this source code is governed by a + BSD-style license that can be found in the LICENSE file. +*/ + +#pragma once + +#include +#include + +#if defined(__GNUG__) +#include +#endif + +#include "common.h" + +NAMESPACE_BEGIN(PYBIND11_NAMESPACE) +NAMESPACE_BEGIN(detail) +/// Erase all occurrences of a substring +inline void erase_all(std::string &string, const std::string &search) { + for (size_t pos = 0;;) { + pos = string.find(search, pos); + if (pos == std::string::npos) break; + string.erase(pos, search.length()); + } +} + +PYBIND11_NOINLINE inline void clean_type_id(std::string &name) { +#if defined(__GNUG__) + int status = 0; + std::unique_ptr res { + abi::__cxa_demangle(name.c_str(), nullptr, nullptr, &status), std::free }; + if (status == 0) + name = res.get(); +#else + detail::erase_all(name, "class "); + detail::erase_all(name, "struct "); + detail::erase_all(name, "enum "); +#endif + detail::erase_all(name, "pybind11::"); +} +NAMESPACE_END(detail) + +/// Return a string representation of a C++ type +template static std::string type_id() { + std::string name(typeid(T).name()); + detail::clean_type_id(name); + return name; +} + +NAMESPACE_END(PYBIND11_NAMESPACE) diff --git a/wrap/python/pybind11/include/pybind11/eigen.h b/wrap/python/pybind11/include/pybind11/eigen.h new file mode 100644 index 000000000..d963d9650 --- /dev/null +++ b/wrap/python/pybind11/include/pybind11/eigen.h @@ -0,0 +1,607 @@ +/* + pybind11/eigen.h: Transparent conversion for dense and sparse Eigen matrices + + Copyright (c) 2016 Wenzel Jakob + + All rights reserved. Use of this source code is governed by a + BSD-style license that can be found in the LICENSE file. +*/ + +#pragma once + +#include "numpy.h" + +#if defined(__INTEL_COMPILER) +# pragma warning(disable: 1682) // implicit conversion of a 64-bit integral type to a smaller integral type (potential portability problem) +#elif defined(__GNUG__) || defined(__clang__) +# pragma GCC diagnostic push +# pragma GCC diagnostic ignored "-Wconversion" +# pragma GCC diagnostic ignored "-Wdeprecated-declarations" +# ifdef __clang__ +// Eigen generates a bunch of implicit-copy-constructor-is-deprecated warnings with -Wdeprecated +// under Clang, so disable that warning here: +# pragma GCC diagnostic ignored "-Wdeprecated" +# endif +# if __GNUC__ >= 7 +# pragma GCC diagnostic ignored "-Wint-in-bool-context" +# endif +#endif + +#if defined(_MSC_VER) +# pragma warning(push) +# pragma warning(disable: 4127) // warning C4127: Conditional expression is constant +# pragma warning(disable: 4996) // warning C4996: std::unary_negate is deprecated in C++17 +#endif + +#include +#include + +// Eigen prior to 3.2.7 doesn't have proper move constructors--but worse, some classes get implicit +// move constructors that break things. We could detect this an explicitly copy, but an extra copy +// of matrices seems highly undesirable. +static_assert(EIGEN_VERSION_AT_LEAST(3,2,7), "Eigen support in pybind11 requires Eigen >= 3.2.7"); + +NAMESPACE_BEGIN(PYBIND11_NAMESPACE) + +// Provide a convenience alias for easier pass-by-ref usage with fully dynamic strides: +using EigenDStride = Eigen::Stride; +template using EigenDRef = Eigen::Ref; +template using EigenDMap = Eigen::Map; + +NAMESPACE_BEGIN(detail) + +#if EIGEN_VERSION_AT_LEAST(3,3,0) +using EigenIndex = Eigen::Index; +#else +using EigenIndex = EIGEN_DEFAULT_DENSE_INDEX_TYPE; +#endif + +// Matches Eigen::Map, Eigen::Ref, blocks, etc: +template using is_eigen_dense_map = all_of, std::is_base_of, T>>; +template using is_eigen_mutable_map = std::is_base_of, T>; +template using is_eigen_dense_plain = all_of>, is_template_base_of>; +template using is_eigen_sparse = is_template_base_of; +// Test for objects inheriting from EigenBase that aren't captured by the above. This +// basically covers anything that can be assigned to a dense matrix but that don't have a typical +// matrix data layout that can be copied from their .data(). For example, DiagonalMatrix and +// SelfAdjointView fall into this category. +template using is_eigen_other = all_of< + is_template_base_of, + negation, is_eigen_dense_plain, is_eigen_sparse>> +>; + +// Captures numpy/eigen conformability status (returned by EigenProps::conformable()): +template struct EigenConformable { + bool conformable = false; + EigenIndex rows = 0, cols = 0; + EigenDStride stride{0, 0}; // Only valid if negativestrides is false! + bool negativestrides = false; // If true, do not use stride! + + EigenConformable(bool fits = false) : conformable{fits} {} + // Matrix type: + EigenConformable(EigenIndex r, EigenIndex c, + EigenIndex rstride, EigenIndex cstride) : + conformable{true}, rows{r}, cols{c} { + // TODO: when Eigen bug #747 is fixed, remove the tests for non-negativity. http://eigen.tuxfamily.org/bz/show_bug.cgi?id=747 + if (rstride < 0 || cstride < 0) { + negativestrides = true; + } else { + stride = {EigenRowMajor ? rstride : cstride /* outer stride */, + EigenRowMajor ? cstride : rstride /* inner stride */ }; + } + } + // Vector type: + EigenConformable(EigenIndex r, EigenIndex c, EigenIndex stride) + : EigenConformable(r, c, r == 1 ? c*stride : stride, c == 1 ? r : r*stride) {} + + template bool stride_compatible() const { + // To have compatible strides, we need (on both dimensions) one of fully dynamic strides, + // matching strides, or a dimension size of 1 (in which case the stride value is irrelevant) + return + !negativestrides && + (props::inner_stride == Eigen::Dynamic || props::inner_stride == stride.inner() || + (EigenRowMajor ? cols : rows) == 1) && + (props::outer_stride == Eigen::Dynamic || props::outer_stride == stride.outer() || + (EigenRowMajor ? rows : cols) == 1); + } + operator bool() const { return conformable; } +}; + +template struct eigen_extract_stride { using type = Type; }; +template +struct eigen_extract_stride> { using type = StrideType; }; +template +struct eigen_extract_stride> { using type = StrideType; }; + +// Helper struct for extracting information from an Eigen type +template struct EigenProps { + using Type = Type_; + using Scalar = typename Type::Scalar; + using StrideType = typename eigen_extract_stride::type; + static constexpr EigenIndex + rows = Type::RowsAtCompileTime, + cols = Type::ColsAtCompileTime, + size = Type::SizeAtCompileTime; + static constexpr bool + row_major = Type::IsRowMajor, + vector = Type::IsVectorAtCompileTime, // At least one dimension has fixed size 1 + fixed_rows = rows != Eigen::Dynamic, + fixed_cols = cols != Eigen::Dynamic, + fixed = size != Eigen::Dynamic, // Fully-fixed size + dynamic = !fixed_rows && !fixed_cols; // Fully-dynamic size + + template using if_zero = std::integral_constant; + static constexpr EigenIndex inner_stride = if_zero::value, + outer_stride = if_zero::value; + static constexpr bool dynamic_stride = inner_stride == Eigen::Dynamic && outer_stride == Eigen::Dynamic; + static constexpr bool requires_row_major = !dynamic_stride && !vector && (row_major ? inner_stride : outer_stride) == 1; + static constexpr bool requires_col_major = !dynamic_stride && !vector && (row_major ? outer_stride : inner_stride) == 1; + + // Takes an input array and determines whether we can make it fit into the Eigen type. If + // the array is a vector, we attempt to fit it into either an Eigen 1xN or Nx1 vector + // (preferring the latter if it will fit in either, i.e. for a fully dynamic matrix type). + static EigenConformable conformable(const array &a) { + const auto dims = a.ndim(); + if (dims < 1 || dims > 2) + return false; + + if (dims == 2) { // Matrix type: require exact match (or dynamic) + + EigenIndex + np_rows = a.shape(0), + np_cols = a.shape(1), + np_rstride = a.strides(0) / static_cast(sizeof(Scalar)), + np_cstride = a.strides(1) / static_cast(sizeof(Scalar)); + if ((fixed_rows && np_rows != rows) || (fixed_cols && np_cols != cols)) + return false; + + return {np_rows, np_cols, np_rstride, np_cstride}; + } + + // Otherwise we're storing an n-vector. Only one of the strides will be used, but whichever + // is used, we want the (single) numpy stride value. + const EigenIndex n = a.shape(0), + stride = a.strides(0) / static_cast(sizeof(Scalar)); + + if (vector) { // Eigen type is a compile-time vector + if (fixed && size != n) + return false; // Vector size mismatch + return {rows == 1 ? 1 : n, cols == 1 ? 1 : n, stride}; + } + else if (fixed) { + // The type has a fixed size, but is not a vector: abort + return false; + } + else if (fixed_cols) { + // Since this isn't a vector, cols must be != 1. We allow this only if it exactly + // equals the number of elements (rows is Dynamic, and so 1 row is allowed). + if (cols != n) return false; + return {1, n, stride}; + } + else { + // Otherwise it's either fully dynamic, or column dynamic; both become a column vector + if (fixed_rows && rows != n) return false; + return {n, 1, stride}; + } + } + + static constexpr bool show_writeable = is_eigen_dense_map::value && is_eigen_mutable_map::value; + static constexpr bool show_order = is_eigen_dense_map::value; + static constexpr bool show_c_contiguous = show_order && requires_row_major; + static constexpr bool show_f_contiguous = !show_c_contiguous && show_order && requires_col_major; + + static constexpr auto descriptor = + _("numpy.ndarray[") + npy_format_descriptor::name + + _("[") + _(_<(size_t) rows>(), _("m")) + + _(", ") + _(_<(size_t) cols>(), _("n")) + + _("]") + + // For a reference type (e.g. Ref) we have other constraints that might need to be + // satisfied: writeable=True (for a mutable reference), and, depending on the map's stride + // options, possibly f_contiguous or c_contiguous. We include them in the descriptor output + // to provide some hint as to why a TypeError is occurring (otherwise it can be confusing to + // see that a function accepts a 'numpy.ndarray[float64[3,2]]' and an error message that you + // *gave* a numpy.ndarray of the right type and dimensions. + _(", flags.writeable", "") + + _(", flags.c_contiguous", "") + + _(", flags.f_contiguous", "") + + _("]"); +}; + +// Casts an Eigen type to numpy array. If given a base, the numpy array references the src data, +// otherwise it'll make a copy. writeable lets you turn off the writeable flag for the array. +template handle eigen_array_cast(typename props::Type const &src, handle base = handle(), bool writeable = true) { + constexpr ssize_t elem_size = sizeof(typename props::Scalar); + array a; + if (props::vector) + a = array({ src.size() }, { elem_size * src.innerStride() }, src.data(), base); + else + a = array({ src.rows(), src.cols() }, { elem_size * src.rowStride(), elem_size * src.colStride() }, + src.data(), base); + + if (!writeable) + array_proxy(a.ptr())->flags &= ~detail::npy_api::NPY_ARRAY_WRITEABLE_; + + return a.release(); +} + +// Takes an lvalue ref to some Eigen type and a (python) base object, creating a numpy array that +// reference the Eigen object's data with `base` as the python-registered base class (if omitted, +// the base will be set to None, and lifetime management is up to the caller). The numpy array is +// non-writeable if the given type is const. +template +handle eigen_ref_array(Type &src, handle parent = none()) { + // none here is to get past array's should-we-copy detection, which currently always + // copies when there is no base. Setting the base to None should be harmless. + return eigen_array_cast(src, parent, !std::is_const::value); +} + +// Takes a pointer to some dense, plain Eigen type, builds a capsule around it, then returns a numpy +// array that references the encapsulated data with a python-side reference to the capsule to tie +// its destruction to that of any dependent python objects. Const-ness is determined by whether or +// not the Type of the pointer given is const. +template ::value>> +handle eigen_encapsulate(Type *src) { + capsule base(src, [](void *o) { delete static_cast(o); }); + return eigen_ref_array(*src, base); +} + +// Type caster for regular, dense matrix types (e.g. MatrixXd), but not maps/refs/etc. of dense +// types. +template +struct type_caster::value>> { + using Scalar = typename Type::Scalar; + using props = EigenProps; + + bool load(handle src, bool convert) { + // If we're in no-convert mode, only load if given an array of the correct type + if (!convert && !isinstance>(src)) + return false; + + // Coerce into an array, but don't do type conversion yet; the copy below handles it. + auto buf = array::ensure(src); + + if (!buf) + return false; + + auto dims = buf.ndim(); + if (dims < 1 || dims > 2) + return false; + + auto fits = props::conformable(buf); + if (!fits) + return false; + + // Allocate the new type, then build a numpy reference into it + value = Type(fits.rows, fits.cols); + auto ref = reinterpret_steal(eigen_ref_array(value)); + if (dims == 1) ref = ref.squeeze(); + else if (ref.ndim() == 1) buf = buf.squeeze(); + + int result = detail::npy_api::get().PyArray_CopyInto_(ref.ptr(), buf.ptr()); + + if (result < 0) { // Copy failed! + PyErr_Clear(); + return false; + } + + return true; + } + +private: + + // Cast implementation + template + static handle cast_impl(CType *src, return_value_policy policy, handle parent) { + switch (policy) { + case return_value_policy::take_ownership: + case return_value_policy::automatic: + return eigen_encapsulate(src); + case return_value_policy::move: + return eigen_encapsulate(new CType(std::move(*src))); + case return_value_policy::copy: + return eigen_array_cast(*src); + case return_value_policy::reference: + case return_value_policy::automatic_reference: + return eigen_ref_array(*src); + case return_value_policy::reference_internal: + return eigen_ref_array(*src, parent); + default: + throw cast_error("unhandled return_value_policy: should not happen!"); + }; + } + +public: + + // Normal returned non-reference, non-const value: + static handle cast(Type &&src, return_value_policy /* policy */, handle parent) { + return cast_impl(&src, return_value_policy::move, parent); + } + // If you return a non-reference const, we mark the numpy array readonly: + static handle cast(const Type &&src, return_value_policy /* policy */, handle parent) { + return cast_impl(&src, return_value_policy::move, parent); + } + // lvalue reference return; default (automatic) becomes copy + static handle cast(Type &src, return_value_policy policy, handle parent) { + if (policy == return_value_policy::automatic || policy == return_value_policy::automatic_reference) + policy = return_value_policy::copy; + return cast_impl(&src, policy, parent); + } + // const lvalue reference return; default (automatic) becomes copy + static handle cast(const Type &src, return_value_policy policy, handle parent) { + if (policy == return_value_policy::automatic || policy == return_value_policy::automatic_reference) + policy = return_value_policy::copy; + return cast(&src, policy, parent); + } + // non-const pointer return + static handle cast(Type *src, return_value_policy policy, handle parent) { + return cast_impl(src, policy, parent); + } + // const pointer return + static handle cast(const Type *src, return_value_policy policy, handle parent) { + return cast_impl(src, policy, parent); + } + + static constexpr auto name = props::descriptor; + + operator Type*() { return &value; } + operator Type&() { return value; } + operator Type&&() && { return std::move(value); } + template using cast_op_type = movable_cast_op_type; + +private: + Type value; +}; + +// Base class for casting reference/map/block/etc. objects back to python. +template struct eigen_map_caster { +private: + using props = EigenProps; + +public: + + // Directly referencing a ref/map's data is a bit dangerous (whatever the map/ref points to has + // to stay around), but we'll allow it under the assumption that you know what you're doing (and + // have an appropriate keep_alive in place). We return a numpy array pointing directly at the + // ref's data (The numpy array ends up read-only if the ref was to a const matrix type.) Note + // that this means you need to ensure you don't destroy the object in some other way (e.g. with + // an appropriate keep_alive, or with a reference to a statically allocated matrix). + static handle cast(const MapType &src, return_value_policy policy, handle parent) { + switch (policy) { + case return_value_policy::copy: + return eigen_array_cast(src); + case return_value_policy::reference_internal: + return eigen_array_cast(src, parent, is_eigen_mutable_map::value); + case return_value_policy::reference: + case return_value_policy::automatic: + case return_value_policy::automatic_reference: + return eigen_array_cast(src, none(), is_eigen_mutable_map::value); + default: + // move, take_ownership don't make any sense for a ref/map: + pybind11_fail("Invalid return_value_policy for Eigen Map/Ref/Block type"); + } + } + + static constexpr auto name = props::descriptor; + + // Explicitly delete these: support python -> C++ conversion on these (i.e. these can be return + // types but not bound arguments). We still provide them (with an explicitly delete) so that + // you end up here if you try anyway. + bool load(handle, bool) = delete; + operator MapType() = delete; + template using cast_op_type = MapType; +}; + +// We can return any map-like object (but can only load Refs, specialized next): +template struct type_caster::value>> + : eigen_map_caster {}; + +// Loader for Ref<...> arguments. See the documentation for info on how to make this work without +// copying (it requires some extra effort in many cases). +template +struct type_caster< + Eigen::Ref, + enable_if_t>::value> +> : public eigen_map_caster> { +private: + using Type = Eigen::Ref; + using props = EigenProps; + using Scalar = typename props::Scalar; + using MapType = Eigen::Map; + using Array = array_t; + static constexpr bool need_writeable = is_eigen_mutable_map::value; + // Delay construction (these have no default constructor) + std::unique_ptr map; + std::unique_ptr ref; + // Our array. When possible, this is just a numpy array pointing to the source data, but + // sometimes we can't avoid copying (e.g. input is not a numpy array at all, has an incompatible + // layout, or is an array of a type that needs to be converted). Using a numpy temporary + // (rather than an Eigen temporary) saves an extra copy when we need both type conversion and + // storage order conversion. (Note that we refuse to use this temporary copy when loading an + // argument for a Ref with M non-const, i.e. a read-write reference). + Array copy_or_ref; +public: + bool load(handle src, bool convert) { + // First check whether what we have is already an array of the right type. If not, we can't + // avoid a copy (because the copy is also going to do type conversion). + bool need_copy = !isinstance(src); + + EigenConformable fits; + if (!need_copy) { + // We don't need a converting copy, but we also need to check whether the strides are + // compatible with the Ref's stride requirements + Array aref = reinterpret_borrow(src); + + if (aref && (!need_writeable || aref.writeable())) { + fits = props::conformable(aref); + if (!fits) return false; // Incompatible dimensions + if (!fits.template stride_compatible()) + need_copy = true; + else + copy_or_ref = std::move(aref); + } + else { + need_copy = true; + } + } + + if (need_copy) { + // We need to copy: If we need a mutable reference, or we're not supposed to convert + // (either because we're in the no-convert overload pass, or because we're explicitly + // instructed not to copy (via `py::arg().noconvert()`) we have to fail loading. + if (!convert || need_writeable) return false; + + Array copy = Array::ensure(src); + if (!copy) return false; + fits = props::conformable(copy); + if (!fits || !fits.template stride_compatible()) + return false; + copy_or_ref = std::move(copy); + loader_life_support::add_patient(copy_or_ref); + } + + ref.reset(); + map.reset(new MapType(data(copy_or_ref), fits.rows, fits.cols, make_stride(fits.stride.outer(), fits.stride.inner()))); + ref.reset(new Type(*map)); + + return true; + } + + operator Type*() { return ref.get(); } + operator Type&() { return *ref; } + template using cast_op_type = pybind11::detail::cast_op_type<_T>; + +private: + template ::value, int> = 0> + Scalar *data(Array &a) { return a.mutable_data(); } + + template ::value, int> = 0> + const Scalar *data(Array &a) { return a.data(); } + + // Attempt to figure out a constructor of `Stride` that will work. + // If both strides are fixed, use a default constructor: + template using stride_ctor_default = bool_constant< + S::InnerStrideAtCompileTime != Eigen::Dynamic && S::OuterStrideAtCompileTime != Eigen::Dynamic && + std::is_default_constructible::value>; + // Otherwise, if there is a two-index constructor, assume it is (outer,inner) like + // Eigen::Stride, and use it: + template using stride_ctor_dual = bool_constant< + !stride_ctor_default::value && std::is_constructible::value>; + // Otherwise, if there is a one-index constructor, and just one of the strides is dynamic, use + // it (passing whichever stride is dynamic). + template using stride_ctor_outer = bool_constant< + !any_of, stride_ctor_dual>::value && + S::OuterStrideAtCompileTime == Eigen::Dynamic && S::InnerStrideAtCompileTime != Eigen::Dynamic && + std::is_constructible::value>; + template using stride_ctor_inner = bool_constant< + !any_of, stride_ctor_dual>::value && + S::InnerStrideAtCompileTime == Eigen::Dynamic && S::OuterStrideAtCompileTime != Eigen::Dynamic && + std::is_constructible::value>; + + template ::value, int> = 0> + static S make_stride(EigenIndex, EigenIndex) { return S(); } + template ::value, int> = 0> + static S make_stride(EigenIndex outer, EigenIndex inner) { return S(outer, inner); } + template ::value, int> = 0> + static S make_stride(EigenIndex outer, EigenIndex) { return S(outer); } + template ::value, int> = 0> + static S make_stride(EigenIndex, EigenIndex inner) { return S(inner); } + +}; + +// type_caster for special matrix types (e.g. DiagonalMatrix), which are EigenBase, but not +// EigenDense (i.e. they don't have a data(), at least not with the usual matrix layout). +// load() is not supported, but we can cast them into the python domain by first copying to a +// regular Eigen::Matrix, then casting that. +template +struct type_caster::value>> { +protected: + using Matrix = Eigen::Matrix; + using props = EigenProps; +public: + static handle cast(const Type &src, return_value_policy /* policy */, handle /* parent */) { + handle h = eigen_encapsulate(new Matrix(src)); + return h; + } + static handle cast(const Type *src, return_value_policy policy, handle parent) { return cast(*src, policy, parent); } + + static constexpr auto name = props::descriptor; + + // Explicitly delete these: support python -> C++ conversion on these (i.e. these can be return + // types but not bound arguments). We still provide them (with an explicitly delete) so that + // you end up here if you try anyway. + bool load(handle, bool) = delete; + operator Type() = delete; + template using cast_op_type = Type; +}; + +template +struct type_caster::value>> { + typedef typename Type::Scalar Scalar; + typedef remove_reference_t().outerIndexPtr())> StorageIndex; + typedef typename Type::Index Index; + static constexpr bool rowMajor = Type::IsRowMajor; + + bool load(handle src, bool) { + if (!src) + return false; + + auto obj = reinterpret_borrow(src); + object sparse_module = module::import("scipy.sparse"); + object matrix_type = sparse_module.attr( + rowMajor ? "csr_matrix" : "csc_matrix"); + + if (!obj.get_type().is(matrix_type)) { + try { + obj = matrix_type(obj); + } catch (const error_already_set &) { + return false; + } + } + + auto values = array_t((object) obj.attr("data")); + auto innerIndices = array_t((object) obj.attr("indices")); + auto outerIndices = array_t((object) obj.attr("indptr")); + auto shape = pybind11::tuple((pybind11::object) obj.attr("shape")); + auto nnz = obj.attr("nnz").cast(); + + if (!values || !innerIndices || !outerIndices) + return false; + + value = Eigen::MappedSparseMatrix( + shape[0].cast(), shape[1].cast(), nnz, + outerIndices.mutable_data(), innerIndices.mutable_data(), values.mutable_data()); + + return true; + } + + static handle cast(const Type &src, return_value_policy /* policy */, handle /* parent */) { + const_cast(src).makeCompressed(); + + object matrix_type = module::import("scipy.sparse").attr( + rowMajor ? "csr_matrix" : "csc_matrix"); + + array data(src.nonZeros(), src.valuePtr()); + array outerIndices((rowMajor ? src.rows() : src.cols()) + 1, src.outerIndexPtr()); + array innerIndices(src.nonZeros(), src.innerIndexPtr()); + + return matrix_type( + std::make_tuple(data, innerIndices, outerIndices), + std::make_pair(src.rows(), src.cols()) + ).release(); + } + + PYBIND11_TYPE_CASTER(Type, _<(Type::IsRowMajor) != 0>("scipy.sparse.csr_matrix[", "scipy.sparse.csc_matrix[") + + npy_format_descriptor::name + _("]")); +}; + +NAMESPACE_END(detail) +NAMESPACE_END(PYBIND11_NAMESPACE) + +#if defined(__GNUG__) || defined(__clang__) +# pragma GCC diagnostic pop +#elif defined(_MSC_VER) +# pragma warning(pop) +#endif diff --git a/wrap/python/pybind11/include/pybind11/embed.h b/wrap/python/pybind11/include/pybind11/embed.h new file mode 100644 index 000000000..72655885e --- /dev/null +++ b/wrap/python/pybind11/include/pybind11/embed.h @@ -0,0 +1,200 @@ +/* + pybind11/embed.h: Support for embedding the interpreter + + Copyright (c) 2017 Wenzel Jakob + + All rights reserved. Use of this source code is governed by a + BSD-style license that can be found in the LICENSE file. +*/ + +#pragma once + +#include "pybind11.h" +#include "eval.h" + +#if defined(PYPY_VERSION) +# error Embedding the interpreter is not supported with PyPy +#endif + +#if PY_MAJOR_VERSION >= 3 +# define PYBIND11_EMBEDDED_MODULE_IMPL(name) \ + extern "C" PyObject *pybind11_init_impl_##name() { \ + return pybind11_init_wrapper_##name(); \ + } +#else +# define PYBIND11_EMBEDDED_MODULE_IMPL(name) \ + extern "C" void pybind11_init_impl_##name() { \ + pybind11_init_wrapper_##name(); \ + } +#endif + +/** \rst + Add a new module to the table of builtins for the interpreter. Must be + defined in global scope. The first macro parameter is the name of the + module (without quotes). The second parameter is the variable which will + be used as the interface to add functions and classes to the module. + + .. code-block:: cpp + + PYBIND11_EMBEDDED_MODULE(example, m) { + // ... initialize functions and classes here + m.def("foo", []() { + return "Hello, World!"; + }); + } + \endrst */ +#define PYBIND11_EMBEDDED_MODULE(name, variable) \ + static void PYBIND11_CONCAT(pybind11_init_, name)(pybind11::module &); \ + static PyObject PYBIND11_CONCAT(*pybind11_init_wrapper_, name)() { \ + auto m = pybind11::module(PYBIND11_TOSTRING(name)); \ + try { \ + PYBIND11_CONCAT(pybind11_init_, name)(m); \ + return m.ptr(); \ + } catch (pybind11::error_already_set &e) { \ + PyErr_SetString(PyExc_ImportError, e.what()); \ + return nullptr; \ + } catch (const std::exception &e) { \ + PyErr_SetString(PyExc_ImportError, e.what()); \ + return nullptr; \ + } \ + } \ + PYBIND11_EMBEDDED_MODULE_IMPL(name) \ + pybind11::detail::embedded_module name(PYBIND11_TOSTRING(name), \ + PYBIND11_CONCAT(pybind11_init_impl_, name)); \ + void PYBIND11_CONCAT(pybind11_init_, name)(pybind11::module &variable) + + +NAMESPACE_BEGIN(PYBIND11_NAMESPACE) +NAMESPACE_BEGIN(detail) + +/// Python 2.7/3.x compatible version of `PyImport_AppendInittab` and error checks. +struct embedded_module { +#if PY_MAJOR_VERSION >= 3 + using init_t = PyObject *(*)(); +#else + using init_t = void (*)(); +#endif + embedded_module(const char *name, init_t init) { + if (Py_IsInitialized()) + pybind11_fail("Can't add new modules after the interpreter has been initialized"); + + auto result = PyImport_AppendInittab(name, init); + if (result == -1) + pybind11_fail("Insufficient memory to add a new module"); + } +}; + +NAMESPACE_END(detail) + +/** \rst + Initialize the Python interpreter. No other pybind11 or CPython API functions can be + called before this is done; with the exception of `PYBIND11_EMBEDDED_MODULE`. The + optional parameter can be used to skip the registration of signal handlers (see the + `Python documentation`_ for details). Calling this function again after the interpreter + has already been initialized is a fatal error. + + If initializing the Python interpreter fails, then the program is terminated. (This + is controlled by the CPython runtime and is an exception to pybind11's normal behavior + of throwing exceptions on errors.) + + .. _Python documentation: https://docs.python.org/3/c-api/init.html#c.Py_InitializeEx + \endrst */ +inline void initialize_interpreter(bool init_signal_handlers = true) { + if (Py_IsInitialized()) + pybind11_fail("The interpreter is already running"); + + Py_InitializeEx(init_signal_handlers ? 1 : 0); + + // Make .py files in the working directory available by default + module::import("sys").attr("path").cast().append("."); +} + +/** \rst + Shut down the Python interpreter. No pybind11 or CPython API functions can be called + after this. In addition, pybind11 objects must not outlive the interpreter: + + .. code-block:: cpp + + { // BAD + py::initialize_interpreter(); + auto hello = py::str("Hello, World!"); + py::finalize_interpreter(); + } // <-- BOOM, hello's destructor is called after interpreter shutdown + + { // GOOD + py::initialize_interpreter(); + { // scoped + auto hello = py::str("Hello, World!"); + } // <-- OK, hello is cleaned up properly + py::finalize_interpreter(); + } + + { // BETTER + py::scoped_interpreter guard{}; + auto hello = py::str("Hello, World!"); + } + + .. warning:: + + The interpreter can be restarted by calling `initialize_interpreter` again. + Modules created using pybind11 can be safely re-initialized. However, Python + itself cannot completely unload binary extension modules and there are several + caveats with regard to interpreter restarting. All the details can be found + in the CPython documentation. In short, not all interpreter memory may be + freed, either due to reference cycles or user-created global data. + + \endrst */ +inline void finalize_interpreter() { + handle builtins(PyEval_GetBuiltins()); + const char *id = PYBIND11_INTERNALS_ID; + + // Get the internals pointer (without creating it if it doesn't exist). It's possible for the + // internals to be created during Py_Finalize() (e.g. if a py::capsule calls `get_internals()` + // during destruction), so we get the pointer-pointer here and check it after Py_Finalize(). + detail::internals **internals_ptr_ptr = detail::get_internals_pp(); + // It could also be stashed in builtins, so look there too: + if (builtins.contains(id) && isinstance(builtins[id])) + internals_ptr_ptr = capsule(builtins[id]); + + Py_Finalize(); + + if (internals_ptr_ptr) { + delete *internals_ptr_ptr; + *internals_ptr_ptr = nullptr; + } +} + +/** \rst + Scope guard version of `initialize_interpreter` and `finalize_interpreter`. + This a move-only guard and only a single instance can exist. + + .. code-block:: cpp + + #include + + int main() { + py::scoped_interpreter guard{}; + py::print(Hello, World!); + } // <-- interpreter shutdown + \endrst */ +class scoped_interpreter { +public: + scoped_interpreter(bool init_signal_handlers = true) { + initialize_interpreter(init_signal_handlers); + } + + scoped_interpreter(const scoped_interpreter &) = delete; + scoped_interpreter(scoped_interpreter &&other) noexcept { other.is_valid = false; } + scoped_interpreter &operator=(const scoped_interpreter &) = delete; + scoped_interpreter &operator=(scoped_interpreter &&) = delete; + + ~scoped_interpreter() { + if (is_valid) + finalize_interpreter(); + } + +private: + bool is_valid = true; +}; + +NAMESPACE_END(PYBIND11_NAMESPACE) diff --git a/wrap/python/pybind11/include/pybind11/eval.h b/wrap/python/pybind11/include/pybind11/eval.h new file mode 100644 index 000000000..ea85ba1db --- /dev/null +++ b/wrap/python/pybind11/include/pybind11/eval.h @@ -0,0 +1,117 @@ +/* + pybind11/exec.h: Support for evaluating Python expressions and statements + from strings and files + + Copyright (c) 2016 Klemens Morgenstern and + Wenzel Jakob + + All rights reserved. Use of this source code is governed by a + BSD-style license that can be found in the LICENSE file. +*/ + +#pragma once + +#include "pybind11.h" + +NAMESPACE_BEGIN(PYBIND11_NAMESPACE) + +enum eval_mode { + /// Evaluate a string containing an isolated expression + eval_expr, + + /// Evaluate a string containing a single statement. Returns \c none + eval_single_statement, + + /// Evaluate a string containing a sequence of statement. Returns \c none + eval_statements +}; + +template +object eval(str expr, object global = globals(), object local = object()) { + if (!local) + local = global; + + /* PyRun_String does not accept a PyObject / encoding specifier, + this seems to be the only alternative */ + std::string buffer = "# -*- coding: utf-8 -*-\n" + (std::string) expr; + + int start; + switch (mode) { + case eval_expr: start = Py_eval_input; break; + case eval_single_statement: start = Py_single_input; break; + case eval_statements: start = Py_file_input; break; + default: pybind11_fail("invalid evaluation mode"); + } + + PyObject *result = PyRun_String(buffer.c_str(), start, global.ptr(), local.ptr()); + if (!result) + throw error_already_set(); + return reinterpret_steal(result); +} + +template +object eval(const char (&s)[N], object global = globals(), object local = object()) { + /* Support raw string literals by removing common leading whitespace */ + auto expr = (s[0] == '\n') ? str(module::import("textwrap").attr("dedent")(s)) + : str(s); + return eval(expr, global, local); +} + +inline void exec(str expr, object global = globals(), object local = object()) { + eval(expr, global, local); +} + +template +void exec(const char (&s)[N], object global = globals(), object local = object()) { + eval(s, global, local); +} + +template +object eval_file(str fname, object global = globals(), object local = object()) { + if (!local) + local = global; + + int start; + switch (mode) { + case eval_expr: start = Py_eval_input; break; + case eval_single_statement: start = Py_single_input; break; + case eval_statements: start = Py_file_input; break; + default: pybind11_fail("invalid evaluation mode"); + } + + int closeFile = 1; + std::string fname_str = (std::string) fname; +#if PY_VERSION_HEX >= 0x03040000 + FILE *f = _Py_fopen_obj(fname.ptr(), "r"); +#elif PY_VERSION_HEX >= 0x03000000 + FILE *f = _Py_fopen(fname.ptr(), "r"); +#else + /* No unicode support in open() :( */ + auto fobj = reinterpret_steal(PyFile_FromString( + const_cast(fname_str.c_str()), + const_cast("r"))); + FILE *f = nullptr; + if (fobj) + f = PyFile_AsFile(fobj.ptr()); + closeFile = 0; +#endif + if (!f) { + PyErr_Clear(); + pybind11_fail("File \"" + fname_str + "\" could not be opened!"); + } + +#if PY_VERSION_HEX < 0x03000000 && defined(PYPY_VERSION) + PyObject *result = PyRun_File(f, fname_str.c_str(), start, global.ptr(), + local.ptr()); + (void) closeFile; +#else + PyObject *result = PyRun_FileEx(f, fname_str.c_str(), start, global.ptr(), + local.ptr(), closeFile); +#endif + + if (!result) + throw error_already_set(); + return reinterpret_steal(result); +} + +NAMESPACE_END(PYBIND11_NAMESPACE) diff --git a/wrap/python/pybind11/include/pybind11/functional.h b/wrap/python/pybind11/include/pybind11/functional.h new file mode 100644 index 000000000..7a0988ab0 --- /dev/null +++ b/wrap/python/pybind11/include/pybind11/functional.h @@ -0,0 +1,94 @@ +/* + pybind11/functional.h: std::function<> support + + Copyright (c) 2016 Wenzel Jakob + + All rights reserved. Use of this source code is governed by a + BSD-style license that can be found in the LICENSE file. +*/ + +#pragma once + +#include "pybind11.h" +#include + +NAMESPACE_BEGIN(PYBIND11_NAMESPACE) +NAMESPACE_BEGIN(detail) + +template +struct type_caster> { + using type = std::function; + using retval_type = conditional_t::value, void_type, Return>; + using function_type = Return (*) (Args...); + +public: + bool load(handle src, bool convert) { + if (src.is_none()) { + // Defer accepting None to other overloads (if we aren't in convert mode): + if (!convert) return false; + return true; + } + + if (!isinstance(src)) + return false; + + auto func = reinterpret_borrow(src); + + /* + When passing a C++ function as an argument to another C++ + function via Python, every function call would normally involve + a full C++ -> Python -> C++ roundtrip, which can be prohibitive. + Here, we try to at least detect the case where the function is + stateless (i.e. function pointer or lambda function without + captured variables), in which case the roundtrip can be avoided. + */ + if (auto cfunc = func.cpp_function()) { + auto c = reinterpret_borrow(PyCFunction_GET_SELF(cfunc.ptr())); + auto rec = (function_record *) c; + + if (rec && rec->is_stateless && + same_type(typeid(function_type), *reinterpret_cast(rec->data[1]))) { + struct capture { function_type f; }; + value = ((capture *) &rec->data)->f; + return true; + } + } + + // ensure GIL is held during functor destruction + struct func_handle { + function f; + func_handle(function&& f_) : f(std::move(f_)) {} + func_handle(const func_handle&) = default; + ~func_handle() { + gil_scoped_acquire acq; + function kill_f(std::move(f)); + } + }; + + value = [hfunc = func_handle(std::move(func))](Args... args) -> Return { + gil_scoped_acquire acq; + object retval(hfunc.f(std::forward(args)...)); + /* Visual studio 2015 parser issue: need parentheses around this expression */ + return (retval.template cast()); + }; + return true; + } + + template + static handle cast(Func &&f_, return_value_policy policy, handle /* parent */) { + if (!f_) + return none().inc_ref(); + + auto result = f_.template target(); + if (result) + return cpp_function(*result, policy).release(); + else + return cpp_function(std::forward(f_), policy).release(); + } + + PYBIND11_TYPE_CASTER(type, _("Callable[[") + concat(make_caster::name...) + _("], ") + + make_caster::name + _("]")); +}; + +NAMESPACE_END(detail) +NAMESPACE_END(PYBIND11_NAMESPACE) diff --git a/wrap/python/pybind11/include/pybind11/iostream.h b/wrap/python/pybind11/include/pybind11/iostream.h new file mode 100644 index 000000000..72baef8fd --- /dev/null +++ b/wrap/python/pybind11/include/pybind11/iostream.h @@ -0,0 +1,207 @@ +/* + pybind11/iostream.h -- Tools to assist with redirecting cout and cerr to Python + + Copyright (c) 2017 Henry F. Schreiner + + All rights reserved. Use of this source code is governed by a + BSD-style license that can be found in the LICENSE file. +*/ + +#pragma once + +#include "pybind11.h" + +#include +#include +#include +#include +#include + +NAMESPACE_BEGIN(PYBIND11_NAMESPACE) +NAMESPACE_BEGIN(detail) + +// Buffer that writes to Python instead of C++ +class pythonbuf : public std::streambuf { +private: + using traits_type = std::streambuf::traits_type; + + const size_t buf_size; + std::unique_ptr d_buffer; + object pywrite; + object pyflush; + + int overflow(int c) { + if (!traits_type::eq_int_type(c, traits_type::eof())) { + *pptr() = traits_type::to_char_type(c); + pbump(1); + } + return sync() == 0 ? traits_type::not_eof(c) : traits_type::eof(); + } + + int sync() { + if (pbase() != pptr()) { + // This subtraction cannot be negative, so dropping the sign + str line(pbase(), static_cast(pptr() - pbase())); + + { + gil_scoped_acquire tmp; + pywrite(line); + pyflush(); + } + + setp(pbase(), epptr()); + } + return 0; + } + +public: + + pythonbuf(object pyostream, size_t buffer_size = 1024) + : buf_size(buffer_size), + d_buffer(new char[buf_size]), + pywrite(pyostream.attr("write")), + pyflush(pyostream.attr("flush")) { + setp(d_buffer.get(), d_buffer.get() + buf_size - 1); + } + + /// Sync before destroy + ~pythonbuf() { + sync(); + } +}; + +NAMESPACE_END(detail) + + +/** \rst + This a move-only guard that redirects output. + + .. code-block:: cpp + + #include + + ... + + { + py::scoped_ostream_redirect output; + std::cout << "Hello, World!"; // Python stdout + } // <-- return std::cout to normal + + You can explicitly pass the c++ stream and the python object, + for example to guard stderr instead. + + .. code-block:: cpp + + { + py::scoped_ostream_redirect output{std::cerr, py::module::import("sys").attr("stderr")}; + std::cerr << "Hello, World!"; + } + \endrst */ +class scoped_ostream_redirect { +protected: + std::streambuf *old; + std::ostream &costream; + detail::pythonbuf buffer; + +public: + scoped_ostream_redirect( + std::ostream &costream = std::cout, + object pyostream = module::import("sys").attr("stdout")) + : costream(costream), buffer(pyostream) { + old = costream.rdbuf(&buffer); + } + + ~scoped_ostream_redirect() { + costream.rdbuf(old); + } + + scoped_ostream_redirect(const scoped_ostream_redirect &) = delete; + scoped_ostream_redirect(scoped_ostream_redirect &&other) = default; + scoped_ostream_redirect &operator=(const scoped_ostream_redirect &) = delete; + scoped_ostream_redirect &operator=(scoped_ostream_redirect &&) = delete; +}; + + +/** \rst + Like `scoped_ostream_redirect`, but redirects cerr by default. This class + is provided primary to make ``py::call_guard`` easier to make. + + .. code-block:: cpp + + m.def("noisy_func", &noisy_func, + py::call_guard()); + +\endrst */ +class scoped_estream_redirect : public scoped_ostream_redirect { +public: + scoped_estream_redirect( + std::ostream &costream = std::cerr, + object pyostream = module::import("sys").attr("stderr")) + : scoped_ostream_redirect(costream,pyostream) {} +}; + + +NAMESPACE_BEGIN(detail) + +// Class to redirect output as a context manager. C++ backend. +class OstreamRedirect { + bool do_stdout_; + bool do_stderr_; + std::unique_ptr redirect_stdout; + std::unique_ptr redirect_stderr; + +public: + OstreamRedirect(bool do_stdout = true, bool do_stderr = true) + : do_stdout_(do_stdout), do_stderr_(do_stderr) {} + + void enter() { + if (do_stdout_) + redirect_stdout.reset(new scoped_ostream_redirect()); + if (do_stderr_) + redirect_stderr.reset(new scoped_estream_redirect()); + } + + void exit() { + redirect_stdout.reset(); + redirect_stderr.reset(); + } +}; + +NAMESPACE_END(detail) + +/** \rst + This is a helper function to add a C++ redirect context manager to Python + instead of using a C++ guard. To use it, add the following to your binding code: + + .. code-block:: cpp + + #include + + ... + + py::add_ostream_redirect(m, "ostream_redirect"); + + You now have a Python context manager that redirects your output: + + .. code-block:: python + + with m.ostream_redirect(): + m.print_to_cout_function() + + This manager can optionally be told which streams to operate on: + + .. code-block:: python + + with m.ostream_redirect(stdout=true, stderr=true): + m.noisy_function_with_error_printing() + + \endrst */ +inline class_ add_ostream_redirect(module m, std::string name = "ostream_redirect") { + return class_(m, name.c_str(), module_local()) + .def(init(), arg("stdout")=true, arg("stderr")=true) + .def("__enter__", &detail::OstreamRedirect::enter) + .def("__exit__", [](detail::OstreamRedirect &self_, args) { self_.exit(); }); +} + +NAMESPACE_END(PYBIND11_NAMESPACE) diff --git a/wrap/python/pybind11/include/pybind11/numpy.h b/wrap/python/pybind11/include/pybind11/numpy.h new file mode 100644 index 000000000..b2a02e024 --- /dev/null +++ b/wrap/python/pybind11/include/pybind11/numpy.h @@ -0,0 +1,1610 @@ +/* + pybind11/numpy.h: Basic NumPy support, vectorize() wrapper + + Copyright (c) 2016 Wenzel Jakob + + All rights reserved. Use of this source code is governed by a + BSD-style license that can be found in the LICENSE file. +*/ + +#pragma once + +#include "pybind11.h" +#include "complex.h" +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#if defined(_MSC_VER) +# pragma warning(push) +# pragma warning(disable: 4127) // warning C4127: Conditional expression is constant +#endif + +/* This will be true on all flat address space platforms and allows us to reduce the + whole npy_intp / ssize_t / Py_intptr_t business down to just ssize_t for all size + and dimension types (e.g. shape, strides, indexing), instead of inflicting this + upon the library user. */ +static_assert(sizeof(ssize_t) == sizeof(Py_intptr_t), "ssize_t != Py_intptr_t"); + +NAMESPACE_BEGIN(PYBIND11_NAMESPACE) + +class array; // Forward declaration + +NAMESPACE_BEGIN(detail) +template struct npy_format_descriptor; + +struct PyArrayDescr_Proxy { + PyObject_HEAD + PyObject *typeobj; + char kind; + char type; + char byteorder; + char flags; + int type_num; + int elsize; + int alignment; + char *subarray; + PyObject *fields; + PyObject *names; +}; + +struct PyArray_Proxy { + PyObject_HEAD + char *data; + int nd; + ssize_t *dimensions; + ssize_t *strides; + PyObject *base; + PyObject *descr; + int flags; +}; + +struct PyVoidScalarObject_Proxy { + PyObject_VAR_HEAD + char *obval; + PyArrayDescr_Proxy *descr; + int flags; + PyObject *base; +}; + +struct numpy_type_info { + PyObject* dtype_ptr; + std::string format_str; +}; + +struct numpy_internals { + std::unordered_map registered_dtypes; + + numpy_type_info *get_type_info(const std::type_info& tinfo, bool throw_if_missing = true) { + auto it = registered_dtypes.find(std::type_index(tinfo)); + if (it != registered_dtypes.end()) + return &(it->second); + if (throw_if_missing) + pybind11_fail(std::string("NumPy type info missing for ") + tinfo.name()); + return nullptr; + } + + template numpy_type_info *get_type_info(bool throw_if_missing = true) { + return get_type_info(typeid(typename std::remove_cv::type), throw_if_missing); + } +}; + +inline PYBIND11_NOINLINE void load_numpy_internals(numpy_internals* &ptr) { + ptr = &get_or_create_shared_data("_numpy_internals"); +} + +inline numpy_internals& get_numpy_internals() { + static numpy_internals* ptr = nullptr; + if (!ptr) + load_numpy_internals(ptr); + return *ptr; +} + +struct npy_api { + enum constants { + NPY_ARRAY_C_CONTIGUOUS_ = 0x0001, + NPY_ARRAY_F_CONTIGUOUS_ = 0x0002, + NPY_ARRAY_OWNDATA_ = 0x0004, + NPY_ARRAY_FORCECAST_ = 0x0010, + NPY_ARRAY_ENSUREARRAY_ = 0x0040, + NPY_ARRAY_ALIGNED_ = 0x0100, + NPY_ARRAY_WRITEABLE_ = 0x0400, + NPY_BOOL_ = 0, + NPY_BYTE_, NPY_UBYTE_, + NPY_SHORT_, NPY_USHORT_, + NPY_INT_, NPY_UINT_, + NPY_LONG_, NPY_ULONG_, + NPY_LONGLONG_, NPY_ULONGLONG_, + NPY_FLOAT_, NPY_DOUBLE_, NPY_LONGDOUBLE_, + NPY_CFLOAT_, NPY_CDOUBLE_, NPY_CLONGDOUBLE_, + NPY_OBJECT_ = 17, + NPY_STRING_, NPY_UNICODE_, NPY_VOID_ + }; + + typedef struct { + Py_intptr_t *ptr; + int len; + } PyArray_Dims; + + static npy_api& get() { + static npy_api api = lookup(); + return api; + } + + bool PyArray_Check_(PyObject *obj) const { + return (bool) PyObject_TypeCheck(obj, PyArray_Type_); + } + bool PyArrayDescr_Check_(PyObject *obj) const { + return (bool) PyObject_TypeCheck(obj, PyArrayDescr_Type_); + } + + unsigned int (*PyArray_GetNDArrayCFeatureVersion_)(); + PyObject *(*PyArray_DescrFromType_)(int); + PyObject *(*PyArray_NewFromDescr_) + (PyTypeObject *, PyObject *, int, Py_intptr_t *, + Py_intptr_t *, void *, int, PyObject *); + PyObject *(*PyArray_DescrNewFromType_)(int); + int (*PyArray_CopyInto_)(PyObject *, PyObject *); + PyObject *(*PyArray_NewCopy_)(PyObject *, int); + PyTypeObject *PyArray_Type_; + PyTypeObject *PyVoidArrType_Type_; + PyTypeObject *PyArrayDescr_Type_; + PyObject *(*PyArray_DescrFromScalar_)(PyObject *); + PyObject *(*PyArray_FromAny_) (PyObject *, PyObject *, int, int, int, PyObject *); + int (*PyArray_DescrConverter_) (PyObject *, PyObject **); + bool (*PyArray_EquivTypes_) (PyObject *, PyObject *); + int (*PyArray_GetArrayParamsFromObject_)(PyObject *, PyObject *, char, PyObject **, int *, + Py_ssize_t *, PyObject **, PyObject *); + PyObject *(*PyArray_Squeeze_)(PyObject *); + int (*PyArray_SetBaseObject_)(PyObject *, PyObject *); + PyObject* (*PyArray_Resize_)(PyObject*, PyArray_Dims*, int, int); +private: + enum functions { + API_PyArray_GetNDArrayCFeatureVersion = 211, + API_PyArray_Type = 2, + API_PyArrayDescr_Type = 3, + API_PyVoidArrType_Type = 39, + API_PyArray_DescrFromType = 45, + API_PyArray_DescrFromScalar = 57, + API_PyArray_FromAny = 69, + API_PyArray_Resize = 80, + API_PyArray_CopyInto = 82, + API_PyArray_NewCopy = 85, + API_PyArray_NewFromDescr = 94, + API_PyArray_DescrNewFromType = 9, + API_PyArray_DescrConverter = 174, + API_PyArray_EquivTypes = 182, + API_PyArray_GetArrayParamsFromObject = 278, + API_PyArray_Squeeze = 136, + API_PyArray_SetBaseObject = 282 + }; + + static npy_api lookup() { + module m = module::import("numpy.core.multiarray"); + auto c = m.attr("_ARRAY_API"); +#if PY_MAJOR_VERSION >= 3 + void **api_ptr = (void **) PyCapsule_GetPointer(c.ptr(), NULL); +#else + void **api_ptr = (void **) PyCObject_AsVoidPtr(c.ptr()); +#endif + npy_api api; +#define DECL_NPY_API(Func) api.Func##_ = (decltype(api.Func##_)) api_ptr[API_##Func]; + DECL_NPY_API(PyArray_GetNDArrayCFeatureVersion); + if (api.PyArray_GetNDArrayCFeatureVersion_() < 0x7) + pybind11_fail("pybind11 numpy support requires numpy >= 1.7.0"); + DECL_NPY_API(PyArray_Type); + DECL_NPY_API(PyVoidArrType_Type); + DECL_NPY_API(PyArrayDescr_Type); + DECL_NPY_API(PyArray_DescrFromType); + DECL_NPY_API(PyArray_DescrFromScalar); + DECL_NPY_API(PyArray_FromAny); + DECL_NPY_API(PyArray_Resize); + DECL_NPY_API(PyArray_CopyInto); + DECL_NPY_API(PyArray_NewCopy); + DECL_NPY_API(PyArray_NewFromDescr); + DECL_NPY_API(PyArray_DescrNewFromType); + DECL_NPY_API(PyArray_DescrConverter); + DECL_NPY_API(PyArray_EquivTypes); + DECL_NPY_API(PyArray_GetArrayParamsFromObject); + DECL_NPY_API(PyArray_Squeeze); + DECL_NPY_API(PyArray_SetBaseObject); +#undef DECL_NPY_API + return api; + } +}; + +inline PyArray_Proxy* array_proxy(void* ptr) { + return reinterpret_cast(ptr); +} + +inline const PyArray_Proxy* array_proxy(const void* ptr) { + return reinterpret_cast(ptr); +} + +inline PyArrayDescr_Proxy* array_descriptor_proxy(PyObject* ptr) { + return reinterpret_cast(ptr); +} + +inline const PyArrayDescr_Proxy* array_descriptor_proxy(const PyObject* ptr) { + return reinterpret_cast(ptr); +} + +inline bool check_flags(const void* ptr, int flag) { + return (flag == (array_proxy(ptr)->flags & flag)); +} + +template struct is_std_array : std::false_type { }; +template struct is_std_array> : std::true_type { }; +template struct is_complex : std::false_type { }; +template struct is_complex> : std::true_type { }; + +template struct array_info_scalar { + typedef T type; + static constexpr bool is_array = false; + static constexpr bool is_empty = false; + static constexpr auto extents = _(""); + static void append_extents(list& /* shape */) { } +}; +// Computes underlying type and a comma-separated list of extents for array +// types (any mix of std::array and built-in arrays). An array of char is +// treated as scalar because it gets special handling. +template struct array_info : array_info_scalar { }; +template struct array_info> { + using type = typename array_info::type; + static constexpr bool is_array = true; + static constexpr bool is_empty = (N == 0) || array_info::is_empty; + static constexpr size_t extent = N; + + // appends the extents to shape + static void append_extents(list& shape) { + shape.append(N); + array_info::append_extents(shape); + } + + static constexpr auto extents = _::is_array>( + concat(_(), array_info::extents), _() + ); +}; +// For numpy we have special handling for arrays of characters, so we don't include +// the size in the array extents. +template struct array_info : array_info_scalar { }; +template struct array_info> : array_info_scalar> { }; +template struct array_info : array_info> { }; +template using remove_all_extents_t = typename array_info::type; + +template using is_pod_struct = all_of< + std::is_standard_layout, // since we're accessing directly in memory we need a standard layout type +#if !defined(__GNUG__) || defined(_LIBCPP_VERSION) || defined(_GLIBCXX_USE_CXX11_ABI) + // _GLIBCXX_USE_CXX11_ABI indicates that we're using libstdc++ from GCC 5 or newer, independent + // of the actual compiler (Clang can also use libstdc++, but it always defines __GNUC__ == 4). + std::is_trivially_copyable, +#else + // GCC 4 doesn't implement is_trivially_copyable, so approximate it + std::is_trivially_destructible, + satisfies_any_of, +#endif + satisfies_none_of +>; + +template ssize_t byte_offset_unsafe(const Strides &) { return 0; } +template +ssize_t byte_offset_unsafe(const Strides &strides, ssize_t i, Ix... index) { + return i * strides[Dim] + byte_offset_unsafe(strides, index...); +} + +/** + * Proxy class providing unsafe, unchecked const access to array data. This is constructed through + * the `unchecked()` method of `array` or the `unchecked()` method of `array_t`. `Dims` + * will be -1 for dimensions determined at runtime. + */ +template +class unchecked_reference { +protected: + static constexpr bool Dynamic = Dims < 0; + const unsigned char *data_; + // Storing the shape & strides in local variables (i.e. these arrays) allows the compiler to + // make large performance gains on big, nested loops, but requires compile-time dimensions + conditional_t> + shape_, strides_; + const ssize_t dims_; + + friend class pybind11::array; + // Constructor for compile-time dimensions: + template + unchecked_reference(const void *data, const ssize_t *shape, const ssize_t *strides, enable_if_t) + : data_{reinterpret_cast(data)}, dims_{Dims} { + for (size_t i = 0; i < (size_t) dims_; i++) { + shape_[i] = shape[i]; + strides_[i] = strides[i]; + } + } + // Constructor for runtime dimensions: + template + unchecked_reference(const void *data, const ssize_t *shape, const ssize_t *strides, enable_if_t dims) + : data_{reinterpret_cast(data)}, shape_{shape}, strides_{strides}, dims_{dims} {} + +public: + /** + * Unchecked const reference access to data at the given indices. For a compile-time known + * number of dimensions, this requires the correct number of arguments; for run-time + * dimensionality, this is not checked (and so is up to the caller to use safely). + */ + template const T &operator()(Ix... index) const { + static_assert(ssize_t{sizeof...(Ix)} == Dims || Dynamic, + "Invalid number of indices for unchecked array reference"); + return *reinterpret_cast(data_ + byte_offset_unsafe(strides_, ssize_t(index)...)); + } + /** + * Unchecked const reference access to data; this operator only participates if the reference + * is to a 1-dimensional array. When present, this is exactly equivalent to `obj(index)`. + */ + template > + const T &operator[](ssize_t index) const { return operator()(index); } + + /// Pointer access to the data at the given indices. + template const T *data(Ix... ix) const { return &operator()(ssize_t(ix)...); } + + /// Returns the item size, i.e. sizeof(T) + constexpr static ssize_t itemsize() { return sizeof(T); } + + /// Returns the shape (i.e. size) of dimension `dim` + ssize_t shape(ssize_t dim) const { return shape_[(size_t) dim]; } + + /// Returns the number of dimensions of the array + ssize_t ndim() const { return dims_; } + + /// Returns the total number of elements in the referenced array, i.e. the product of the shapes + template + enable_if_t size() const { + return std::accumulate(shape_.begin(), shape_.end(), (ssize_t) 1, std::multiplies()); + } + template + enable_if_t size() const { + return std::accumulate(shape_, shape_ + ndim(), (ssize_t) 1, std::multiplies()); + } + + /// Returns the total number of bytes used by the referenced data. Note that the actual span in + /// memory may be larger if the referenced array has non-contiguous strides (e.g. for a slice). + ssize_t nbytes() const { + return size() * itemsize(); + } +}; + +template +class unchecked_mutable_reference : public unchecked_reference { + friend class pybind11::array; + using ConstBase = unchecked_reference; + using ConstBase::ConstBase; + using ConstBase::Dynamic; +public: + /// Mutable, unchecked access to data at the given indices. + template T& operator()(Ix... index) { + static_assert(ssize_t{sizeof...(Ix)} == Dims || Dynamic, + "Invalid number of indices for unchecked array reference"); + return const_cast(ConstBase::operator()(index...)); + } + /** + * Mutable, unchecked access data at the given index; this operator only participates if the + * reference is to a 1-dimensional array (or has runtime dimensions). When present, this is + * exactly equivalent to `obj(index)`. + */ + template > + T &operator[](ssize_t index) { return operator()(index); } + + /// Mutable pointer access to the data at the given indices. + template T *mutable_data(Ix... ix) { return &operator()(ssize_t(ix)...); } +}; + +template +struct type_caster> { + static_assert(Dim == 0 && Dim > 0 /* always fail */, "unchecked array proxy object is not castable"); +}; +template +struct type_caster> : type_caster> {}; + +NAMESPACE_END(detail) + +class dtype : public object { +public: + PYBIND11_OBJECT_DEFAULT(dtype, object, detail::npy_api::get().PyArrayDescr_Check_); + + explicit dtype(const buffer_info &info) { + dtype descr(_dtype_from_pep3118()(PYBIND11_STR_TYPE(info.format))); + // If info.itemsize == 0, use the value calculated from the format string + m_ptr = descr.strip_padding(info.itemsize ? info.itemsize : descr.itemsize()).release().ptr(); + } + + explicit dtype(const std::string &format) { + m_ptr = from_args(pybind11::str(format)).release().ptr(); + } + + dtype(const char *format) : dtype(std::string(format)) { } + + dtype(list names, list formats, list offsets, ssize_t itemsize) { + dict args; + args["names"] = names; + args["formats"] = formats; + args["offsets"] = offsets; + args["itemsize"] = pybind11::int_(itemsize); + m_ptr = from_args(args).release().ptr(); + } + + /// This is essentially the same as calling numpy.dtype(args) in Python. + static dtype from_args(object args) { + PyObject *ptr = nullptr; + if (!detail::npy_api::get().PyArray_DescrConverter_(args.ptr(), &ptr) || !ptr) + throw error_already_set(); + return reinterpret_steal(ptr); + } + + /// Return dtype associated with a C++ type. + template static dtype of() { + return detail::npy_format_descriptor::type>::dtype(); + } + + /// Size of the data type in bytes. + ssize_t itemsize() const { + return detail::array_descriptor_proxy(m_ptr)->elsize; + } + + /// Returns true for structured data types. + bool has_fields() const { + return detail::array_descriptor_proxy(m_ptr)->names != nullptr; + } + + /// Single-character type code. + char kind() const { + return detail::array_descriptor_proxy(m_ptr)->kind; + } + +private: + static object _dtype_from_pep3118() { + static PyObject *obj = module::import("numpy.core._internal") + .attr("_dtype_from_pep3118").cast().release().ptr(); + return reinterpret_borrow(obj); + } + + dtype strip_padding(ssize_t itemsize) { + // Recursively strip all void fields with empty names that are generated for + // padding fields (as of NumPy v1.11). + if (!has_fields()) + return *this; + + struct field_descr { PYBIND11_STR_TYPE name; object format; pybind11::int_ offset; }; + std::vector field_descriptors; + + for (auto field : attr("fields").attr("items")()) { + auto spec = field.cast(); + auto name = spec[0].cast(); + auto format = spec[1].cast()[0].cast(); + auto offset = spec[1].cast()[1].cast(); + if (!len(name) && format.kind() == 'V') + continue; + field_descriptors.push_back({(PYBIND11_STR_TYPE) name, format.strip_padding(format.itemsize()), offset}); + } + + std::sort(field_descriptors.begin(), field_descriptors.end(), + [](const field_descr& a, const field_descr& b) { + return a.offset.cast() < b.offset.cast(); + }); + + list names, formats, offsets; + for (auto& descr : field_descriptors) { + names.append(descr.name); + formats.append(descr.format); + offsets.append(descr.offset); + } + return dtype(names, formats, offsets, itemsize); + } +}; + +class array : public buffer { +public: + PYBIND11_OBJECT_CVT(array, buffer, detail::npy_api::get().PyArray_Check_, raw_array) + + enum { + c_style = detail::npy_api::NPY_ARRAY_C_CONTIGUOUS_, + f_style = detail::npy_api::NPY_ARRAY_F_CONTIGUOUS_, + forcecast = detail::npy_api::NPY_ARRAY_FORCECAST_ + }; + + array() : array({{0}}, static_cast(nullptr)) {} + + using ShapeContainer = detail::any_container; + using StridesContainer = detail::any_container; + + // Constructs an array taking shape/strides from arbitrary container types + array(const pybind11::dtype &dt, ShapeContainer shape, StridesContainer strides, + const void *ptr = nullptr, handle base = handle()) { + + if (strides->empty()) + *strides = c_strides(*shape, dt.itemsize()); + + auto ndim = shape->size(); + if (ndim != strides->size()) + pybind11_fail("NumPy: shape ndim doesn't match strides ndim"); + auto descr = dt; + + int flags = 0; + if (base && ptr) { + if (isinstance(base)) + /* Copy flags from base (except ownership bit) */ + flags = reinterpret_borrow(base).flags() & ~detail::npy_api::NPY_ARRAY_OWNDATA_; + else + /* Writable by default, easy to downgrade later on if needed */ + flags = detail::npy_api::NPY_ARRAY_WRITEABLE_; + } + + auto &api = detail::npy_api::get(); + auto tmp = reinterpret_steal(api.PyArray_NewFromDescr_( + api.PyArray_Type_, descr.release().ptr(), (int) ndim, shape->data(), strides->data(), + const_cast(ptr), flags, nullptr)); + if (!tmp) + throw error_already_set(); + if (ptr) { + if (base) { + api.PyArray_SetBaseObject_(tmp.ptr(), base.inc_ref().ptr()); + } else { + tmp = reinterpret_steal(api.PyArray_NewCopy_(tmp.ptr(), -1 /* any order */)); + } + } + m_ptr = tmp.release().ptr(); + } + + array(const pybind11::dtype &dt, ShapeContainer shape, const void *ptr = nullptr, handle base = handle()) + : array(dt, std::move(shape), {}, ptr, base) { } + + template ::value && !std::is_same::value>> + array(const pybind11::dtype &dt, T count, const void *ptr = nullptr, handle base = handle()) + : array(dt, {{count}}, ptr, base) { } + + template + array(ShapeContainer shape, StridesContainer strides, const T *ptr, handle base = handle()) + : array(pybind11::dtype::of(), std::move(shape), std::move(strides), ptr, base) { } + + template + array(ShapeContainer shape, const T *ptr, handle base = handle()) + : array(std::move(shape), {}, ptr, base) { } + + template + explicit array(ssize_t count, const T *ptr, handle base = handle()) : array({count}, {}, ptr, base) { } + + explicit array(const buffer_info &info) + : array(pybind11::dtype(info), info.shape, info.strides, info.ptr) { } + + /// Array descriptor (dtype) + pybind11::dtype dtype() const { + return reinterpret_borrow(detail::array_proxy(m_ptr)->descr); + } + + /// Total number of elements + ssize_t size() const { + return std::accumulate(shape(), shape() + ndim(), (ssize_t) 1, std::multiplies()); + } + + /// Byte size of a single element + ssize_t itemsize() const { + return detail::array_descriptor_proxy(detail::array_proxy(m_ptr)->descr)->elsize; + } + + /// Total number of bytes + ssize_t nbytes() const { + return size() * itemsize(); + } + + /// Number of dimensions + ssize_t ndim() const { + return detail::array_proxy(m_ptr)->nd; + } + + /// Base object + object base() const { + return reinterpret_borrow(detail::array_proxy(m_ptr)->base); + } + + /// Dimensions of the array + const ssize_t* shape() const { + return detail::array_proxy(m_ptr)->dimensions; + } + + /// Dimension along a given axis + ssize_t shape(ssize_t dim) const { + if (dim >= ndim()) + fail_dim_check(dim, "invalid axis"); + return shape()[dim]; + } + + /// Strides of the array + const ssize_t* strides() const { + return detail::array_proxy(m_ptr)->strides; + } + + /// Stride along a given axis + ssize_t strides(ssize_t dim) const { + if (dim >= ndim()) + fail_dim_check(dim, "invalid axis"); + return strides()[dim]; + } + + /// Return the NumPy array flags + int flags() const { + return detail::array_proxy(m_ptr)->flags; + } + + /// If set, the array is writeable (otherwise the buffer is read-only) + bool writeable() const { + return detail::check_flags(m_ptr, detail::npy_api::NPY_ARRAY_WRITEABLE_); + } + + /// If set, the array owns the data (will be freed when the array is deleted) + bool owndata() const { + return detail::check_flags(m_ptr, detail::npy_api::NPY_ARRAY_OWNDATA_); + } + + /// Pointer to the contained data. If index is not provided, points to the + /// beginning of the buffer. May throw if the index would lead to out of bounds access. + template const void* data(Ix... index) const { + return static_cast(detail::array_proxy(m_ptr)->data + offset_at(index...)); + } + + /// Mutable pointer to the contained data. If index is not provided, points to the + /// beginning of the buffer. May throw if the index would lead to out of bounds access. + /// May throw if the array is not writeable. + template void* mutable_data(Ix... index) { + check_writeable(); + return static_cast(detail::array_proxy(m_ptr)->data + offset_at(index...)); + } + + /// Byte offset from beginning of the array to a given index (full or partial). + /// May throw if the index would lead to out of bounds access. + template ssize_t offset_at(Ix... index) const { + if ((ssize_t) sizeof...(index) > ndim()) + fail_dim_check(sizeof...(index), "too many indices for an array"); + return byte_offset(ssize_t(index)...); + } + + ssize_t offset_at() const { return 0; } + + /// Item count from beginning of the array to a given index (full or partial). + /// May throw if the index would lead to out of bounds access. + template ssize_t index_at(Ix... index) const { + return offset_at(index...) / itemsize(); + } + + /** + * Returns a proxy object that provides access to the array's data without bounds or + * dimensionality checking. Will throw if the array is missing the `writeable` flag. Use with + * care: the array must not be destroyed or reshaped for the duration of the returned object, + * and the caller must take care not to access invalid dimensions or dimension indices. + */ + template detail::unchecked_mutable_reference mutable_unchecked() & { + if (Dims >= 0 && ndim() != Dims) + throw std::domain_error("array has incorrect number of dimensions: " + std::to_string(ndim()) + + "; expected " + std::to_string(Dims)); + return detail::unchecked_mutable_reference(mutable_data(), shape(), strides(), ndim()); + } + + /** + * Returns a proxy object that provides const access to the array's data without bounds or + * dimensionality checking. Unlike `mutable_unchecked()`, this does not require that the + * underlying array have the `writable` flag. Use with care: the array must not be destroyed or + * reshaped for the duration of the returned object, and the caller must take care not to access + * invalid dimensions or dimension indices. + */ + template detail::unchecked_reference unchecked() const & { + if (Dims >= 0 && ndim() != Dims) + throw std::domain_error("array has incorrect number of dimensions: " + std::to_string(ndim()) + + "; expected " + std::to_string(Dims)); + return detail::unchecked_reference(data(), shape(), strides(), ndim()); + } + + /// Return a new view with all of the dimensions of length 1 removed + array squeeze() { + auto& api = detail::npy_api::get(); + return reinterpret_steal(api.PyArray_Squeeze_(m_ptr)); + } + + /// Resize array to given shape + /// If refcheck is true and more that one reference exist to this array + /// then resize will succeed only if it makes a reshape, i.e. original size doesn't change + void resize(ShapeContainer new_shape, bool refcheck = true) { + detail::npy_api::PyArray_Dims d = { + new_shape->data(), int(new_shape->size()) + }; + // try to resize, set ordering param to -1 cause it's not used anyway + object new_array = reinterpret_steal( + detail::npy_api::get().PyArray_Resize_(m_ptr, &d, int(refcheck), -1) + ); + if (!new_array) throw error_already_set(); + if (isinstance(new_array)) { *this = std::move(new_array); } + } + + /// Ensure that the argument is a NumPy array + /// In case of an error, nullptr is returned and the Python error is cleared. + static array ensure(handle h, int ExtraFlags = 0) { + auto result = reinterpret_steal(raw_array(h.ptr(), ExtraFlags)); + if (!result) + PyErr_Clear(); + return result; + } + +protected: + template friend struct detail::npy_format_descriptor; + + void fail_dim_check(ssize_t dim, const std::string& msg) const { + throw index_error(msg + ": " + std::to_string(dim) + + " (ndim = " + std::to_string(ndim()) + ")"); + } + + template ssize_t byte_offset(Ix... index) const { + check_dimensions(index...); + return detail::byte_offset_unsafe(strides(), ssize_t(index)...); + } + + void check_writeable() const { + if (!writeable()) + throw std::domain_error("array is not writeable"); + } + + // Default, C-style strides + static std::vector c_strides(const std::vector &shape, ssize_t itemsize) { + auto ndim = shape.size(); + std::vector strides(ndim, itemsize); + if (ndim > 0) + for (size_t i = ndim - 1; i > 0; --i) + strides[i - 1] = strides[i] * shape[i]; + return strides; + } + + // F-style strides; default when constructing an array_t with `ExtraFlags & f_style` + static std::vector f_strides(const std::vector &shape, ssize_t itemsize) { + auto ndim = shape.size(); + std::vector strides(ndim, itemsize); + for (size_t i = 1; i < ndim; ++i) + strides[i] = strides[i - 1] * shape[i - 1]; + return strides; + } + + template void check_dimensions(Ix... index) const { + check_dimensions_impl(ssize_t(0), shape(), ssize_t(index)...); + } + + void check_dimensions_impl(ssize_t, const ssize_t*) const { } + + template void check_dimensions_impl(ssize_t axis, const ssize_t* shape, ssize_t i, Ix... index) const { + if (i >= *shape) { + throw index_error(std::string("index ") + std::to_string(i) + + " is out of bounds for axis " + std::to_string(axis) + + " with size " + std::to_string(*shape)); + } + check_dimensions_impl(axis + 1, shape + 1, index...); + } + + /// Create array from any object -- always returns a new reference + static PyObject *raw_array(PyObject *ptr, int ExtraFlags = 0) { + if (ptr == nullptr) { + PyErr_SetString(PyExc_ValueError, "cannot create a pybind11::array from a nullptr"); + return nullptr; + } + return detail::npy_api::get().PyArray_FromAny_( + ptr, nullptr, 0, 0, detail::npy_api::NPY_ARRAY_ENSUREARRAY_ | ExtraFlags, nullptr); + } +}; + +template class array_t : public array { +private: + struct private_ctor {}; + // Delegating constructor needed when both moving and accessing in the same constructor + array_t(private_ctor, ShapeContainer &&shape, StridesContainer &&strides, const T *ptr, handle base) + : array(std::move(shape), std::move(strides), ptr, base) {} +public: + static_assert(!detail::array_info::is_array, "Array types cannot be used with array_t"); + + using value_type = T; + + array_t() : array(0, static_cast(nullptr)) {} + array_t(handle h, borrowed_t) : array(h, borrowed_t{}) { } + array_t(handle h, stolen_t) : array(h, stolen_t{}) { } + + PYBIND11_DEPRECATED("Use array_t::ensure() instead") + array_t(handle h, bool is_borrowed) : array(raw_array_t(h.ptr()), stolen_t{}) { + if (!m_ptr) PyErr_Clear(); + if (!is_borrowed) Py_XDECREF(h.ptr()); + } + + array_t(const object &o) : array(raw_array_t(o.ptr()), stolen_t{}) { + if (!m_ptr) throw error_already_set(); + } + + explicit array_t(const buffer_info& info) : array(info) { } + + array_t(ShapeContainer shape, StridesContainer strides, const T *ptr = nullptr, handle base = handle()) + : array(std::move(shape), std::move(strides), ptr, base) { } + + explicit array_t(ShapeContainer shape, const T *ptr = nullptr, handle base = handle()) + : array_t(private_ctor{}, std::move(shape), + ExtraFlags & f_style ? f_strides(*shape, itemsize()) : c_strides(*shape, itemsize()), + ptr, base) { } + + explicit array_t(size_t count, const T *ptr = nullptr, handle base = handle()) + : array({count}, {}, ptr, base) { } + + constexpr ssize_t itemsize() const { + return sizeof(T); + } + + template ssize_t index_at(Ix... index) const { + return offset_at(index...) / itemsize(); + } + + template const T* data(Ix... index) const { + return static_cast(array::data(index...)); + } + + template T* mutable_data(Ix... index) { + return static_cast(array::mutable_data(index...)); + } + + // Reference to element at a given index + template const T& at(Ix... index) const { + if ((ssize_t) sizeof...(index) != ndim()) + fail_dim_check(sizeof...(index), "index dimension mismatch"); + return *(static_cast(array::data()) + byte_offset(ssize_t(index)...) / itemsize()); + } + + // Mutable reference to element at a given index + template T& mutable_at(Ix... index) { + if ((ssize_t) sizeof...(index) != ndim()) + fail_dim_check(sizeof...(index), "index dimension mismatch"); + return *(static_cast(array::mutable_data()) + byte_offset(ssize_t(index)...) / itemsize()); + } + + /** + * Returns a proxy object that provides access to the array's data without bounds or + * dimensionality checking. Will throw if the array is missing the `writeable` flag. Use with + * care: the array must not be destroyed or reshaped for the duration of the returned object, + * and the caller must take care not to access invalid dimensions or dimension indices. + */ + template detail::unchecked_mutable_reference mutable_unchecked() & { + return array::mutable_unchecked(); + } + + /** + * Returns a proxy object that provides const access to the array's data without bounds or + * dimensionality checking. Unlike `unchecked()`, this does not require that the underlying + * array have the `writable` flag. Use with care: the array must not be destroyed or reshaped + * for the duration of the returned object, and the caller must take care not to access invalid + * dimensions or dimension indices. + */ + template detail::unchecked_reference unchecked() const & { + return array::unchecked(); + } + + /// Ensure that the argument is a NumPy array of the correct dtype (and if not, try to convert + /// it). In case of an error, nullptr is returned and the Python error is cleared. + static array_t ensure(handle h) { + auto result = reinterpret_steal(raw_array_t(h.ptr())); + if (!result) + PyErr_Clear(); + return result; + } + + static bool check_(handle h) { + const auto &api = detail::npy_api::get(); + return api.PyArray_Check_(h.ptr()) + && api.PyArray_EquivTypes_(detail::array_proxy(h.ptr())->descr, dtype::of().ptr()); + } + +protected: + /// Create array from any object -- always returns a new reference + static PyObject *raw_array_t(PyObject *ptr) { + if (ptr == nullptr) { + PyErr_SetString(PyExc_ValueError, "cannot create a pybind11::array_t from a nullptr"); + return nullptr; + } + return detail::npy_api::get().PyArray_FromAny_( + ptr, dtype::of().release().ptr(), 0, 0, + detail::npy_api::NPY_ARRAY_ENSUREARRAY_ | ExtraFlags, nullptr); + } +}; + +template +struct format_descriptor::value>> { + static std::string format() { + return detail::npy_format_descriptor::type>::format(); + } +}; + +template struct format_descriptor { + static std::string format() { return std::to_string(N) + "s"; } +}; +template struct format_descriptor> { + static std::string format() { return std::to_string(N) + "s"; } +}; + +template +struct format_descriptor::value>> { + static std::string format() { + return format_descriptor< + typename std::remove_cv::type>::type>::format(); + } +}; + +template +struct format_descriptor::is_array>> { + static std::string format() { + using namespace detail; + static constexpr auto extents = _("(") + array_info::extents + _(")"); + return extents.text + format_descriptor>::format(); + } +}; + +NAMESPACE_BEGIN(detail) +template +struct pyobject_caster> { + using type = array_t; + + bool load(handle src, bool convert) { + if (!convert && !type::check_(src)) + return false; + value = type::ensure(src); + return static_cast(value); + } + + static handle cast(const handle &src, return_value_policy /* policy */, handle /* parent */) { + return src.inc_ref(); + } + PYBIND11_TYPE_CASTER(type, handle_type_name::name); +}; + +template +struct compare_buffer_info::value>> { + static bool compare(const buffer_info& b) { + return npy_api::get().PyArray_EquivTypes_(dtype::of().ptr(), dtype(b).ptr()); + } +}; + +template +struct npy_format_descriptor_name; + +template +struct npy_format_descriptor_name::value>> { + static constexpr auto name = _::value>( + _("bool"), _::value>("int", "uint") + _() + ); +}; + +template +struct npy_format_descriptor_name::value>> { + static constexpr auto name = _::value || std::is_same::value>( + _("float") + _(), _("longdouble") + ); +}; + +template +struct npy_format_descriptor_name::value>> { + static constexpr auto name = _::value + || std::is_same::value>( + _("complex") + _(), _("longcomplex") + ); +}; + +template +struct npy_format_descriptor::value>> + : npy_format_descriptor_name { +private: + // NB: the order here must match the one in common.h + constexpr static const int values[15] = { + npy_api::NPY_BOOL_, + npy_api::NPY_BYTE_, npy_api::NPY_UBYTE_, npy_api::NPY_SHORT_, npy_api::NPY_USHORT_, + npy_api::NPY_INT_, npy_api::NPY_UINT_, npy_api::NPY_LONGLONG_, npy_api::NPY_ULONGLONG_, + npy_api::NPY_FLOAT_, npy_api::NPY_DOUBLE_, npy_api::NPY_LONGDOUBLE_, + npy_api::NPY_CFLOAT_, npy_api::NPY_CDOUBLE_, npy_api::NPY_CLONGDOUBLE_ + }; + +public: + static constexpr int value = values[detail::is_fmt_numeric::index]; + + static pybind11::dtype dtype() { + if (auto ptr = npy_api::get().PyArray_DescrFromType_(value)) + return reinterpret_borrow(ptr); + pybind11_fail("Unsupported buffer format!"); + } +}; + +#define PYBIND11_DECL_CHAR_FMT \ + static constexpr auto name = _("S") + _(); \ + static pybind11::dtype dtype() { return pybind11::dtype(std::string("S") + std::to_string(N)); } +template struct npy_format_descriptor { PYBIND11_DECL_CHAR_FMT }; +template struct npy_format_descriptor> { PYBIND11_DECL_CHAR_FMT }; +#undef PYBIND11_DECL_CHAR_FMT + +template struct npy_format_descriptor::is_array>> { +private: + using base_descr = npy_format_descriptor::type>; +public: + static_assert(!array_info::is_empty, "Zero-sized arrays are not supported"); + + static constexpr auto name = _("(") + array_info::extents + _(")") + base_descr::name; + static pybind11::dtype dtype() { + list shape; + array_info::append_extents(shape); + return pybind11::dtype::from_args(pybind11::make_tuple(base_descr::dtype(), shape)); + } +}; + +template struct npy_format_descriptor::value>> { +private: + using base_descr = npy_format_descriptor::type>; +public: + static constexpr auto name = base_descr::name; + static pybind11::dtype dtype() { return base_descr::dtype(); } +}; + +struct field_descriptor { + const char *name; + ssize_t offset; + ssize_t size; + std::string format; + dtype descr; +}; + +inline PYBIND11_NOINLINE void register_structured_dtype( + any_container fields, + const std::type_info& tinfo, ssize_t itemsize, + bool (*direct_converter)(PyObject *, void *&)) { + + auto& numpy_internals = get_numpy_internals(); + if (numpy_internals.get_type_info(tinfo, false)) + pybind11_fail("NumPy: dtype is already registered"); + + list names, formats, offsets; + for (auto field : *fields) { + if (!field.descr) + pybind11_fail(std::string("NumPy: unsupported field dtype: `") + + field.name + "` @ " + tinfo.name()); + names.append(PYBIND11_STR_TYPE(field.name)); + formats.append(field.descr); + offsets.append(pybind11::int_(field.offset)); + } + auto dtype_ptr = pybind11::dtype(names, formats, offsets, itemsize).release().ptr(); + + // There is an existing bug in NumPy (as of v1.11): trailing bytes are + // not encoded explicitly into the format string. This will supposedly + // get fixed in v1.12; for further details, see these: + // - https://github.com/numpy/numpy/issues/7797 + // - https://github.com/numpy/numpy/pull/7798 + // Because of this, we won't use numpy's logic to generate buffer format + // strings and will just do it ourselves. + std::vector ordered_fields(std::move(fields)); + std::sort(ordered_fields.begin(), ordered_fields.end(), + [](const field_descriptor &a, const field_descriptor &b) { return a.offset < b.offset; }); + ssize_t offset = 0; + std::ostringstream oss; + // mark the structure as unaligned with '^', because numpy and C++ don't + // always agree about alignment (particularly for complex), and we're + // explicitly listing all our padding. This depends on none of the fields + // overriding the endianness. Putting the ^ in front of individual fields + // isn't guaranteed to work due to https://github.com/numpy/numpy/issues/9049 + oss << "^T{"; + for (auto& field : ordered_fields) { + if (field.offset > offset) + oss << (field.offset - offset) << 'x'; + oss << field.format << ':' << field.name << ':'; + offset = field.offset + field.size; + } + if (itemsize > offset) + oss << (itemsize - offset) << 'x'; + oss << '}'; + auto format_str = oss.str(); + + // Sanity check: verify that NumPy properly parses our buffer format string + auto& api = npy_api::get(); + auto arr = array(buffer_info(nullptr, itemsize, format_str, 1)); + if (!api.PyArray_EquivTypes_(dtype_ptr, arr.dtype().ptr())) + pybind11_fail("NumPy: invalid buffer descriptor!"); + + auto tindex = std::type_index(tinfo); + numpy_internals.registered_dtypes[tindex] = { dtype_ptr, format_str }; + get_internals().direct_conversions[tindex].push_back(direct_converter); +} + +template struct npy_format_descriptor { + static_assert(is_pod_struct::value, "Attempt to use a non-POD or unimplemented POD type as a numpy dtype"); + + static constexpr auto name = make_caster::name; + + static pybind11::dtype dtype() { + return reinterpret_borrow(dtype_ptr()); + } + + static std::string format() { + static auto format_str = get_numpy_internals().get_type_info(true)->format_str; + return format_str; + } + + static void register_dtype(any_container fields) { + register_structured_dtype(std::move(fields), typeid(typename std::remove_cv::type), + sizeof(T), &direct_converter); + } + +private: + static PyObject* dtype_ptr() { + static PyObject* ptr = get_numpy_internals().get_type_info(true)->dtype_ptr; + return ptr; + } + + static bool direct_converter(PyObject *obj, void*& value) { + auto& api = npy_api::get(); + if (!PyObject_TypeCheck(obj, api.PyVoidArrType_Type_)) + return false; + if (auto descr = reinterpret_steal(api.PyArray_DescrFromScalar_(obj))) { + if (api.PyArray_EquivTypes_(dtype_ptr(), descr.ptr())) { + value = ((PyVoidScalarObject_Proxy *) obj)->obval; + return true; + } + } + return false; + } +}; + +#ifdef __CLION_IDE__ // replace heavy macro with dummy code for the IDE (doesn't affect code) +# define PYBIND11_NUMPY_DTYPE(Type, ...) ((void)0) +# define PYBIND11_NUMPY_DTYPE_EX(Type, ...) ((void)0) +#else + +#define PYBIND11_FIELD_DESCRIPTOR_EX(T, Field, Name) \ + ::pybind11::detail::field_descriptor { \ + Name, offsetof(T, Field), sizeof(decltype(std::declval().Field)), \ + ::pybind11::format_descriptor().Field)>::format(), \ + ::pybind11::detail::npy_format_descriptor().Field)>::dtype() \ + } + +// Extract name, offset and format descriptor for a struct field +#define PYBIND11_FIELD_DESCRIPTOR(T, Field) PYBIND11_FIELD_DESCRIPTOR_EX(T, Field, #Field) + +// The main idea of this macro is borrowed from https://github.com/swansontec/map-macro +// (C) William Swanson, Paul Fultz +#define PYBIND11_EVAL0(...) __VA_ARGS__ +#define PYBIND11_EVAL1(...) PYBIND11_EVAL0 (PYBIND11_EVAL0 (PYBIND11_EVAL0 (__VA_ARGS__))) +#define PYBIND11_EVAL2(...) PYBIND11_EVAL1 (PYBIND11_EVAL1 (PYBIND11_EVAL1 (__VA_ARGS__))) +#define PYBIND11_EVAL3(...) PYBIND11_EVAL2 (PYBIND11_EVAL2 (PYBIND11_EVAL2 (__VA_ARGS__))) +#define PYBIND11_EVAL4(...) PYBIND11_EVAL3 (PYBIND11_EVAL3 (PYBIND11_EVAL3 (__VA_ARGS__))) +#define PYBIND11_EVAL(...) PYBIND11_EVAL4 (PYBIND11_EVAL4 (PYBIND11_EVAL4 (__VA_ARGS__))) +#define PYBIND11_MAP_END(...) +#define PYBIND11_MAP_OUT +#define PYBIND11_MAP_COMMA , +#define PYBIND11_MAP_GET_END() 0, PYBIND11_MAP_END +#define PYBIND11_MAP_NEXT0(test, next, ...) next PYBIND11_MAP_OUT +#define PYBIND11_MAP_NEXT1(test, next) PYBIND11_MAP_NEXT0 (test, next, 0) +#define PYBIND11_MAP_NEXT(test, next) PYBIND11_MAP_NEXT1 (PYBIND11_MAP_GET_END test, next) +#ifdef _MSC_VER // MSVC is not as eager to expand macros, hence this workaround +#define PYBIND11_MAP_LIST_NEXT1(test, next) \ + PYBIND11_EVAL0 (PYBIND11_MAP_NEXT0 (test, PYBIND11_MAP_COMMA next, 0)) +#else +#define PYBIND11_MAP_LIST_NEXT1(test, next) \ + PYBIND11_MAP_NEXT0 (test, PYBIND11_MAP_COMMA next, 0) +#endif +#define PYBIND11_MAP_LIST_NEXT(test, next) \ + PYBIND11_MAP_LIST_NEXT1 (PYBIND11_MAP_GET_END test, next) +#define PYBIND11_MAP_LIST0(f, t, x, peek, ...) \ + f(t, x) PYBIND11_MAP_LIST_NEXT (peek, PYBIND11_MAP_LIST1) (f, t, peek, __VA_ARGS__) +#define PYBIND11_MAP_LIST1(f, t, x, peek, ...) \ + f(t, x) PYBIND11_MAP_LIST_NEXT (peek, PYBIND11_MAP_LIST0) (f, t, peek, __VA_ARGS__) +// PYBIND11_MAP_LIST(f, t, a1, a2, ...) expands to f(t, a1), f(t, a2), ... +#define PYBIND11_MAP_LIST(f, t, ...) \ + PYBIND11_EVAL (PYBIND11_MAP_LIST1 (f, t, __VA_ARGS__, (), 0)) + +#define PYBIND11_NUMPY_DTYPE(Type, ...) \ + ::pybind11::detail::npy_format_descriptor::register_dtype \ + (::std::vector<::pybind11::detail::field_descriptor> \ + {PYBIND11_MAP_LIST (PYBIND11_FIELD_DESCRIPTOR, Type, __VA_ARGS__)}) + +#ifdef _MSC_VER +#define PYBIND11_MAP2_LIST_NEXT1(test, next) \ + PYBIND11_EVAL0 (PYBIND11_MAP_NEXT0 (test, PYBIND11_MAP_COMMA next, 0)) +#else +#define PYBIND11_MAP2_LIST_NEXT1(test, next) \ + PYBIND11_MAP_NEXT0 (test, PYBIND11_MAP_COMMA next, 0) +#endif +#define PYBIND11_MAP2_LIST_NEXT(test, next) \ + PYBIND11_MAP2_LIST_NEXT1 (PYBIND11_MAP_GET_END test, next) +#define PYBIND11_MAP2_LIST0(f, t, x1, x2, peek, ...) \ + f(t, x1, x2) PYBIND11_MAP2_LIST_NEXT (peek, PYBIND11_MAP2_LIST1) (f, t, peek, __VA_ARGS__) +#define PYBIND11_MAP2_LIST1(f, t, x1, x2, peek, ...) \ + f(t, x1, x2) PYBIND11_MAP2_LIST_NEXT (peek, PYBIND11_MAP2_LIST0) (f, t, peek, __VA_ARGS__) +// PYBIND11_MAP2_LIST(f, t, a1, a2, ...) expands to f(t, a1, a2), f(t, a3, a4), ... +#define PYBIND11_MAP2_LIST(f, t, ...) \ + PYBIND11_EVAL (PYBIND11_MAP2_LIST1 (f, t, __VA_ARGS__, (), 0)) + +#define PYBIND11_NUMPY_DTYPE_EX(Type, ...) \ + ::pybind11::detail::npy_format_descriptor::register_dtype \ + (::std::vector<::pybind11::detail::field_descriptor> \ + {PYBIND11_MAP2_LIST (PYBIND11_FIELD_DESCRIPTOR_EX, Type, __VA_ARGS__)}) + +#endif // __CLION_IDE__ + +template +using array_iterator = typename std::add_pointer::type; + +template +array_iterator array_begin(const buffer_info& buffer) { + return array_iterator(reinterpret_cast(buffer.ptr)); +} + +template +array_iterator array_end(const buffer_info& buffer) { + return array_iterator(reinterpret_cast(buffer.ptr) + buffer.size); +} + +class common_iterator { +public: + using container_type = std::vector; + using value_type = container_type::value_type; + using size_type = container_type::size_type; + + common_iterator() : p_ptr(0), m_strides() {} + + common_iterator(void* ptr, const container_type& strides, const container_type& shape) + : p_ptr(reinterpret_cast(ptr)), m_strides(strides.size()) { + m_strides.back() = static_cast(strides.back()); + for (size_type i = m_strides.size() - 1; i != 0; --i) { + size_type j = i - 1; + value_type s = static_cast(shape[i]); + m_strides[j] = strides[j] + m_strides[i] - strides[i] * s; + } + } + + void increment(size_type dim) { + p_ptr += m_strides[dim]; + } + + void* data() const { + return p_ptr; + } + +private: + char* p_ptr; + container_type m_strides; +}; + +template class multi_array_iterator { +public: + using container_type = std::vector; + + multi_array_iterator(const std::array &buffers, + const container_type &shape) + : m_shape(shape.size()), m_index(shape.size(), 0), + m_common_iterator() { + + // Manual copy to avoid conversion warning if using std::copy + for (size_t i = 0; i < shape.size(); ++i) + m_shape[i] = shape[i]; + + container_type strides(shape.size()); + for (size_t i = 0; i < N; ++i) + init_common_iterator(buffers[i], shape, m_common_iterator[i], strides); + } + + multi_array_iterator& operator++() { + for (size_t j = m_index.size(); j != 0; --j) { + size_t i = j - 1; + if (++m_index[i] != m_shape[i]) { + increment_common_iterator(i); + break; + } else { + m_index[i] = 0; + } + } + return *this; + } + + template T* data() const { + return reinterpret_cast(m_common_iterator[K].data()); + } + +private: + + using common_iter = common_iterator; + + void init_common_iterator(const buffer_info &buffer, + const container_type &shape, + common_iter &iterator, + container_type &strides) { + auto buffer_shape_iter = buffer.shape.rbegin(); + auto buffer_strides_iter = buffer.strides.rbegin(); + auto shape_iter = shape.rbegin(); + auto strides_iter = strides.rbegin(); + + while (buffer_shape_iter != buffer.shape.rend()) { + if (*shape_iter == *buffer_shape_iter) + *strides_iter = *buffer_strides_iter; + else + *strides_iter = 0; + + ++buffer_shape_iter; + ++buffer_strides_iter; + ++shape_iter; + ++strides_iter; + } + + std::fill(strides_iter, strides.rend(), 0); + iterator = common_iter(buffer.ptr, strides, shape); + } + + void increment_common_iterator(size_t dim) { + for (auto &iter : m_common_iterator) + iter.increment(dim); + } + + container_type m_shape; + container_type m_index; + std::array m_common_iterator; +}; + +enum class broadcast_trivial { non_trivial, c_trivial, f_trivial }; + +// Populates the shape and number of dimensions for the set of buffers. Returns a broadcast_trivial +// enum value indicating whether the broadcast is "trivial"--that is, has each buffer being either a +// singleton or a full-size, C-contiguous (`c_trivial`) or Fortran-contiguous (`f_trivial`) storage +// buffer; returns `non_trivial` otherwise. +template +broadcast_trivial broadcast(const std::array &buffers, ssize_t &ndim, std::vector &shape) { + ndim = std::accumulate(buffers.begin(), buffers.end(), ssize_t(0), [](ssize_t res, const buffer_info &buf) { + return std::max(res, buf.ndim); + }); + + shape.clear(); + shape.resize((size_t) ndim, 1); + + // Figure out the output size, and make sure all input arrays conform (i.e. are either size 1 or + // the full size). + for (size_t i = 0; i < N; ++i) { + auto res_iter = shape.rbegin(); + auto end = buffers[i].shape.rend(); + for (auto shape_iter = buffers[i].shape.rbegin(); shape_iter != end; ++shape_iter, ++res_iter) { + const auto &dim_size_in = *shape_iter; + auto &dim_size_out = *res_iter; + + // Each input dimension can either be 1 or `n`, but `n` values must match across buffers + if (dim_size_out == 1) + dim_size_out = dim_size_in; + else if (dim_size_in != 1 && dim_size_in != dim_size_out) + pybind11_fail("pybind11::vectorize: incompatible size/dimension of inputs!"); + } + } + + bool trivial_broadcast_c = true; + bool trivial_broadcast_f = true; + for (size_t i = 0; i < N && (trivial_broadcast_c || trivial_broadcast_f); ++i) { + if (buffers[i].size == 1) + continue; + + // Require the same number of dimensions: + if (buffers[i].ndim != ndim) + return broadcast_trivial::non_trivial; + + // Require all dimensions be full-size: + if (!std::equal(buffers[i].shape.cbegin(), buffers[i].shape.cend(), shape.cbegin())) + return broadcast_trivial::non_trivial; + + // Check for C contiguity (but only if previous inputs were also C contiguous) + if (trivial_broadcast_c) { + ssize_t expect_stride = buffers[i].itemsize; + auto end = buffers[i].shape.crend(); + for (auto shape_iter = buffers[i].shape.crbegin(), stride_iter = buffers[i].strides.crbegin(); + trivial_broadcast_c && shape_iter != end; ++shape_iter, ++stride_iter) { + if (expect_stride == *stride_iter) + expect_stride *= *shape_iter; + else + trivial_broadcast_c = false; + } + } + + // Check for Fortran contiguity (if previous inputs were also F contiguous) + if (trivial_broadcast_f) { + ssize_t expect_stride = buffers[i].itemsize; + auto end = buffers[i].shape.cend(); + for (auto shape_iter = buffers[i].shape.cbegin(), stride_iter = buffers[i].strides.cbegin(); + trivial_broadcast_f && shape_iter != end; ++shape_iter, ++stride_iter) { + if (expect_stride == *stride_iter) + expect_stride *= *shape_iter; + else + trivial_broadcast_f = false; + } + } + } + + return + trivial_broadcast_c ? broadcast_trivial::c_trivial : + trivial_broadcast_f ? broadcast_trivial::f_trivial : + broadcast_trivial::non_trivial; +} + +template +struct vectorize_arg { + static_assert(!std::is_rvalue_reference::value, "Functions with rvalue reference arguments cannot be vectorized"); + // The wrapped function gets called with this type: + using call_type = remove_reference_t; + // Is this a vectorized argument? + static constexpr bool vectorize = + satisfies_any_of::value && + satisfies_none_of::value && + (!std::is_reference::value || + (std::is_lvalue_reference::value && std::is_const::value)); + // Accept this type: an array for vectorized types, otherwise the type as-is: + using type = conditional_t, array::forcecast>, T>; +}; + +template +struct vectorize_helper { +private: + static constexpr size_t N = sizeof...(Args); + static constexpr size_t NVectorized = constexpr_sum(vectorize_arg::vectorize...); + static_assert(NVectorized >= 1, + "pybind11::vectorize(...) requires a function with at least one vectorizable argument"); + +public: + template + explicit vectorize_helper(T &&f) : f(std::forward(f)) { } + + object operator()(typename vectorize_arg::type... args) { + return run(args..., + make_index_sequence(), + select_indices::vectorize...>(), + make_index_sequence()); + } + +private: + remove_reference_t f; + + // Internal compiler error in MSVC 19.16.27025.1 (Visual Studio 2017 15.9.4), when compiling with "/permissive-" flag + // when arg_call_types is manually inlined. + using arg_call_types = std::tuple::call_type...>; + template using param_n_t = typename std::tuple_element::type; + + // Runs a vectorized function given arguments tuple and three index sequences: + // - Index is the full set of 0 ... (N-1) argument indices; + // - VIndex is the subset of argument indices with vectorized parameters, letting us access + // vectorized arguments (anything not in this sequence is passed through) + // - BIndex is a incremental sequence (beginning at 0) of the same size as VIndex, so that + // we can store vectorized buffer_infos in an array (argument VIndex has its buffer at + // index BIndex in the array). + template object run( + typename vectorize_arg::type &...args, + index_sequence i_seq, index_sequence vi_seq, index_sequence bi_seq) { + + // Pointers to values the function was called with; the vectorized ones set here will start + // out as array_t pointers, but they will be changed them to T pointers before we make + // call the wrapped function. Non-vectorized pointers are left as-is. + std::array params{{ &args... }}; + + // The array of `buffer_info`s of vectorized arguments: + std::array buffers{{ reinterpret_cast(params[VIndex])->request()... }}; + + /* Determine dimensions parameters of output array */ + ssize_t nd = 0; + std::vector shape(0); + auto trivial = broadcast(buffers, nd, shape); + size_t ndim = (size_t) nd; + + size_t size = std::accumulate(shape.begin(), shape.end(), (size_t) 1, std::multiplies()); + + // If all arguments are 0-dimension arrays (i.e. single values) return a plain value (i.e. + // not wrapped in an array). + if (size == 1 && ndim == 0) { + PYBIND11_EXPAND_SIDE_EFFECTS(params[VIndex] = buffers[BIndex].ptr); + return cast(f(*reinterpret_cast *>(params[Index])...)); + } + + array_t result; + if (trivial == broadcast_trivial::f_trivial) result = array_t(shape); + else result = array_t(shape); + + if (size == 0) return std::move(result); + + /* Call the function */ + if (trivial == broadcast_trivial::non_trivial) + apply_broadcast(buffers, params, result, i_seq, vi_seq, bi_seq); + else + apply_trivial(buffers, params, result.mutable_data(), size, i_seq, vi_seq, bi_seq); + + return std::move(result); + } + + template + void apply_trivial(std::array &buffers, + std::array ¶ms, + Return *out, + size_t size, + index_sequence, index_sequence, index_sequence) { + + // Initialize an array of mutable byte references and sizes with references set to the + // appropriate pointer in `params`; as we iterate, we'll increment each pointer by its size + // (except for singletons, which get an increment of 0). + std::array, NVectorized> vecparams{{ + std::pair( + reinterpret_cast(params[VIndex] = buffers[BIndex].ptr), + buffers[BIndex].size == 1 ? 0 : sizeof(param_n_t) + )... + }}; + + for (size_t i = 0; i < size; ++i) { + out[i] = f(*reinterpret_cast *>(params[Index])...); + for (auto &x : vecparams) x.first += x.second; + } + } + + template + void apply_broadcast(std::array &buffers, + std::array ¶ms, + array_t &output_array, + index_sequence, index_sequence, index_sequence) { + + buffer_info output = output_array.request(); + multi_array_iterator input_iter(buffers, output.shape); + + for (array_iterator iter = array_begin(output), end = array_end(output); + iter != end; + ++iter, ++input_iter) { + PYBIND11_EXPAND_SIDE_EFFECTS(( + params[VIndex] = input_iter.template data() + )); + *iter = f(*reinterpret_cast *>(std::get(params))...); + } + } +}; + +template +vectorize_helper +vectorize_extractor(const Func &f, Return (*) (Args ...)) { + return detail::vectorize_helper(f); +} + +template struct handle_type_name> { + static constexpr auto name = _("numpy.ndarray[") + npy_format_descriptor::name + _("]"); +}; + +NAMESPACE_END(detail) + +// Vanilla pointer vectorizer: +template +detail::vectorize_helper +vectorize(Return (*f) (Args ...)) { + return detail::vectorize_helper(f); +} + +// lambda vectorizer: +template ::value, int> = 0> +auto vectorize(Func &&f) -> decltype( + detail::vectorize_extractor(std::forward(f), (detail::function_signature_t *) nullptr)) { + return detail::vectorize_extractor(std::forward(f), (detail::function_signature_t *) nullptr); +} + +// Vectorize a class method (non-const): +template ())), Return, Class *, Args...>> +Helper vectorize(Return (Class::*f)(Args...)) { + return Helper(std::mem_fn(f)); +} + +// Vectorize a class method (const): +template ())), Return, const Class *, Args...>> +Helper vectorize(Return (Class::*f)(Args...) const) { + return Helper(std::mem_fn(f)); +} + +NAMESPACE_END(PYBIND11_NAMESPACE) + +#if defined(_MSC_VER) +#pragma warning(pop) +#endif diff --git a/wrap/python/pybind11/include/pybind11/operators.h b/wrap/python/pybind11/include/pybind11/operators.h new file mode 100644 index 000000000..b3dd62c3b --- /dev/null +++ b/wrap/python/pybind11/include/pybind11/operators.h @@ -0,0 +1,168 @@ +/* + pybind11/operator.h: Metatemplates for operator overloading + + Copyright (c) 2016 Wenzel Jakob + + All rights reserved. Use of this source code is governed by a + BSD-style license that can be found in the LICENSE file. +*/ + +#pragma once + +#include "pybind11.h" + +#if defined(__clang__) && !defined(__INTEL_COMPILER) +# pragma clang diagnostic ignored "-Wunsequenced" // multiple unsequenced modifications to 'self' (when using def(py::self OP Type())) +#elif defined(_MSC_VER) +# pragma warning(push) +# pragma warning(disable: 4127) // warning C4127: Conditional expression is constant +#endif + +NAMESPACE_BEGIN(PYBIND11_NAMESPACE) +NAMESPACE_BEGIN(detail) + +/// Enumeration with all supported operator types +enum op_id : int { + op_add, op_sub, op_mul, op_div, op_mod, op_divmod, op_pow, op_lshift, + op_rshift, op_and, op_xor, op_or, op_neg, op_pos, op_abs, op_invert, + op_int, op_long, op_float, op_str, op_cmp, op_gt, op_ge, op_lt, op_le, + op_eq, op_ne, op_iadd, op_isub, op_imul, op_idiv, op_imod, op_ilshift, + op_irshift, op_iand, op_ixor, op_ior, op_complex, op_bool, op_nonzero, + op_repr, op_truediv, op_itruediv, op_hash +}; + +enum op_type : int { + op_l, /* base type on left */ + op_r, /* base type on right */ + op_u /* unary operator */ +}; + +struct self_t { }; +static const self_t self = self_t(); + +/// Type for an unused type slot +struct undefined_t { }; + +/// Don't warn about an unused variable +inline self_t __self() { return self; } + +/// base template of operator implementations +template struct op_impl { }; + +/// Operator implementation generator +template struct op_ { + template void execute(Class &cl, const Extra&... extra) const { + using Base = typename Class::type; + using L_type = conditional_t::value, Base, L>; + using R_type = conditional_t::value, Base, R>; + using op = op_impl; + cl.def(op::name(), &op::execute, is_operator(), extra...); + #if PY_MAJOR_VERSION < 3 + if (id == op_truediv || id == op_itruediv) + cl.def(id == op_itruediv ? "__idiv__" : ot == op_l ? "__div__" : "__rdiv__", + &op::execute, is_operator(), extra...); + #endif + } + template void execute_cast(Class &cl, const Extra&... extra) const { + using Base = typename Class::type; + using L_type = conditional_t::value, Base, L>; + using R_type = conditional_t::value, Base, R>; + using op = op_impl; + cl.def(op::name(), &op::execute_cast, is_operator(), extra...); + #if PY_MAJOR_VERSION < 3 + if (id == op_truediv || id == op_itruediv) + cl.def(id == op_itruediv ? "__idiv__" : ot == op_l ? "__div__" : "__rdiv__", + &op::execute, is_operator(), extra...); + #endif + } +}; + +#define PYBIND11_BINARY_OPERATOR(id, rid, op, expr) \ +template struct op_impl { \ + static char const* name() { return "__" #id "__"; } \ + static auto execute(const L &l, const R &r) -> decltype(expr) { return (expr); } \ + static B execute_cast(const L &l, const R &r) { return B(expr); } \ +}; \ +template struct op_impl { \ + static char const* name() { return "__" #rid "__"; } \ + static auto execute(const R &r, const L &l) -> decltype(expr) { return (expr); } \ + static B execute_cast(const R &r, const L &l) { return B(expr); } \ +}; \ +inline op_ op(const self_t &, const self_t &) { \ + return op_(); \ +} \ +template op_ op(const self_t &, const T &) { \ + return op_(); \ +} \ +template op_ op(const T &, const self_t &) { \ + return op_(); \ +} + +#define PYBIND11_INPLACE_OPERATOR(id, op, expr) \ +template struct op_impl { \ + static char const* name() { return "__" #id "__"; } \ + static auto execute(L &l, const R &r) -> decltype(expr) { return expr; } \ + static B execute_cast(L &l, const R &r) { return B(expr); } \ +}; \ +template op_ op(const self_t &, const T &) { \ + return op_(); \ +} + +#define PYBIND11_UNARY_OPERATOR(id, op, expr) \ +template struct op_impl { \ + static char const* name() { return "__" #id "__"; } \ + static auto execute(const L &l) -> decltype(expr) { return expr; } \ + static B execute_cast(const L &l) { return B(expr); } \ +}; \ +inline op_ op(const self_t &) { \ + return op_(); \ +} + +PYBIND11_BINARY_OPERATOR(sub, rsub, operator-, l - r) +PYBIND11_BINARY_OPERATOR(add, radd, operator+, l + r) +PYBIND11_BINARY_OPERATOR(mul, rmul, operator*, l * r) +PYBIND11_BINARY_OPERATOR(truediv, rtruediv, operator/, l / r) +PYBIND11_BINARY_OPERATOR(mod, rmod, operator%, l % r) +PYBIND11_BINARY_OPERATOR(lshift, rlshift, operator<<, l << r) +PYBIND11_BINARY_OPERATOR(rshift, rrshift, operator>>, l >> r) +PYBIND11_BINARY_OPERATOR(and, rand, operator&, l & r) +PYBIND11_BINARY_OPERATOR(xor, rxor, operator^, l ^ r) +PYBIND11_BINARY_OPERATOR(eq, eq, operator==, l == r) +PYBIND11_BINARY_OPERATOR(ne, ne, operator!=, l != r) +PYBIND11_BINARY_OPERATOR(or, ror, operator|, l | r) +PYBIND11_BINARY_OPERATOR(gt, lt, operator>, l > r) +PYBIND11_BINARY_OPERATOR(ge, le, operator>=, l >= r) +PYBIND11_BINARY_OPERATOR(lt, gt, operator<, l < r) +PYBIND11_BINARY_OPERATOR(le, ge, operator<=, l <= r) +//PYBIND11_BINARY_OPERATOR(pow, rpow, pow, std::pow(l, r)) +PYBIND11_INPLACE_OPERATOR(iadd, operator+=, l += r) +PYBIND11_INPLACE_OPERATOR(isub, operator-=, l -= r) +PYBIND11_INPLACE_OPERATOR(imul, operator*=, l *= r) +PYBIND11_INPLACE_OPERATOR(itruediv, operator/=, l /= r) +PYBIND11_INPLACE_OPERATOR(imod, operator%=, l %= r) +PYBIND11_INPLACE_OPERATOR(ilshift, operator<<=, l <<= r) +PYBIND11_INPLACE_OPERATOR(irshift, operator>>=, l >>= r) +PYBIND11_INPLACE_OPERATOR(iand, operator&=, l &= r) +PYBIND11_INPLACE_OPERATOR(ixor, operator^=, l ^= r) +PYBIND11_INPLACE_OPERATOR(ior, operator|=, l |= r) +PYBIND11_UNARY_OPERATOR(neg, operator-, -l) +PYBIND11_UNARY_OPERATOR(pos, operator+, +l) +PYBIND11_UNARY_OPERATOR(abs, abs, std::abs(l)) +PYBIND11_UNARY_OPERATOR(hash, hash, std::hash()(l)) +PYBIND11_UNARY_OPERATOR(invert, operator~, (~l)) +PYBIND11_UNARY_OPERATOR(bool, operator!, !!l) +PYBIND11_UNARY_OPERATOR(int, int_, (int) l) +PYBIND11_UNARY_OPERATOR(float, float_, (double) l) + +#undef PYBIND11_BINARY_OPERATOR +#undef PYBIND11_INPLACE_OPERATOR +#undef PYBIND11_UNARY_OPERATOR +NAMESPACE_END(detail) + +using detail::self; + +NAMESPACE_END(PYBIND11_NAMESPACE) + +#if defined(_MSC_VER) +# pragma warning(pop) +#endif diff --git a/wrap/python/pybind11/include/pybind11/options.h b/wrap/python/pybind11/include/pybind11/options.h new file mode 100644 index 000000000..cc1e1f6f0 --- /dev/null +++ b/wrap/python/pybind11/include/pybind11/options.h @@ -0,0 +1,65 @@ +/* + pybind11/options.h: global settings that are configurable at runtime. + + Copyright (c) 2016 Wenzel Jakob + + All rights reserved. Use of this source code is governed by a + BSD-style license that can be found in the LICENSE file. +*/ + +#pragma once + +#include "detail/common.h" + +NAMESPACE_BEGIN(PYBIND11_NAMESPACE) + +class options { +public: + + // Default RAII constructor, which leaves settings as they currently are. + options() : previous_state(global_state()) {} + + // Class is non-copyable. + options(const options&) = delete; + options& operator=(const options&) = delete; + + // Destructor, which restores settings that were in effect before. + ~options() { + global_state() = previous_state; + } + + // Setter methods (affect the global state): + + options& disable_user_defined_docstrings() & { global_state().show_user_defined_docstrings = false; return *this; } + + options& enable_user_defined_docstrings() & { global_state().show_user_defined_docstrings = true; return *this; } + + options& disable_function_signatures() & { global_state().show_function_signatures = false; return *this; } + + options& enable_function_signatures() & { global_state().show_function_signatures = true; return *this; } + + // Getter methods (return the global state): + + static bool show_user_defined_docstrings() { return global_state().show_user_defined_docstrings; } + + static bool show_function_signatures() { return global_state().show_function_signatures; } + + // This type is not meant to be allocated on the heap. + void* operator new(size_t) = delete; + +private: + + struct state { + bool show_user_defined_docstrings = true; //< Include user-supplied texts in docstrings. + bool show_function_signatures = true; //< Include auto-generated function signatures in docstrings. + }; + + static state &global_state() { + static state instance; + return instance; + } + + state previous_state; +}; + +NAMESPACE_END(PYBIND11_NAMESPACE) diff --git a/wrap/python/pybind11/include/pybind11/pybind11.h b/wrap/python/pybind11/include/pybind11/pybind11.h new file mode 100644 index 000000000..f1d91c788 --- /dev/null +++ b/wrap/python/pybind11/include/pybind11/pybind11.h @@ -0,0 +1,2162 @@ +/* + pybind11/pybind11.h: Main header file of the C++11 python + binding generator library + + Copyright (c) 2016 Wenzel Jakob + + All rights reserved. Use of this source code is governed by a + BSD-style license that can be found in the LICENSE file. +*/ + +#pragma once + +#if defined(__INTEL_COMPILER) +# pragma warning push +# pragma warning disable 68 // integer conversion resulted in a change of sign +# pragma warning disable 186 // pointless comparison of unsigned integer with zero +# pragma warning disable 878 // incompatible exception specifications +# pragma warning disable 1334 // the "template" keyword used for syntactic disambiguation may only be used within a template +# pragma warning disable 1682 // implicit conversion of a 64-bit integral type to a smaller integral type (potential portability problem) +# pragma warning disable 1786 // function "strdup" was declared deprecated +# pragma warning disable 1875 // offsetof applied to non-POD (Plain Old Data) types is nonstandard +# pragma warning disable 2196 // warning #2196: routine is both "inline" and "noinline" +#elif defined(_MSC_VER) +# pragma warning(push) +# pragma warning(disable: 4100) // warning C4100: Unreferenced formal parameter +# pragma warning(disable: 4127) // warning C4127: Conditional expression is constant +# pragma warning(disable: 4512) // warning C4512: Assignment operator was implicitly defined as deleted +# pragma warning(disable: 4800) // warning C4800: 'int': forcing value to bool 'true' or 'false' (performance warning) +# pragma warning(disable: 4996) // warning C4996: The POSIX name for this item is deprecated. Instead, use the ISO C and C++ conformant name +# pragma warning(disable: 4702) // warning C4702: unreachable code +# pragma warning(disable: 4522) // warning C4522: multiple assignment operators specified +#elif defined(__GNUG__) && !defined(__clang__) +# pragma GCC diagnostic push +# pragma GCC diagnostic ignored "-Wunused-but-set-parameter" +# pragma GCC diagnostic ignored "-Wunused-but-set-variable" +# pragma GCC diagnostic ignored "-Wmissing-field-initializers" +# pragma GCC diagnostic ignored "-Wstrict-aliasing" +# pragma GCC diagnostic ignored "-Wattributes" +# if __GNUC__ >= 7 +# pragma GCC diagnostic ignored "-Wnoexcept-type" +# endif +#endif + +#if defined(__GNUG__) && !defined(__clang__) + #include +#endif + + +#include "attr.h" +#include "options.h" +#include "detail/class.h" +#include "detail/init.h" + +NAMESPACE_BEGIN(PYBIND11_NAMESPACE) + +/// Wraps an arbitrary C++ function/method/lambda function/.. into a callable Python object +class cpp_function : public function { +public: + cpp_function() { } + cpp_function(std::nullptr_t) { } + + /// Construct a cpp_function from a vanilla function pointer + template + cpp_function(Return (*f)(Args...), const Extra&... extra) { + initialize(f, f, extra...); + } + + /// Construct a cpp_function from a lambda function (possibly with internal state) + template ::value>> + cpp_function(Func &&f, const Extra&... extra) { + initialize(std::forward(f), + (detail::function_signature_t *) nullptr, extra...); + } + + /// Construct a cpp_function from a class method (non-const) + template + cpp_function(Return (Class::*f)(Arg...), const Extra&... extra) { + initialize([f](Class *c, Arg... args) -> Return { return (c->*f)(args...); }, + (Return (*) (Class *, Arg...)) nullptr, extra...); + } + + /// Construct a cpp_function from a class method (const) + template + cpp_function(Return (Class::*f)(Arg...) const, const Extra&... extra) { + initialize([f](const Class *c, Arg... args) -> Return { return (c->*f)(args...); }, + (Return (*)(const Class *, Arg ...)) nullptr, extra...); + } + + /// Return the function name + object name() const { return attr("__name__"); } + +protected: + /// Space optimization: don't inline this frequently instantiated fragment + PYBIND11_NOINLINE detail::function_record *make_function_record() { + return new detail::function_record(); + } + + /// Special internal constructor for functors, lambda functions, etc. + template + void initialize(Func &&f, Return (*)(Args...), const Extra&... extra) { + using namespace detail; + struct capture { remove_reference_t f; }; + + /* Store the function including any extra state it might have (e.g. a lambda capture object) */ + auto rec = make_function_record(); + + /* Store the capture object directly in the function record if there is enough space */ + if (sizeof(capture) <= sizeof(rec->data)) { + /* Without these pragmas, GCC warns that there might not be + enough space to use the placement new operator. However, the + 'if' statement above ensures that this is the case. */ +#if defined(__GNUG__) && !defined(__clang__) && __GNUC__ >= 6 +# pragma GCC diagnostic push +# pragma GCC diagnostic ignored "-Wplacement-new" +#endif + new ((capture *) &rec->data) capture { std::forward(f) }; +#if defined(__GNUG__) && !defined(__clang__) && __GNUC__ >= 6 +# pragma GCC diagnostic pop +#endif + if (!std::is_trivially_destructible::value) + rec->free_data = [](function_record *r) { ((capture *) &r->data)->~capture(); }; + } else { + rec->data[0] = new capture { std::forward(f) }; + rec->free_data = [](function_record *r) { delete ((capture *) r->data[0]); }; + } + + /* Type casters for the function arguments and return value */ + using cast_in = argument_loader; + using cast_out = make_caster< + conditional_t::value, void_type, Return> + >; + + static_assert(expected_num_args(sizeof...(Args), cast_in::has_args, cast_in::has_kwargs), + "The number of argument annotations does not match the number of function arguments"); + + /* Dispatch code which converts function arguments and performs the actual function call */ + rec->impl = [](function_call &call) -> handle { + cast_in args_converter; + + /* Try to cast the function arguments into the C++ domain */ + if (!args_converter.load_args(call)) + return PYBIND11_TRY_NEXT_OVERLOAD; + + /* Invoke call policy pre-call hook */ + process_attributes::precall(call); + + /* Get a pointer to the capture object */ + auto data = (sizeof(capture) <= sizeof(call.func.data) + ? &call.func.data : call.func.data[0]); + capture *cap = const_cast(reinterpret_cast(data)); + + /* Override policy for rvalues -- usually to enforce rvp::move on an rvalue */ + return_value_policy policy = return_value_policy_override::policy(call.func.policy); + + /* Function scope guard -- defaults to the compile-to-nothing `void_type` */ + using Guard = extract_guard_t; + + /* Perform the function call */ + handle result = cast_out::cast( + std::move(args_converter).template call(cap->f), policy, call.parent); + + /* Invoke call policy post-call hook */ + process_attributes::postcall(call, result); + + return result; + }; + + /* Process any user-provided function attributes */ + process_attributes::init(extra..., rec); + + /* Generate a readable signature describing the function's arguments and return value types */ + static constexpr auto signature = _("(") + cast_in::arg_names + _(") -> ") + cast_out::name; + PYBIND11_DESCR_CONSTEXPR auto types = decltype(signature)::types(); + + /* Register the function with Python from generic (non-templated) code */ + initialize_generic(rec, signature.text, types.data(), sizeof...(Args)); + + if (cast_in::has_args) rec->has_args = true; + if (cast_in::has_kwargs) rec->has_kwargs = true; + + /* Stash some additional information used by an important optimization in 'functional.h' */ + using FunctionType = Return (*)(Args...); + constexpr bool is_function_ptr = + std::is_convertible::value && + sizeof(capture) == sizeof(void *); + if (is_function_ptr) { + rec->is_stateless = true; + rec->data[1] = const_cast(reinterpret_cast(&typeid(FunctionType))); + } + } + + /// Register a function call with Python (generic non-templated code goes here) + void initialize_generic(detail::function_record *rec, const char *text, + const std::type_info *const *types, size_t args) { + + /* Create copies of all referenced C-style strings */ + rec->name = strdup(rec->name ? rec->name : ""); + if (rec->doc) rec->doc = strdup(rec->doc); + for (auto &a: rec->args) { + if (a.name) + a.name = strdup(a.name); + if (a.descr) + a.descr = strdup(a.descr); + else if (a.value) + a.descr = strdup(a.value.attr("__repr__")().cast().c_str()); + } + + rec->is_constructor = !strcmp(rec->name, "__init__") || !strcmp(rec->name, "__setstate__"); + +#if !defined(NDEBUG) && !defined(PYBIND11_DISABLE_NEW_STYLE_INIT_WARNING) + if (rec->is_constructor && !rec->is_new_style_constructor) { + const auto class_name = std::string(((PyTypeObject *) rec->scope.ptr())->tp_name); + const auto func_name = std::string(rec->name); + PyErr_WarnEx( + PyExc_FutureWarning, + ("pybind11-bound class '" + class_name + "' is using an old-style " + "placement-new '" + func_name + "' which has been deprecated. See " + "the upgrade guide in pybind11's docs. This message is only visible " + "when compiled in debug mode.").c_str(), 0 + ); + } +#endif + + /* Generate a proper function signature */ + std::string signature; + size_t type_index = 0, arg_index = 0; + for (auto *pc = text; *pc != '\0'; ++pc) { + const auto c = *pc; + + if (c == '{') { + // Write arg name for everything except *args and **kwargs. + if (*(pc + 1) == '*') + continue; + + if (arg_index < rec->args.size() && rec->args[arg_index].name) { + signature += rec->args[arg_index].name; + } else if (arg_index == 0 && rec->is_method) { + signature += "self"; + } else { + signature += "arg" + std::to_string(arg_index - (rec->is_method ? 1 : 0)); + } + signature += ": "; + } else if (c == '}') { + // Write default value if available. + if (arg_index < rec->args.size() && rec->args[arg_index].descr) { + signature += " = "; + signature += rec->args[arg_index].descr; + } + arg_index++; + } else if (c == '%') { + const std::type_info *t = types[type_index++]; + if (!t) + pybind11_fail("Internal error while parsing type signature (1)"); + if (auto tinfo = detail::get_type_info(*t)) { + handle th((PyObject *) tinfo->type); + signature += + th.attr("__module__").cast() + "." + + th.attr("__qualname__").cast(); // Python 3.3+, but we backport it to earlier versions + } else if (rec->is_new_style_constructor && arg_index == 0) { + // A new-style `__init__` takes `self` as `value_and_holder`. + // Rewrite it to the proper class type. + signature += + rec->scope.attr("__module__").cast() + "." + + rec->scope.attr("__qualname__").cast(); + } else { + std::string tname(t->name()); + detail::clean_type_id(tname); + signature += tname; + } + } else { + signature += c; + } + } + if (arg_index != args || types[type_index] != nullptr) + pybind11_fail("Internal error while parsing type signature (2)"); + +#if PY_MAJOR_VERSION < 3 + if (strcmp(rec->name, "__next__") == 0) { + std::free(rec->name); + rec->name = strdup("next"); + } else if (strcmp(rec->name, "__bool__") == 0) { + std::free(rec->name); + rec->name = strdup("__nonzero__"); + } +#endif + rec->signature = strdup(signature.c_str()); + rec->args.shrink_to_fit(); + rec->nargs = (std::uint16_t) args; + + if (rec->sibling && PYBIND11_INSTANCE_METHOD_CHECK(rec->sibling.ptr())) + rec->sibling = PYBIND11_INSTANCE_METHOD_GET_FUNCTION(rec->sibling.ptr()); + + detail::function_record *chain = nullptr, *chain_start = rec; + if (rec->sibling) { + if (PyCFunction_Check(rec->sibling.ptr())) { + auto rec_capsule = reinterpret_borrow(PyCFunction_GET_SELF(rec->sibling.ptr())); + chain = (detail::function_record *) rec_capsule; + /* Never append a method to an overload chain of a parent class; + instead, hide the parent's overloads in this case */ + if (!chain->scope.is(rec->scope)) + chain = nullptr; + } + // Don't trigger for things like the default __init__, which are wrapper_descriptors that we are intentionally replacing + else if (!rec->sibling.is_none() && rec->name[0] != '_') + pybind11_fail("Cannot overload existing non-function object \"" + std::string(rec->name) + + "\" with a function of the same name"); + } + + if (!chain) { + /* No existing overload was found, create a new function object */ + rec->def = new PyMethodDef(); + std::memset(rec->def, 0, sizeof(PyMethodDef)); + rec->def->ml_name = rec->name; + rec->def->ml_meth = reinterpret_cast(reinterpret_cast(*dispatcher)); + rec->def->ml_flags = METH_VARARGS | METH_KEYWORDS; + + capsule rec_capsule(rec, [](void *ptr) { + destruct((detail::function_record *) ptr); + }); + + object scope_module; + if (rec->scope) { + if (hasattr(rec->scope, "__module__")) { + scope_module = rec->scope.attr("__module__"); + } else if (hasattr(rec->scope, "__name__")) { + scope_module = rec->scope.attr("__name__"); + } + } + + m_ptr = PyCFunction_NewEx(rec->def, rec_capsule.ptr(), scope_module.ptr()); + if (!m_ptr) + pybind11_fail("cpp_function::cpp_function(): Could not allocate function object"); + } else { + /* Append at the end of the overload chain */ + m_ptr = rec->sibling.ptr(); + inc_ref(); + chain_start = chain; + if (chain->is_method != rec->is_method) + pybind11_fail("overloading a method with both static and instance methods is not supported; " + #if defined(NDEBUG) + "compile in debug mode for more details" + #else + "error while attempting to bind " + std::string(rec->is_method ? "instance" : "static") + " method " + + std::string(pybind11::str(rec->scope.attr("__name__"))) + "." + std::string(rec->name) + signature + #endif + ); + while (chain->next) + chain = chain->next; + chain->next = rec; + } + + std::string signatures; + int index = 0; + /* Create a nice pydoc rec including all signatures and + docstrings of the functions in the overload chain */ + if (chain && options::show_function_signatures()) { + // First a generic signature + signatures += rec->name; + signatures += "(*args, **kwargs)\n"; + signatures += "Overloaded function.\n\n"; + } + // Then specific overload signatures + bool first_user_def = true; + for (auto it = chain_start; it != nullptr; it = it->next) { + if (options::show_function_signatures()) { + if (index > 0) signatures += "\n"; + if (chain) + signatures += std::to_string(++index) + ". "; + signatures += rec->name; + signatures += it->signature; + signatures += "\n"; + } + if (it->doc && strlen(it->doc) > 0 && options::show_user_defined_docstrings()) { + // If we're appending another docstring, and aren't printing function signatures, we + // need to append a newline first: + if (!options::show_function_signatures()) { + if (first_user_def) first_user_def = false; + else signatures += "\n"; + } + if (options::show_function_signatures()) signatures += "\n"; + signatures += it->doc; + if (options::show_function_signatures()) signatures += "\n"; + } + } + + /* Install docstring */ + PyCFunctionObject *func = (PyCFunctionObject *) m_ptr; + if (func->m_ml->ml_doc) + std::free(const_cast(func->m_ml->ml_doc)); + func->m_ml->ml_doc = strdup(signatures.c_str()); + + if (rec->is_method) { + m_ptr = PYBIND11_INSTANCE_METHOD_NEW(m_ptr, rec->scope.ptr()); + if (!m_ptr) + pybind11_fail("cpp_function::cpp_function(): Could not allocate instance method object"); + Py_DECREF(func); + } + } + + /// When a cpp_function is GCed, release any memory allocated by pybind11 + static void destruct(detail::function_record *rec) { + while (rec) { + detail::function_record *next = rec->next; + if (rec->free_data) + rec->free_data(rec); + std::free((char *) rec->name); + std::free((char *) rec->doc); + std::free((char *) rec->signature); + for (auto &arg: rec->args) { + std::free(const_cast(arg.name)); + std::free(const_cast(arg.descr)); + arg.value.dec_ref(); + } + if (rec->def) { + std::free(const_cast(rec->def->ml_doc)); + delete rec->def; + } + delete rec; + rec = next; + } + } + + /// Main dispatch logic for calls to functions bound using pybind11 + static PyObject *dispatcher(PyObject *self, PyObject *args_in, PyObject *kwargs_in) { + using namespace detail; + + /* Iterator over the list of potentially admissible overloads */ + const function_record *overloads = (function_record *) PyCapsule_GetPointer(self, nullptr), + *it = overloads; + + /* Need to know how many arguments + keyword arguments there are to pick the right overload */ + const size_t n_args_in = (size_t) PyTuple_GET_SIZE(args_in); + + handle parent = n_args_in > 0 ? PyTuple_GET_ITEM(args_in, 0) : nullptr, + result = PYBIND11_TRY_NEXT_OVERLOAD; + + auto self_value_and_holder = value_and_holder(); + if (overloads->is_constructor) { + const auto tinfo = get_type_info((PyTypeObject *) overloads->scope.ptr()); + const auto pi = reinterpret_cast(parent.ptr()); + self_value_and_holder = pi->get_value_and_holder(tinfo, false); + + if (!self_value_and_holder.type || !self_value_and_holder.inst) { + PyErr_SetString(PyExc_TypeError, "__init__(self, ...) called with invalid `self` argument"); + return nullptr; + } + + // If this value is already registered it must mean __init__ is invoked multiple times; + // we really can't support that in C++, so just ignore the second __init__. + if (self_value_and_holder.instance_registered()) + return none().release().ptr(); + } + + try { + // We do this in two passes: in the first pass, we load arguments with `convert=false`; + // in the second, we allow conversion (except for arguments with an explicit + // py::arg().noconvert()). This lets us prefer calls without conversion, with + // conversion as a fallback. + std::vector second_pass; + + // However, if there are no overloads, we can just skip the no-convert pass entirely + const bool overloaded = it != nullptr && it->next != nullptr; + + for (; it != nullptr; it = it->next) { + + /* For each overload: + 1. Copy all positional arguments we were given, also checking to make sure that + named positional arguments weren't *also* specified via kwarg. + 2. If we weren't given enough, try to make up the omitted ones by checking + whether they were provided by a kwarg matching the `py::arg("name")` name. If + so, use it (and remove it from kwargs; if not, see if the function binding + provided a default that we can use. + 3. Ensure that either all keyword arguments were "consumed", or that the function + takes a kwargs argument to accept unconsumed kwargs. + 4. Any positional arguments still left get put into a tuple (for args), and any + leftover kwargs get put into a dict. + 5. Pack everything into a vector; if we have py::args or py::kwargs, they are an + extra tuple or dict at the end of the positional arguments. + 6. Call the function call dispatcher (function_record::impl) + + If one of these fail, move on to the next overload and keep trying until we get a + result other than PYBIND11_TRY_NEXT_OVERLOAD. + */ + + const function_record &func = *it; + size_t pos_args = func.nargs; // Number of positional arguments that we need + if (func.has_args) --pos_args; // (but don't count py::args + if (func.has_kwargs) --pos_args; // or py::kwargs) + + if (!func.has_args && n_args_in > pos_args) + continue; // Too many arguments for this overload + + if (n_args_in < pos_args && func.args.size() < pos_args) + continue; // Not enough arguments given, and not enough defaults to fill in the blanks + + function_call call(func, parent); + + size_t args_to_copy = std::min(pos_args, n_args_in); + size_t args_copied = 0; + + // 0. Inject new-style `self` argument + if (func.is_new_style_constructor) { + // The `value` may have been preallocated by an old-style `__init__` + // if it was a preceding candidate for overload resolution. + if (self_value_and_holder) + self_value_and_holder.type->dealloc(self_value_and_holder); + + call.init_self = PyTuple_GET_ITEM(args_in, 0); + call.args.push_back(reinterpret_cast(&self_value_and_holder)); + call.args_convert.push_back(false); + ++args_copied; + } + + // 1. Copy any position arguments given. + bool bad_arg = false; + for (; args_copied < args_to_copy; ++args_copied) { + const argument_record *arg_rec = args_copied < func.args.size() ? &func.args[args_copied] : nullptr; + if (kwargs_in && arg_rec && arg_rec->name && PyDict_GetItemString(kwargs_in, arg_rec->name)) { + bad_arg = true; + break; + } + + handle arg(PyTuple_GET_ITEM(args_in, args_copied)); + if (arg_rec && !arg_rec->none && arg.is_none()) { + bad_arg = true; + break; + } + call.args.push_back(arg); + call.args_convert.push_back(arg_rec ? arg_rec->convert : true); + } + if (bad_arg) + continue; // Maybe it was meant for another overload (issue #688) + + // We'll need to copy this if we steal some kwargs for defaults + dict kwargs = reinterpret_borrow(kwargs_in); + + // 2. Check kwargs and, failing that, defaults that may help complete the list + if (args_copied < pos_args) { + bool copied_kwargs = false; + + for (; args_copied < pos_args; ++args_copied) { + const auto &arg = func.args[args_copied]; + + handle value; + if (kwargs_in && arg.name) + value = PyDict_GetItemString(kwargs.ptr(), arg.name); + + if (value) { + // Consume a kwargs value + if (!copied_kwargs) { + kwargs = reinterpret_steal(PyDict_Copy(kwargs.ptr())); + copied_kwargs = true; + } + PyDict_DelItemString(kwargs.ptr(), arg.name); + } else if (arg.value) { + value = arg.value; + } + + if (value) { + call.args.push_back(value); + call.args_convert.push_back(arg.convert); + } + else + break; + } + + if (args_copied < pos_args) + continue; // Not enough arguments, defaults, or kwargs to fill the positional arguments + } + + // 3. Check everything was consumed (unless we have a kwargs arg) + if (kwargs && kwargs.size() > 0 && !func.has_kwargs) + continue; // Unconsumed kwargs, but no py::kwargs argument to accept them + + // 4a. If we have a py::args argument, create a new tuple with leftovers + if (func.has_args) { + tuple extra_args; + if (args_to_copy == 0) { + // We didn't copy out any position arguments from the args_in tuple, so we + // can reuse it directly without copying: + extra_args = reinterpret_borrow(args_in); + } else if (args_copied >= n_args_in) { + extra_args = tuple(0); + } else { + size_t args_size = n_args_in - args_copied; + extra_args = tuple(args_size); + for (size_t i = 0; i < args_size; ++i) { + extra_args[i] = PyTuple_GET_ITEM(args_in, args_copied + i); + } + } + call.args.push_back(extra_args); + call.args_convert.push_back(false); + call.args_ref = std::move(extra_args); + } + + // 4b. If we have a py::kwargs, pass on any remaining kwargs + if (func.has_kwargs) { + if (!kwargs.ptr()) + kwargs = dict(); // If we didn't get one, send an empty one + call.args.push_back(kwargs); + call.args_convert.push_back(false); + call.kwargs_ref = std::move(kwargs); + } + + // 5. Put everything in a vector. Not technically step 5, we've been building it + // in `call.args` all along. + #if !defined(NDEBUG) + if (call.args.size() != func.nargs || call.args_convert.size() != func.nargs) + pybind11_fail("Internal error: function call dispatcher inserted wrong number of arguments!"); + #endif + + std::vector second_pass_convert; + if (overloaded) { + // We're in the first no-convert pass, so swap out the conversion flags for a + // set of all-false flags. If the call fails, we'll swap the flags back in for + // the conversion-allowed call below. + second_pass_convert.resize(func.nargs, false); + call.args_convert.swap(second_pass_convert); + } + + // 6. Call the function. + try { + loader_life_support guard{}; + result = func.impl(call); + } catch (reference_cast_error &) { + result = PYBIND11_TRY_NEXT_OVERLOAD; + } + + if (result.ptr() != PYBIND11_TRY_NEXT_OVERLOAD) + break; + + if (overloaded) { + // The (overloaded) call failed; if the call has at least one argument that + // permits conversion (i.e. it hasn't been explicitly specified `.noconvert()`) + // then add this call to the list of second pass overloads to try. + for (size_t i = func.is_method ? 1 : 0; i < pos_args; i++) { + if (second_pass_convert[i]) { + // Found one: swap the converting flags back in and store the call for + // the second pass. + call.args_convert.swap(second_pass_convert); + second_pass.push_back(std::move(call)); + break; + } + } + } + } + + if (overloaded && !second_pass.empty() && result.ptr() == PYBIND11_TRY_NEXT_OVERLOAD) { + // The no-conversion pass finished without success, try again with conversion allowed + for (auto &call : second_pass) { + try { + loader_life_support guard{}; + result = call.func.impl(call); + } catch (reference_cast_error &) { + result = PYBIND11_TRY_NEXT_OVERLOAD; + } + + if (result.ptr() != PYBIND11_TRY_NEXT_OVERLOAD) { + // The error reporting logic below expects 'it' to be valid, as it would be + // if we'd encountered this failure in the first-pass loop. + if (!result) + it = &call.func; + break; + } + } + } + } catch (error_already_set &e) { + e.restore(); + return nullptr; +#if defined(__GNUG__) && !defined(__clang__) + } catch ( abi::__forced_unwind& ) { + throw; +#endif + } catch (...) { + /* When an exception is caught, give each registered exception + translator a chance to translate it to a Python exception + in reverse order of registration. + + A translator may choose to do one of the following: + + - catch the exception and call PyErr_SetString or PyErr_SetObject + to set a standard (or custom) Python exception, or + - do nothing and let the exception fall through to the next translator, or + - delegate translation to the next translator by throwing a new type of exception. */ + + auto last_exception = std::current_exception(); + auto ®istered_exception_translators = get_internals().registered_exception_translators; + for (auto& translator : registered_exception_translators) { + try { + translator(last_exception); + } catch (...) { + last_exception = std::current_exception(); + continue; + } + return nullptr; + } + PyErr_SetString(PyExc_SystemError, "Exception escaped from default exception translator!"); + return nullptr; + } + + auto append_note_if_missing_header_is_suspected = [](std::string &msg) { + if (msg.find("std::") != std::string::npos) { + msg += "\n\n" + "Did you forget to `#include `? Or ,\n" + ", , etc. Some automatic\n" + "conversions are optional and require extra headers to be included\n" + "when compiling your pybind11 module."; + } + }; + + if (result.ptr() == PYBIND11_TRY_NEXT_OVERLOAD) { + if (overloads->is_operator) + return handle(Py_NotImplemented).inc_ref().ptr(); + + std::string msg = std::string(overloads->name) + "(): incompatible " + + std::string(overloads->is_constructor ? "constructor" : "function") + + " arguments. The following argument types are supported:\n"; + + int ctr = 0; + for (const function_record *it2 = overloads; it2 != nullptr; it2 = it2->next) { + msg += " "+ std::to_string(++ctr) + ". "; + + bool wrote_sig = false; + if (overloads->is_constructor) { + // For a constructor, rewrite `(self: Object, arg0, ...) -> NoneType` as `Object(arg0, ...)` + std::string sig = it2->signature; + size_t start = sig.find('(') + 7; // skip "(self: " + if (start < sig.size()) { + // End at the , for the next argument + size_t end = sig.find(", "), next = end + 2; + size_t ret = sig.rfind(" -> "); + // Or the ), if there is no comma: + if (end >= sig.size()) next = end = sig.find(')'); + if (start < end && next < sig.size()) { + msg.append(sig, start, end - start); + msg += '('; + msg.append(sig, next, ret - next); + wrote_sig = true; + } + } + } + if (!wrote_sig) msg += it2->signature; + + msg += "\n"; + } + msg += "\nInvoked with: "; + auto args_ = reinterpret_borrow(args_in); + bool some_args = false; + for (size_t ti = overloads->is_constructor ? 1 : 0; ti < args_.size(); ++ti) { + if (!some_args) some_args = true; + else msg += ", "; + msg += pybind11::repr(args_[ti]); + } + if (kwargs_in) { + auto kwargs = reinterpret_borrow(kwargs_in); + if (kwargs.size() > 0) { + if (some_args) msg += "; "; + msg += "kwargs: "; + bool first = true; + for (auto kwarg : kwargs) { + if (first) first = false; + else msg += ", "; + msg += pybind11::str("{}={!r}").format(kwarg.first, kwarg.second); + } + } + } + + append_note_if_missing_header_is_suspected(msg); + PyErr_SetString(PyExc_TypeError, msg.c_str()); + return nullptr; + } else if (!result) { + std::string msg = "Unable to convert function return value to a " + "Python type! The signature was\n\t"; + msg += it->signature; + append_note_if_missing_header_is_suspected(msg); + PyErr_SetString(PyExc_TypeError, msg.c_str()); + return nullptr; + } else { + if (overloads->is_constructor && !self_value_and_holder.holder_constructed()) { + auto *pi = reinterpret_cast(parent.ptr()); + self_value_and_holder.type->init_instance(pi, nullptr); + } + return result.ptr(); + } + } +}; + +/// Wrapper for Python extension modules +class module : public object { +public: + PYBIND11_OBJECT_DEFAULT(module, object, PyModule_Check) + + /// Create a new top-level Python module with the given name and docstring + explicit module(const char *name, const char *doc = nullptr) { + if (!options::show_user_defined_docstrings()) doc = nullptr; +#if PY_MAJOR_VERSION >= 3 + PyModuleDef *def = new PyModuleDef(); + std::memset(def, 0, sizeof(PyModuleDef)); + def->m_name = name; + def->m_doc = doc; + def->m_size = -1; + Py_INCREF(def); + m_ptr = PyModule_Create(def); +#else + m_ptr = Py_InitModule3(name, nullptr, doc); +#endif + if (m_ptr == nullptr) + pybind11_fail("Internal error in module::module()"); + inc_ref(); + } + + /** \rst + Create Python binding for a new function within the module scope. ``Func`` + can be a plain C++ function, a function pointer, or a lambda function. For + details on the ``Extra&& ... extra`` argument, see section :ref:`extras`. + \endrst */ + template + module &def(const char *name_, Func &&f, const Extra& ... extra) { + cpp_function func(std::forward(f), name(name_), scope(*this), + sibling(getattr(*this, name_, none())), extra...); + // NB: allow overwriting here because cpp_function sets up a chain with the intention of + // overwriting (and has already checked internally that it isn't overwriting non-functions). + add_object(name_, func, true /* overwrite */); + return *this; + } + + /** \rst + Create and return a new Python submodule with the given name and docstring. + This also works recursively, i.e. + + .. code-block:: cpp + + py::module m("example", "pybind11 example plugin"); + py::module m2 = m.def_submodule("sub", "A submodule of 'example'"); + py::module m3 = m2.def_submodule("subsub", "A submodule of 'example.sub'"); + \endrst */ + module def_submodule(const char *name, const char *doc = nullptr) { + std::string full_name = std::string(PyModule_GetName(m_ptr)) + + std::string(".") + std::string(name); + auto result = reinterpret_borrow(PyImport_AddModule(full_name.c_str())); + if (doc && options::show_user_defined_docstrings()) + result.attr("__doc__") = pybind11::str(doc); + attr(name) = result; + return result; + } + + /// Import and return a module or throws `error_already_set`. + static module import(const char *name) { + PyObject *obj = PyImport_ImportModule(name); + if (!obj) + throw error_already_set(); + return reinterpret_steal(obj); + } + + /// Reload the module or throws `error_already_set`. + void reload() { + PyObject *obj = PyImport_ReloadModule(ptr()); + if (!obj) + throw error_already_set(); + *this = reinterpret_steal(obj); + } + + // Adds an object to the module using the given name. Throws if an object with the given name + // already exists. + // + // overwrite should almost always be false: attempting to overwrite objects that pybind11 has + // established will, in most cases, break things. + PYBIND11_NOINLINE void add_object(const char *name, handle obj, bool overwrite = false) { + if (!overwrite && hasattr(*this, name)) + pybind11_fail("Error during initialization: multiple incompatible definitions with name \"" + + std::string(name) + "\""); + + PyModule_AddObject(ptr(), name, obj.inc_ref().ptr() /* steals a reference */); + } +}; + +/// \ingroup python_builtins +/// Return a dictionary representing the global variables in the current execution frame, +/// or ``__main__.__dict__`` if there is no frame (usually when the interpreter is embedded). +inline dict globals() { + PyObject *p = PyEval_GetGlobals(); + return reinterpret_borrow(p ? p : module::import("__main__").attr("__dict__").ptr()); +} + +NAMESPACE_BEGIN(detail) +/// Generic support for creating new Python heap types +class generic_type : public object { + template friend class class_; +public: + PYBIND11_OBJECT_DEFAULT(generic_type, object, PyType_Check) +protected: + void initialize(const type_record &rec) { + if (rec.scope && hasattr(rec.scope, rec.name)) + pybind11_fail("generic_type: cannot initialize type \"" + std::string(rec.name) + + "\": an object with that name is already defined"); + + if (rec.module_local ? get_local_type_info(*rec.type) : get_global_type_info(*rec.type)) + pybind11_fail("generic_type: type \"" + std::string(rec.name) + + "\" is already registered!"); + + m_ptr = make_new_python_type(rec); + + /* Register supplemental type information in C++ dict */ + auto *tinfo = new detail::type_info(); + tinfo->type = (PyTypeObject *) m_ptr; + tinfo->cpptype = rec.type; + tinfo->type_size = rec.type_size; + tinfo->type_align = rec.type_align; + tinfo->operator_new = rec.operator_new; + tinfo->holder_size_in_ptrs = size_in_ptrs(rec.holder_size); + tinfo->init_instance = rec.init_instance; + tinfo->dealloc = rec.dealloc; + tinfo->simple_type = true; + tinfo->simple_ancestors = true; + tinfo->default_holder = rec.default_holder; + tinfo->module_local = rec.module_local; + + auto &internals = get_internals(); + auto tindex = std::type_index(*rec.type); + tinfo->direct_conversions = &internals.direct_conversions[tindex]; + if (rec.module_local) + registered_local_types_cpp()[tindex] = tinfo; + else + internals.registered_types_cpp[tindex] = tinfo; + internals.registered_types_py[(PyTypeObject *) m_ptr] = { tinfo }; + + if (rec.bases.size() > 1 || rec.multiple_inheritance) { + mark_parents_nonsimple(tinfo->type); + tinfo->simple_ancestors = false; + } + else if (rec.bases.size() == 1) { + auto parent_tinfo = get_type_info((PyTypeObject *) rec.bases[0].ptr()); + tinfo->simple_ancestors = parent_tinfo->simple_ancestors; + } + + if (rec.module_local) { + // Stash the local typeinfo and loader so that external modules can access it. + tinfo->module_local_load = &type_caster_generic::local_load; + setattr(m_ptr, PYBIND11_MODULE_LOCAL_ID, capsule(tinfo)); + } + } + + /// Helper function which tags all parents of a type using mult. inheritance + void mark_parents_nonsimple(PyTypeObject *value) { + auto t = reinterpret_borrow(value->tp_bases); + for (handle h : t) { + auto tinfo2 = get_type_info((PyTypeObject *) h.ptr()); + if (tinfo2) + tinfo2->simple_type = false; + mark_parents_nonsimple((PyTypeObject *) h.ptr()); + } + } + + void install_buffer_funcs( + buffer_info *(*get_buffer)(PyObject *, void *), + void *get_buffer_data) { + PyHeapTypeObject *type = (PyHeapTypeObject*) m_ptr; + auto tinfo = detail::get_type_info(&type->ht_type); + + if (!type->ht_type.tp_as_buffer) + pybind11_fail( + "To be able to register buffer protocol support for the type '" + + std::string(tinfo->type->tp_name) + + "' the associated class<>(..) invocation must " + "include the pybind11::buffer_protocol() annotation!"); + + tinfo->get_buffer = get_buffer; + tinfo->get_buffer_data = get_buffer_data; + } + + // rec_func must be set for either fget or fset. + void def_property_static_impl(const char *name, + handle fget, handle fset, + detail::function_record *rec_func) { + const auto is_static = rec_func && !(rec_func->is_method && rec_func->scope); + const auto has_doc = rec_func && rec_func->doc && pybind11::options::show_user_defined_docstrings(); + auto property = handle((PyObject *) (is_static ? get_internals().static_property_type + : &PyProperty_Type)); + attr(name) = property(fget.ptr() ? fget : none(), + fset.ptr() ? fset : none(), + /*deleter*/none(), + pybind11::str(has_doc ? rec_func->doc : "")); + } +}; + +/// Set the pointer to operator new if it exists. The cast is needed because it can be overloaded. +template (T::operator new))>> +void set_operator_new(type_record *r) { r->operator_new = &T::operator new; } + +template void set_operator_new(...) { } + +template struct has_operator_delete : std::false_type { }; +template struct has_operator_delete(T::operator delete))>> + : std::true_type { }; +template struct has_operator_delete_size : std::false_type { }; +template struct has_operator_delete_size(T::operator delete))>> + : std::true_type { }; +/// Call class-specific delete if it exists or global otherwise. Can also be an overload set. +template ::value, int> = 0> +void call_operator_delete(T *p, size_t, size_t) { T::operator delete(p); } +template ::value && has_operator_delete_size::value, int> = 0> +void call_operator_delete(T *p, size_t s, size_t) { T::operator delete(p, s); } + +inline void call_operator_delete(void *p, size_t s, size_t a) { + (void)s; (void)a; +#if defined(PYBIND11_CPP17) + if (a > __STDCPP_DEFAULT_NEW_ALIGNMENT__) + ::operator delete(p, s, std::align_val_t(a)); + else + ::operator delete(p, s); +#else + ::operator delete(p); +#endif +} + +NAMESPACE_END(detail) + +/// Given a pointer to a member function, cast it to its `Derived` version. +/// Forward everything else unchanged. +template +auto method_adaptor(F &&f) -> decltype(std::forward(f)) { return std::forward(f); } + +template +auto method_adaptor(Return (Class::*pmf)(Args...)) -> Return (Derived::*)(Args...) { + static_assert(detail::is_accessible_base_of::value, + "Cannot bind an inaccessible base class method; use a lambda definition instead"); + return pmf; +} + +template +auto method_adaptor(Return (Class::*pmf)(Args...) const) -> Return (Derived::*)(Args...) const { + static_assert(detail::is_accessible_base_of::value, + "Cannot bind an inaccessible base class method; use a lambda definition instead"); + return pmf; +} + +template +class class_ : public detail::generic_type { + template using is_holder = detail::is_holder_type; + template using is_subtype = detail::is_strict_base_of; + template using is_base = detail::is_strict_base_of; + // struct instead of using here to help MSVC: + template struct is_valid_class_option : + detail::any_of, is_subtype, is_base> {}; + +public: + using type = type_; + using type_alias = detail::exactly_one_t; + constexpr static bool has_alias = !std::is_void::value; + using holder_type = detail::exactly_one_t, options...>; + + static_assert(detail::all_of...>::value, + "Unknown/invalid class_ template parameters provided"); + + static_assert(!has_alias || std::is_polymorphic::value, + "Cannot use an alias class with a non-polymorphic type"); + + PYBIND11_OBJECT(class_, generic_type, PyType_Check) + + template + class_(handle scope, const char *name, const Extra &... extra) { + using namespace detail; + + // MI can only be specified via class_ template options, not constructor parameters + static_assert( + none_of...>::value || // no base class arguments, or: + ( constexpr_sum(is_pyobject::value...) == 1 && // Exactly one base + constexpr_sum(is_base::value...) == 0 && // no template option bases + none_of...>::value), // no multiple_inheritance attr + "Error: multiple inheritance bases must be specified via class_ template options"); + + type_record record; + record.scope = scope; + record.name = name; + record.type = &typeid(type); + record.type_size = sizeof(conditional_t); + record.type_align = alignof(conditional_t&); + record.holder_size = sizeof(holder_type); + record.init_instance = init_instance; + record.dealloc = dealloc; + record.default_holder = detail::is_instantiation::value; + + set_operator_new(&record); + + /* Register base classes specified via template arguments to class_, if any */ + PYBIND11_EXPAND_SIDE_EFFECTS(add_base(record)); + + /* Process optional arguments, if any */ + process_attributes::init(extra..., &record); + + generic_type::initialize(record); + + if (has_alias) { + auto &instances = record.module_local ? registered_local_types_cpp() : get_internals().registered_types_cpp; + instances[std::type_index(typeid(type_alias))] = instances[std::type_index(typeid(type))]; + } + } + + template ::value, int> = 0> + static void add_base(detail::type_record &rec) { + rec.add_base(typeid(Base), [](void *src) -> void * { + return static_cast(reinterpret_cast(src)); + }); + } + + template ::value, int> = 0> + static void add_base(detail::type_record &) { } + + template + class_ &def(const char *name_, Func&& f, const Extra&... extra) { + cpp_function cf(method_adaptor(std::forward(f)), name(name_), is_method(*this), + sibling(getattr(*this, name_, none())), extra...); + attr(cf.name()) = cf; + return *this; + } + + template class_ & + def_static(const char *name_, Func &&f, const Extra&... extra) { + static_assert(!std::is_member_function_pointer::value, + "def_static(...) called with a non-static member function pointer"); + cpp_function cf(std::forward(f), name(name_), scope(*this), + sibling(getattr(*this, name_, none())), extra...); + attr(cf.name()) = staticmethod(cf); + return *this; + } + + template + class_ &def(const detail::op_ &op, const Extra&... extra) { + op.execute(*this, extra...); + return *this; + } + + template + class_ & def_cast(const detail::op_ &op, const Extra&... extra) { + op.execute_cast(*this, extra...); + return *this; + } + + template + class_ &def(const detail::initimpl::constructor &init, const Extra&... extra) { + init.execute(*this, extra...); + return *this; + } + + template + class_ &def(const detail::initimpl::alias_constructor &init, const Extra&... extra) { + init.execute(*this, extra...); + return *this; + } + + template + class_ &def(detail::initimpl::factory &&init, const Extra&... extra) { + std::move(init).execute(*this, extra...); + return *this; + } + + template + class_ &def(detail::initimpl::pickle_factory &&pf, const Extra &...extra) { + std::move(pf).execute(*this, extra...); + return *this; + } + + template class_& def_buffer(Func &&func) { + struct capture { Func func; }; + capture *ptr = new capture { std::forward(func) }; + install_buffer_funcs([](PyObject *obj, void *ptr) -> buffer_info* { + detail::make_caster caster; + if (!caster.load(obj, false)) + return nullptr; + return new buffer_info(((capture *) ptr)->func(caster)); + }, ptr); + return *this; + } + + template + class_ &def_buffer(Return (Class::*func)(Args...)) { + return def_buffer([func] (type &obj) { return (obj.*func)(); }); + } + + template + class_ &def_buffer(Return (Class::*func)(Args...) const) { + return def_buffer([func] (const type &obj) { return (obj.*func)(); }); + } + + template + class_ &def_readwrite(const char *name, D C::*pm, const Extra&... extra) { + static_assert(std::is_same::value || std::is_base_of::value, "def_readwrite() requires a class member (or base class member)"); + cpp_function fget([pm](const type &c) -> const D &{ return c.*pm; }, is_method(*this)), + fset([pm](type &c, const D &value) { c.*pm = value; }, is_method(*this)); + def_property(name, fget, fset, return_value_policy::reference_internal, extra...); + return *this; + } + + template + class_ &def_readonly(const char *name, const D C::*pm, const Extra& ...extra) { + static_assert(std::is_same::value || std::is_base_of::value, "def_readonly() requires a class member (or base class member)"); + cpp_function fget([pm](const type &c) -> const D &{ return c.*pm; }, is_method(*this)); + def_property_readonly(name, fget, return_value_policy::reference_internal, extra...); + return *this; + } + + template + class_ &def_readwrite_static(const char *name, D *pm, const Extra& ...extra) { + cpp_function fget([pm](object) -> const D &{ return *pm; }, scope(*this)), + fset([pm](object, const D &value) { *pm = value; }, scope(*this)); + def_property_static(name, fget, fset, return_value_policy::reference, extra...); + return *this; + } + + template + class_ &def_readonly_static(const char *name, const D *pm, const Extra& ...extra) { + cpp_function fget([pm](object) -> const D &{ return *pm; }, scope(*this)); + def_property_readonly_static(name, fget, return_value_policy::reference, extra...); + return *this; + } + + /// Uses return_value_policy::reference_internal by default + template + class_ &def_property_readonly(const char *name, const Getter &fget, const Extra& ...extra) { + return def_property_readonly(name, cpp_function(method_adaptor(fget)), + return_value_policy::reference_internal, extra...); + } + + /// Uses cpp_function's return_value_policy by default + template + class_ &def_property_readonly(const char *name, const cpp_function &fget, const Extra& ...extra) { + return def_property(name, fget, nullptr, extra...); + } + + /// Uses return_value_policy::reference by default + template + class_ &def_property_readonly_static(const char *name, const Getter &fget, const Extra& ...extra) { + return def_property_readonly_static(name, cpp_function(fget), return_value_policy::reference, extra...); + } + + /// Uses cpp_function's return_value_policy by default + template + class_ &def_property_readonly_static(const char *name, const cpp_function &fget, const Extra& ...extra) { + return def_property_static(name, fget, nullptr, extra...); + } + + /// Uses return_value_policy::reference_internal by default + template + class_ &def_property(const char *name, const Getter &fget, const Setter &fset, const Extra& ...extra) { + return def_property(name, fget, cpp_function(method_adaptor(fset)), extra...); + } + template + class_ &def_property(const char *name, const Getter &fget, const cpp_function &fset, const Extra& ...extra) { + return def_property(name, cpp_function(method_adaptor(fget)), fset, + return_value_policy::reference_internal, extra...); + } + + /// Uses cpp_function's return_value_policy by default + template + class_ &def_property(const char *name, const cpp_function &fget, const cpp_function &fset, const Extra& ...extra) { + return def_property_static(name, fget, fset, is_method(*this), extra...); + } + + /// Uses return_value_policy::reference by default + template + class_ &def_property_static(const char *name, const Getter &fget, const cpp_function &fset, const Extra& ...extra) { + return def_property_static(name, cpp_function(fget), fset, return_value_policy::reference, extra...); + } + + /// Uses cpp_function's return_value_policy by default + template + class_ &def_property_static(const char *name, const cpp_function &fget, const cpp_function &fset, const Extra& ...extra) { + static_assert( 0 == detail::constexpr_sum(std::is_base_of::value...), + "Argument annotations are not allowed for properties"); + auto rec_fget = get_function_record(fget), rec_fset = get_function_record(fset); + auto *rec_active = rec_fget; + if (rec_fget) { + char *doc_prev = rec_fget->doc; /* 'extra' field may include a property-specific documentation string */ + detail::process_attributes::init(extra..., rec_fget); + if (rec_fget->doc && rec_fget->doc != doc_prev) { + free(doc_prev); + rec_fget->doc = strdup(rec_fget->doc); + } + } + if (rec_fset) { + char *doc_prev = rec_fset->doc; + detail::process_attributes::init(extra..., rec_fset); + if (rec_fset->doc && rec_fset->doc != doc_prev) { + free(doc_prev); + rec_fset->doc = strdup(rec_fset->doc); + } + if (! rec_active) rec_active = rec_fset; + } + def_property_static_impl(name, fget, fset, rec_active); + return *this; + } + +private: + /// Initialize holder object, variant 1: object derives from enable_shared_from_this + template + static void init_holder(detail::instance *inst, detail::value_and_holder &v_h, + const holder_type * /* unused */, const std::enable_shared_from_this * /* dummy */) { + try { + auto sh = std::dynamic_pointer_cast( + v_h.value_ptr()->shared_from_this()); + if (sh) { + new (std::addressof(v_h.holder())) holder_type(std::move(sh)); + v_h.set_holder_constructed(); + } + } catch (const std::bad_weak_ptr &) {} + + if (!v_h.holder_constructed() && inst->owned) { + new (std::addressof(v_h.holder())) holder_type(v_h.value_ptr()); + v_h.set_holder_constructed(); + } + } + + static void init_holder_from_existing(const detail::value_and_holder &v_h, + const holder_type *holder_ptr, std::true_type /*is_copy_constructible*/) { + new (std::addressof(v_h.holder())) holder_type(*reinterpret_cast(holder_ptr)); + } + + static void init_holder_from_existing(const detail::value_and_holder &v_h, + const holder_type *holder_ptr, std::false_type /*is_copy_constructible*/) { + new (std::addressof(v_h.holder())) holder_type(std::move(*const_cast(holder_ptr))); + } + + /// Initialize holder object, variant 2: try to construct from existing holder object, if possible + static void init_holder(detail::instance *inst, detail::value_and_holder &v_h, + const holder_type *holder_ptr, const void * /* dummy -- not enable_shared_from_this) */) { + if (holder_ptr) { + init_holder_from_existing(v_h, holder_ptr, std::is_copy_constructible()); + v_h.set_holder_constructed(); + } else if (inst->owned || detail::always_construct_holder::value) { + new (std::addressof(v_h.holder())) holder_type(v_h.value_ptr()); + v_h.set_holder_constructed(); + } + } + + /// Performs instance initialization including constructing a holder and registering the known + /// instance. Should be called as soon as the `type` value_ptr is set for an instance. Takes an + /// optional pointer to an existing holder to use; if not specified and the instance is + /// `.owned`, a new holder will be constructed to manage the value pointer. + static void init_instance(detail::instance *inst, const void *holder_ptr) { + auto v_h = inst->get_value_and_holder(detail::get_type_info(typeid(type))); + if (!v_h.instance_registered()) { + register_instance(inst, v_h.value_ptr(), v_h.type); + v_h.set_instance_registered(); + } + init_holder(inst, v_h, (const holder_type *) holder_ptr, v_h.value_ptr()); + } + + /// Deallocates an instance; via holder, if constructed; otherwise via operator delete. + static void dealloc(detail::value_and_holder &v_h) { + if (v_h.holder_constructed()) { + v_h.holder().~holder_type(); + v_h.set_holder_constructed(false); + } + else { + detail::call_operator_delete(v_h.value_ptr(), + v_h.type->type_size, + v_h.type->type_align + ); + } + v_h.value_ptr() = nullptr; + } + + static detail::function_record *get_function_record(handle h) { + h = detail::get_function(h); + return h ? (detail::function_record *) reinterpret_borrow(PyCFunction_GET_SELF(h.ptr())) + : nullptr; + } +}; + +/// Binds an existing constructor taking arguments Args... +template detail::initimpl::constructor init() { return {}; } +/// Like `init()`, but the instance is always constructed through the alias class (even +/// when not inheriting on the Python side). +template detail::initimpl::alias_constructor init_alias() { return {}; } + +/// Binds a factory function as a constructor +template > +Ret init(Func &&f) { return {std::forward(f)}; } + +/// Dual-argument factory function: the first function is called when no alias is needed, the second +/// when an alias is needed (i.e. due to python-side inheritance). Arguments must be identical. +template > +Ret init(CFunc &&c, AFunc &&a) { + return {std::forward(c), std::forward(a)}; +} + +/// Binds pickling functions `__getstate__` and `__setstate__` and ensures that the type +/// returned by `__getstate__` is the same as the argument accepted by `__setstate__`. +template +detail::initimpl::pickle_factory pickle(GetState &&g, SetState &&s) { + return {std::forward(g), std::forward(s)}; +} + +NAMESPACE_BEGIN(detail) +struct enum_base { + enum_base(handle base, handle parent) : m_base(base), m_parent(parent) { } + + PYBIND11_NOINLINE void init(bool is_arithmetic, bool is_convertible) { + m_base.attr("__entries") = dict(); + auto property = handle((PyObject *) &PyProperty_Type); + auto static_property = handle((PyObject *) get_internals().static_property_type); + + m_base.attr("__repr__") = cpp_function( + [](handle arg) -> str { + handle type = arg.get_type(); + object type_name = type.attr("__name__"); + dict entries = type.attr("__entries"); + for (const auto &kv : entries) { + object other = kv.second[int_(0)]; + if (other.equal(arg)) + return pybind11::str("{}.{}").format(type_name, kv.first); + } + return pybind11::str("{}.???").format(type_name); + }, is_method(m_base) + ); + + m_base.attr("name") = property(cpp_function( + [](handle arg) -> str { + dict entries = arg.get_type().attr("__entries"); + for (const auto &kv : entries) { + if (handle(kv.second[int_(0)]).equal(arg)) + return pybind11::str(kv.first); + } + return "???"; + }, is_method(m_base) + )); + + m_base.attr("__doc__") = static_property(cpp_function( + [](handle arg) -> std::string { + std::string docstring; + dict entries = arg.attr("__entries"); + if (((PyTypeObject *) arg.ptr())->tp_doc) + docstring += std::string(((PyTypeObject *) arg.ptr())->tp_doc) + "\n\n"; + docstring += "Members:"; + for (const auto &kv : entries) { + auto key = std::string(pybind11::str(kv.first)); + auto comment = kv.second[int_(1)]; + docstring += "\n\n " + key; + if (!comment.is_none()) + docstring += " : " + (std::string) pybind11::str(comment); + } + return docstring; + } + ), none(), none(), ""); + + m_base.attr("__members__") = static_property(cpp_function( + [](handle arg) -> dict { + dict entries = arg.attr("__entries"), m; + for (const auto &kv : entries) + m[kv.first] = kv.second[int_(0)]; + return m; + }), none(), none(), "" + ); + + #define PYBIND11_ENUM_OP_STRICT(op, expr, strict_behavior) \ + m_base.attr(op) = cpp_function( \ + [](object a, object b) { \ + if (!a.get_type().is(b.get_type())) \ + strict_behavior; \ + return expr; \ + }, \ + is_method(m_base)) + + #define PYBIND11_ENUM_OP_CONV(op, expr) \ + m_base.attr(op) = cpp_function( \ + [](object a_, object b_) { \ + int_ a(a_), b(b_); \ + return expr; \ + }, \ + is_method(m_base)) + + if (is_convertible) { + PYBIND11_ENUM_OP_CONV("__eq__", !b.is_none() && a.equal(b)); + PYBIND11_ENUM_OP_CONV("__ne__", b.is_none() || !a.equal(b)); + + if (is_arithmetic) { + PYBIND11_ENUM_OP_CONV("__lt__", a < b); + PYBIND11_ENUM_OP_CONV("__gt__", a > b); + PYBIND11_ENUM_OP_CONV("__le__", a <= b); + PYBIND11_ENUM_OP_CONV("__ge__", a >= b); + PYBIND11_ENUM_OP_CONV("__and__", a & b); + PYBIND11_ENUM_OP_CONV("__rand__", a & b); + PYBIND11_ENUM_OP_CONV("__or__", a | b); + PYBIND11_ENUM_OP_CONV("__ror__", a | b); + PYBIND11_ENUM_OP_CONV("__xor__", a ^ b); + PYBIND11_ENUM_OP_CONV("__rxor__", a ^ b); + } + } else { + PYBIND11_ENUM_OP_STRICT("__eq__", int_(a).equal(int_(b)), return false); + PYBIND11_ENUM_OP_STRICT("__ne__", !int_(a).equal(int_(b)), return true); + + if (is_arithmetic) { + #define PYBIND11_THROW throw type_error("Expected an enumeration of matching type!"); + PYBIND11_ENUM_OP_STRICT("__lt__", int_(a) < int_(b), PYBIND11_THROW); + PYBIND11_ENUM_OP_STRICT("__gt__", int_(a) > int_(b), PYBIND11_THROW); + PYBIND11_ENUM_OP_STRICT("__le__", int_(a) <= int_(b), PYBIND11_THROW); + PYBIND11_ENUM_OP_STRICT("__ge__", int_(a) >= int_(b), PYBIND11_THROW); + #undef PYBIND11_THROW + } + } + + #undef PYBIND11_ENUM_OP_CONV + #undef PYBIND11_ENUM_OP_STRICT + + object getstate = cpp_function( + [](object arg) { return int_(arg); }, is_method(m_base)); + + m_base.attr("__getstate__") = getstate; + m_base.attr("__hash__") = getstate; + } + + PYBIND11_NOINLINE void value(char const* name_, object value, const char *doc = nullptr) { + dict entries = m_base.attr("__entries"); + str name(name_); + if (entries.contains(name)) { + std::string type_name = (std::string) str(m_base.attr("__name__")); + throw value_error(type_name + ": element \"" + std::string(name_) + "\" already exists!"); + } + + entries[name] = std::make_pair(value, doc); + m_base.attr(name) = value; + } + + PYBIND11_NOINLINE void export_values() { + dict entries = m_base.attr("__entries"); + for (const auto &kv : entries) + m_parent.attr(kv.first) = kv.second[int_(0)]; + } + + handle m_base; + handle m_parent; +}; + +NAMESPACE_END(detail) + +/// Binds C++ enumerations and enumeration classes to Python +template class enum_ : public class_ { +public: + using Base = class_; + using Base::def; + using Base::attr; + using Base::def_property_readonly; + using Base::def_property_readonly_static; + using Scalar = typename std::underlying_type::type; + + template + enum_(const handle &scope, const char *name, const Extra&... extra) + : class_(scope, name, extra...), m_base(*this, scope) { + constexpr bool is_arithmetic = detail::any_of...>::value; + constexpr bool is_convertible = std::is_convertible::value; + m_base.init(is_arithmetic, is_convertible); + + def(init([](Scalar i) { return static_cast(i); })); + def("__int__", [](Type value) { return (Scalar) value; }); + #if PY_MAJOR_VERSION < 3 + def("__long__", [](Type value) { return (Scalar) value; }); + #endif + cpp_function setstate( + [](Type &value, Scalar arg) { value = static_cast(arg); }, + is_method(*this)); + attr("__setstate__") = setstate; + } + + /// Export enumeration entries into the parent scope + enum_& export_values() { + m_base.export_values(); + return *this; + } + + /// Add an enumeration entry + enum_& value(char const* name, Type value, const char *doc = nullptr) { + m_base.value(name, pybind11::cast(value, return_value_policy::copy), doc); + return *this; + } + +private: + detail::enum_base m_base; +}; + +NAMESPACE_BEGIN(detail) + + +inline void keep_alive_impl(handle nurse, handle patient) { + if (!nurse || !patient) + pybind11_fail("Could not activate keep_alive!"); + + if (patient.is_none() || nurse.is_none()) + return; /* Nothing to keep alive or nothing to be kept alive by */ + + auto tinfo = all_type_info(Py_TYPE(nurse.ptr())); + if (!tinfo.empty()) { + /* It's a pybind-registered type, so we can store the patient in the + * internal list. */ + add_patient(nurse.ptr(), patient.ptr()); + } + else { + /* Fall back to clever approach based on weak references taken from + * Boost.Python. This is not used for pybind-registered types because + * the objects can be destroyed out-of-order in a GC pass. */ + cpp_function disable_lifesupport( + [patient](handle weakref) { patient.dec_ref(); weakref.dec_ref(); }); + + weakref wr(nurse, disable_lifesupport); + + patient.inc_ref(); /* reference patient and leak the weak reference */ + (void) wr.release(); + } +} + +PYBIND11_NOINLINE inline void keep_alive_impl(size_t Nurse, size_t Patient, function_call &call, handle ret) { + auto get_arg = [&](size_t n) { + if (n == 0) + return ret; + else if (n == 1 && call.init_self) + return call.init_self; + else if (n <= call.args.size()) + return call.args[n - 1]; + return handle(); + }; + + keep_alive_impl(get_arg(Nurse), get_arg(Patient)); +} + +inline std::pair all_type_info_get_cache(PyTypeObject *type) { + auto res = get_internals().registered_types_py +#ifdef __cpp_lib_unordered_map_try_emplace + .try_emplace(type); +#else + .emplace(type, std::vector()); +#endif + if (res.second) { + // New cache entry created; set up a weak reference to automatically remove it if the type + // gets destroyed: + weakref((PyObject *) type, cpp_function([type](handle wr) { + get_internals().registered_types_py.erase(type); + wr.dec_ref(); + })).release(); + } + + return res; +} + +template +struct iterator_state { + Iterator it; + Sentinel end; + bool first_or_done; +}; + +NAMESPACE_END(detail) + +/// Makes a python iterator from a first and past-the-end C++ InputIterator. +template ()), + typename... Extra> +iterator make_iterator(Iterator first, Sentinel last, Extra &&... extra) { + typedef detail::iterator_state state; + + if (!detail::get_type_info(typeid(state), false)) { + class_(handle(), "iterator", pybind11::module_local()) + .def("__iter__", [](state &s) -> state& { return s; }) + .def("__next__", [](state &s) -> ValueType { + if (!s.first_or_done) + ++s.it; + else + s.first_or_done = false; + if (s.it == s.end) { + s.first_or_done = true; + throw stop_iteration(); + } + return *s.it; + }, std::forward(extra)..., Policy); + } + + return cast(state{first, last, true}); +} + +/// Makes an python iterator over the keys (`.first`) of a iterator over pairs from a +/// first and past-the-end InputIterator. +template ()).first), + typename... Extra> +iterator make_key_iterator(Iterator first, Sentinel last, Extra &&... extra) { + typedef detail::iterator_state state; + + if (!detail::get_type_info(typeid(state), false)) { + class_(handle(), "iterator", pybind11::module_local()) + .def("__iter__", [](state &s) -> state& { return s; }) + .def("__next__", [](state &s) -> KeyType { + if (!s.first_or_done) + ++s.it; + else + s.first_or_done = false; + if (s.it == s.end) { + s.first_or_done = true; + throw stop_iteration(); + } + return (*s.it).first; + }, std::forward(extra)..., Policy); + } + + return cast(state{first, last, true}); +} + +/// Makes an iterator over values of an stl container or other container supporting +/// `std::begin()`/`std::end()` +template iterator make_iterator(Type &value, Extra&&... extra) { + return make_iterator(std::begin(value), std::end(value), extra...); +} + +/// Makes an iterator over the keys (`.first`) of a stl map-like container supporting +/// `std::begin()`/`std::end()` +template iterator make_key_iterator(Type &value, Extra&&... extra) { + return make_key_iterator(std::begin(value), std::end(value), extra...); +} + +template void implicitly_convertible() { + struct set_flag { + bool &flag; + set_flag(bool &flag) : flag(flag) { flag = true; } + ~set_flag() { flag = false; } + }; + auto implicit_caster = [](PyObject *obj, PyTypeObject *type) -> PyObject * { + static bool currently_used = false; + if (currently_used) // implicit conversions are non-reentrant + return nullptr; + set_flag flag_helper(currently_used); + if (!detail::make_caster().load(obj, false)) + return nullptr; + tuple args(1); + args[0] = obj; + PyObject *result = PyObject_Call((PyObject *) type, args.ptr(), nullptr); + if (result == nullptr) + PyErr_Clear(); + return result; + }; + + if (auto tinfo = detail::get_type_info(typeid(OutputType))) + tinfo->implicit_conversions.push_back(implicit_caster); + else + pybind11_fail("implicitly_convertible: Unable to find type " + type_id()); +} + +template +void register_exception_translator(ExceptionTranslator&& translator) { + detail::get_internals().registered_exception_translators.push_front( + std::forward(translator)); +} + +/** + * Wrapper to generate a new Python exception type. + * + * This should only be used with PyErr_SetString for now. + * It is not (yet) possible to use as a py::base. + * Template type argument is reserved for future use. + */ +template +class exception : public object { +public: + exception() = default; + exception(handle scope, const char *name, PyObject *base = PyExc_Exception) { + std::string full_name = scope.attr("__name__").cast() + + std::string(".") + name; + m_ptr = PyErr_NewException(const_cast(full_name.c_str()), base, NULL); + if (hasattr(scope, name)) + pybind11_fail("Error during initialization: multiple incompatible " + "definitions with name \"" + std::string(name) + "\""); + scope.attr(name) = *this; + } + + // Sets the current python exception to this exception object with the given message + void operator()(const char *message) { + PyErr_SetString(m_ptr, message); + } +}; + +NAMESPACE_BEGIN(detail) +// Returns a reference to a function-local static exception object used in the simple +// register_exception approach below. (It would be simpler to have the static local variable +// directly in register_exception, but that makes clang <3.5 segfault - issue #1349). +template +exception &get_exception_object() { static exception ex; return ex; } +NAMESPACE_END(detail) + +/** + * Registers a Python exception in `m` of the given `name` and installs an exception translator to + * translate the C++ exception to the created Python exception using the exceptions what() method. + * This is intended for simple exception translations; for more complex translation, register the + * exception object and translator directly. + */ +template +exception ®ister_exception(handle scope, + const char *name, + PyObject *base = PyExc_Exception) { + auto &ex = detail::get_exception_object(); + if (!ex) ex = exception(scope, name, base); + + register_exception_translator([](std::exception_ptr p) { + if (!p) return; + try { + std::rethrow_exception(p); + } catch (const CppException &e) { + detail::get_exception_object()(e.what()); + } + }); + return ex; +} + +NAMESPACE_BEGIN(detail) +PYBIND11_NOINLINE inline void print(tuple args, dict kwargs) { + auto strings = tuple(args.size()); + for (size_t i = 0; i < args.size(); ++i) { + strings[i] = str(args[i]); + } + auto sep = kwargs.contains("sep") ? kwargs["sep"] : cast(" "); + auto line = sep.attr("join")(strings); + + object file; + if (kwargs.contains("file")) { + file = kwargs["file"].cast(); + } else { + try { + file = module::import("sys").attr("stdout"); + } catch (const error_already_set &) { + /* If print() is called from code that is executed as + part of garbage collection during interpreter shutdown, + importing 'sys' can fail. Give up rather than crashing the + interpreter in this case. */ + return; + } + } + + auto write = file.attr("write"); + write(line); + write(kwargs.contains("end") ? kwargs["end"] : cast("\n")); + + if (kwargs.contains("flush") && kwargs["flush"].cast()) + file.attr("flush")(); +} +NAMESPACE_END(detail) + +template +void print(Args &&...args) { + auto c = detail::collect_arguments(std::forward(args)...); + detail::print(c.args(), c.kwargs()); +} + +#if defined(WITH_THREAD) && !defined(PYPY_VERSION) + +/* The functions below essentially reproduce the PyGILState_* API using a RAII + * pattern, but there are a few important differences: + * + * 1. When acquiring the GIL from an non-main thread during the finalization + * phase, the GILState API blindly terminates the calling thread, which + * is often not what is wanted. This API does not do this. + * + * 2. The gil_scoped_release function can optionally cut the relationship + * of a PyThreadState and its associated thread, which allows moving it to + * another thread (this is a fairly rare/advanced use case). + * + * 3. The reference count of an acquired thread state can be controlled. This + * can be handy to prevent cases where callbacks issued from an external + * thread would otherwise constantly construct and destroy thread state data + * structures. + * + * See the Python bindings of NanoGUI (http://github.com/wjakob/nanogui) for an + * example which uses features 2 and 3 to migrate the Python thread of + * execution to another thread (to run the event loop on the original thread, + * in this case). + */ + +class gil_scoped_acquire { +public: + PYBIND11_NOINLINE gil_scoped_acquire() { + auto const &internals = detail::get_internals(); + tstate = (PyThreadState *) PYBIND11_TLS_GET_VALUE(internals.tstate); + + if (!tstate) { + /* Check if the GIL was acquired using the PyGILState_* API instead (e.g. if + calling from a Python thread). Since we use a different key, this ensures + we don't create a new thread state and deadlock in PyEval_AcquireThread + below. Note we don't save this state with internals.tstate, since we don't + create it we would fail to clear it (its reference count should be > 0). */ + tstate = PyGILState_GetThisThreadState(); + } + + if (!tstate) { + tstate = PyThreadState_New(internals.istate); + #if !defined(NDEBUG) + if (!tstate) + pybind11_fail("scoped_acquire: could not create thread state!"); + #endif + tstate->gilstate_counter = 0; + PYBIND11_TLS_REPLACE_VALUE(internals.tstate, tstate); + } else { + release = detail::get_thread_state_unchecked() != tstate; + } + + if (release) { + /* Work around an annoying assertion in PyThreadState_Swap */ + #if defined(Py_DEBUG) + PyInterpreterState *interp = tstate->interp; + tstate->interp = nullptr; + #endif + PyEval_AcquireThread(tstate); + #if defined(Py_DEBUG) + tstate->interp = interp; + #endif + } + + inc_ref(); + } + + void inc_ref() { + ++tstate->gilstate_counter; + } + + PYBIND11_NOINLINE void dec_ref() { + --tstate->gilstate_counter; + #if !defined(NDEBUG) + if (detail::get_thread_state_unchecked() != tstate) + pybind11_fail("scoped_acquire::dec_ref(): thread state must be current!"); + if (tstate->gilstate_counter < 0) + pybind11_fail("scoped_acquire::dec_ref(): reference count underflow!"); + #endif + if (tstate->gilstate_counter == 0) { + #if !defined(NDEBUG) + if (!release) + pybind11_fail("scoped_acquire::dec_ref(): internal error!"); + #endif + PyThreadState_Clear(tstate); + PyThreadState_DeleteCurrent(); + PYBIND11_TLS_DELETE_VALUE(detail::get_internals().tstate); + release = false; + } + } + + PYBIND11_NOINLINE ~gil_scoped_acquire() { + dec_ref(); + if (release) + PyEval_SaveThread(); + } +private: + PyThreadState *tstate = nullptr; + bool release = true; +}; + +class gil_scoped_release { +public: + explicit gil_scoped_release(bool disassoc = false) : disassoc(disassoc) { + // `get_internals()` must be called here unconditionally in order to initialize + // `internals.tstate` for subsequent `gil_scoped_acquire` calls. Otherwise, an + // initialization race could occur as multiple threads try `gil_scoped_acquire`. + const auto &internals = detail::get_internals(); + tstate = PyEval_SaveThread(); + if (disassoc) { + auto key = internals.tstate; + PYBIND11_TLS_DELETE_VALUE(key); + } + } + ~gil_scoped_release() { + if (!tstate) + return; + PyEval_RestoreThread(tstate); + if (disassoc) { + auto key = detail::get_internals().tstate; + PYBIND11_TLS_REPLACE_VALUE(key, tstate); + } + } +private: + PyThreadState *tstate; + bool disassoc; +}; +#elif defined(PYPY_VERSION) +class gil_scoped_acquire { + PyGILState_STATE state; +public: + gil_scoped_acquire() { state = PyGILState_Ensure(); } + ~gil_scoped_acquire() { PyGILState_Release(state); } +}; + +class gil_scoped_release { + PyThreadState *state; +public: + gil_scoped_release() { state = PyEval_SaveThread(); } + ~gil_scoped_release() { PyEval_RestoreThread(state); } +}; +#else +class gil_scoped_acquire { }; +class gil_scoped_release { }; +#endif + +error_already_set::~error_already_set() { + if (m_type) { + error_scope scope; + gil_scoped_acquire gil; + m_type.release().dec_ref(); + m_value.release().dec_ref(); + m_trace.release().dec_ref(); + } +} + +inline function get_type_overload(const void *this_ptr, const detail::type_info *this_type, const char *name) { + handle self = detail::get_object_handle(this_ptr, this_type); + if (!self) + return function(); + handle type = self.get_type(); + auto key = std::make_pair(type.ptr(), name); + + /* Cache functions that aren't overloaded in Python to avoid + many costly Python dictionary lookups below */ + auto &cache = detail::get_internals().inactive_overload_cache; + if (cache.find(key) != cache.end()) + return function(); + + function overload = getattr(self, name, function()); + if (overload.is_cpp_function()) { + cache.insert(key); + return function(); + } + + /* Don't call dispatch code if invoked from overridden function. + Unfortunately this doesn't work on PyPy. */ +#if !defined(PYPY_VERSION) + PyFrameObject *frame = PyThreadState_Get()->frame; + if (frame && (std::string) str(frame->f_code->co_name) == name && + frame->f_code->co_argcount > 0) { + PyFrame_FastToLocals(frame); + PyObject *self_caller = PyDict_GetItem( + frame->f_locals, PyTuple_GET_ITEM(frame->f_code->co_varnames, 0)); + if (self_caller == self.ptr()) + return function(); + } +#else + /* PyPy currently doesn't provide a detailed cpyext emulation of + frame objects, so we have to emulate this using Python. This + is going to be slow..*/ + dict d; d["self"] = self; d["name"] = pybind11::str(name); + PyObject *result = PyRun_String( + "import inspect\n" + "frame = inspect.currentframe()\n" + "if frame is not None:\n" + " frame = frame.f_back\n" + " if frame is not None and str(frame.f_code.co_name) == name and " + "frame.f_code.co_argcount > 0:\n" + " self_caller = frame.f_locals[frame.f_code.co_varnames[0]]\n" + " if self_caller == self:\n" + " self = None\n", + Py_file_input, d.ptr(), d.ptr()); + if (result == nullptr) + throw error_already_set(); + if (d["self"].is_none()) + return function(); + Py_DECREF(result); +#endif + + return overload; +} + +/** \rst + Try to retrieve a python method by the provided name from the instance pointed to by the this_ptr. + + :this_ptr: The pointer to the object the overload should be retrieved for. This should be the first + non-trampoline class encountered in the inheritance chain. + :name: The name of the overloaded Python method to retrieve. + :return: The Python method by this name from the object or an empty function wrapper. + \endrst */ +template function get_overload(const T *this_ptr, const char *name) { + auto tinfo = detail::get_type_info(typeid(T)); + return tinfo ? get_type_overload(this_ptr, tinfo, name) : function(); +} + +#define PYBIND11_OVERLOAD_INT(ret_type, cname, name, ...) { \ + pybind11::gil_scoped_acquire gil; \ + pybind11::function overload = pybind11::get_overload(static_cast(this), name); \ + if (overload) { \ + auto o = overload(__VA_ARGS__); \ + if (pybind11::detail::cast_is_temporary_value_reference::value) { \ + static pybind11::detail::overload_caster_t caster; \ + return pybind11::detail::cast_ref(std::move(o), caster); \ + } \ + else return pybind11::detail::cast_safe(std::move(o)); \ + } \ + } + +/** \rst + Macro to populate the virtual method in the trampoline class. This macro tries to look up a method named 'fn' + from the Python side, deals with the :ref:`gil` and necessary argument conversions to call this method and return + the appropriate type. See :ref:`overriding_virtuals` for more information. This macro should be used when the method + name in C is not the same as the method name in Python. For example with `__str__`. + + .. code-block:: cpp + + std::string toString() override { + PYBIND11_OVERLOAD_NAME( + std::string, // Return type (ret_type) + Animal, // Parent class (cname) + toString, // Name of function in C++ (name) + "__str__", // Name of method in Python (fn) + ); + } +\endrst */ +#define PYBIND11_OVERLOAD_NAME(ret_type, cname, name, fn, ...) \ + PYBIND11_OVERLOAD_INT(PYBIND11_TYPE(ret_type), PYBIND11_TYPE(cname), name, __VA_ARGS__) \ + return cname::fn(__VA_ARGS__) + +/** \rst + Macro for pure virtual functions, this function is identical to :c:macro:`PYBIND11_OVERLOAD_NAME`, except that it + throws if no overload can be found. +\endrst */ +#define PYBIND11_OVERLOAD_PURE_NAME(ret_type, cname, name, fn, ...) \ + PYBIND11_OVERLOAD_INT(PYBIND11_TYPE(ret_type), PYBIND11_TYPE(cname), name, __VA_ARGS__) \ + pybind11::pybind11_fail("Tried to call pure virtual function \"" PYBIND11_STRINGIFY(cname) "::" name "\""); + +/** \rst + Macro to populate the virtual method in the trampoline class. This macro tries to look up the method + from the Python side, deals with the :ref:`gil` and necessary argument conversions to call this method and return + the appropriate type. This macro should be used if the method name in C and in Python are identical. + See :ref:`overriding_virtuals` for more information. + + .. code-block:: cpp + + class PyAnimal : public Animal { + public: + // Inherit the constructors + using Animal::Animal; + + // Trampoline (need one for each virtual function) + std::string go(int n_times) override { + PYBIND11_OVERLOAD_PURE( + std::string, // Return type (ret_type) + Animal, // Parent class (cname) + go, // Name of function in C++ (must match Python name) (fn) + n_times // Argument(s) (...) + ); + } + }; +\endrst */ +#define PYBIND11_OVERLOAD(ret_type, cname, fn, ...) \ + PYBIND11_OVERLOAD_NAME(PYBIND11_TYPE(ret_type), PYBIND11_TYPE(cname), #fn, fn, __VA_ARGS__) + +/** \rst + Macro for pure virtual functions, this function is identical to :c:macro:`PYBIND11_OVERLOAD`, except that it throws + if no overload can be found. +\endrst */ +#define PYBIND11_OVERLOAD_PURE(ret_type, cname, fn, ...) \ + PYBIND11_OVERLOAD_PURE_NAME(PYBIND11_TYPE(ret_type), PYBIND11_TYPE(cname), #fn, fn, __VA_ARGS__) + +NAMESPACE_END(PYBIND11_NAMESPACE) + +#if defined(_MSC_VER) && !defined(__INTEL_COMPILER) +# pragma warning(pop) +#elif defined(__GNUG__) && !defined(__clang__) +# pragma GCC diagnostic pop +#endif diff --git a/wrap/python/pybind11/include/pybind11/pytypes.h b/wrap/python/pybind11/include/pybind11/pytypes.h new file mode 100644 index 000000000..2d573dfad --- /dev/null +++ b/wrap/python/pybind11/include/pybind11/pytypes.h @@ -0,0 +1,1471 @@ +/* + pybind11/pytypes.h: Convenience wrapper classes for basic Python types + + Copyright (c) 2016 Wenzel Jakob + + All rights reserved. Use of this source code is governed by a + BSD-style license that can be found in the LICENSE file. +*/ + +#pragma once + +#include "detail/common.h" +#include "buffer_info.h" +#include +#include + +NAMESPACE_BEGIN(PYBIND11_NAMESPACE) + +/* A few forward declarations */ +class handle; class object; +class str; class iterator; +struct arg; struct arg_v; + +NAMESPACE_BEGIN(detail) +class args_proxy; +inline bool isinstance_generic(handle obj, const std::type_info &tp); + +// Accessor forward declarations +template class accessor; +namespace accessor_policies { + struct obj_attr; + struct str_attr; + struct generic_item; + struct sequence_item; + struct list_item; + struct tuple_item; +} +using obj_attr_accessor = accessor; +using str_attr_accessor = accessor; +using item_accessor = accessor; +using sequence_accessor = accessor; +using list_accessor = accessor; +using tuple_accessor = accessor; + +/// Tag and check to identify a class which implements the Python object API +class pyobject_tag { }; +template using is_pyobject = std::is_base_of>; + +/** \rst + A mixin class which adds common functions to `handle`, `object` and various accessors. + The only requirement for `Derived` is to implement ``PyObject *Derived::ptr() const``. +\endrst */ +template +class object_api : public pyobject_tag { + const Derived &derived() const { return static_cast(*this); } + +public: + /** \rst + Return an iterator equivalent to calling ``iter()`` in Python. The object + must be a collection which supports the iteration protocol. + \endrst */ + iterator begin() const; + /// Return a sentinel which ends iteration. + iterator end() const; + + /** \rst + Return an internal functor to invoke the object's sequence protocol. Casting + the returned ``detail::item_accessor`` instance to a `handle` or `object` + subclass causes a corresponding call to ``__getitem__``. Assigning a `handle` + or `object` subclass causes a call to ``__setitem__``. + \endrst */ + item_accessor operator[](handle key) const; + /// See above (the only difference is that they key is provided as a string literal) + item_accessor operator[](const char *key) const; + + /** \rst + Return an internal functor to access the object's attributes. Casting the + returned ``detail::obj_attr_accessor`` instance to a `handle` or `object` + subclass causes a corresponding call to ``getattr``. Assigning a `handle` + or `object` subclass causes a call to ``setattr``. + \endrst */ + obj_attr_accessor attr(handle key) const; + /// See above (the only difference is that they key is provided as a string literal) + str_attr_accessor attr(const char *key) const; + + /** \rst + Matches * unpacking in Python, e.g. to unpack arguments out of a ``tuple`` + or ``list`` for a function call. Applying another * to the result yields + ** unpacking, e.g. to unpack a dict as function keyword arguments. + See :ref:`calling_python_functions`. + \endrst */ + args_proxy operator*() const; + + /// Check if the given item is contained within this object, i.e. ``item in obj``. + template bool contains(T &&item) const; + + /** \rst + Assuming the Python object is a function or implements the ``__call__`` + protocol, ``operator()`` invokes the underlying function, passing an + arbitrary set of parameters. The result is returned as a `object` and + may need to be converted back into a Python object using `handle::cast()`. + + When some of the arguments cannot be converted to Python objects, the + function will throw a `cast_error` exception. When the Python function + call fails, a `error_already_set` exception is thrown. + \endrst */ + template + object operator()(Args &&...args) const; + template + PYBIND11_DEPRECATED("call(...) was deprecated in favor of operator()(...)") + object call(Args&&... args) const; + + /// Equivalent to ``obj is other`` in Python. + bool is(object_api const& other) const { return derived().ptr() == other.derived().ptr(); } + /// Equivalent to ``obj is None`` in Python. + bool is_none() const { return derived().ptr() == Py_None; } + /// Equivalent to obj == other in Python + bool equal(object_api const &other) const { return rich_compare(other, Py_EQ); } + bool not_equal(object_api const &other) const { return rich_compare(other, Py_NE); } + bool operator<(object_api const &other) const { return rich_compare(other, Py_LT); } + bool operator<=(object_api const &other) const { return rich_compare(other, Py_LE); } + bool operator>(object_api const &other) const { return rich_compare(other, Py_GT); } + bool operator>=(object_api const &other) const { return rich_compare(other, Py_GE); } + + object operator-() const; + object operator~() const; + object operator+(object_api const &other) const; + object operator+=(object_api const &other) const; + object operator-(object_api const &other) const; + object operator-=(object_api const &other) const; + object operator*(object_api const &other) const; + object operator*=(object_api const &other) const; + object operator/(object_api const &other) const; + object operator/=(object_api const &other) const; + object operator|(object_api const &other) const; + object operator|=(object_api const &other) const; + object operator&(object_api const &other) const; + object operator&=(object_api const &other) const; + object operator^(object_api const &other) const; + object operator^=(object_api const &other) const; + object operator<<(object_api const &other) const; + object operator<<=(object_api const &other) const; + object operator>>(object_api const &other) const; + object operator>>=(object_api const &other) const; + + PYBIND11_DEPRECATED("Use py::str(obj) instead") + pybind11::str str() const; + + /// Get or set the object's docstring, i.e. ``obj.__doc__``. + str_attr_accessor doc() const; + + /// Return the object's current reference count + int ref_count() const { return static_cast(Py_REFCNT(derived().ptr())); } + /// Return a handle to the Python type object underlying the instance + handle get_type() const; + +private: + bool rich_compare(object_api const &other, int value) const; +}; + +NAMESPACE_END(detail) + +/** \rst + Holds a reference to a Python object (no reference counting) + + The `handle` class is a thin wrapper around an arbitrary Python object (i.e. a + ``PyObject *`` in Python's C API). It does not perform any automatic reference + counting and merely provides a basic C++ interface to various Python API functions. + + .. seealso:: + The `object` class inherits from `handle` and adds automatic reference + counting features. +\endrst */ +class handle : public detail::object_api { +public: + /// The default constructor creates a handle with a ``nullptr``-valued pointer + handle() = default; + /// Creates a ``handle`` from the given raw Python object pointer + handle(PyObject *ptr) : m_ptr(ptr) { } // Allow implicit conversion from PyObject* + + /// Return the underlying ``PyObject *`` pointer + PyObject *ptr() const { return m_ptr; } + PyObject *&ptr() { return m_ptr; } + + /** \rst + Manually increase the reference count of the Python object. Usually, it is + preferable to use the `object` class which derives from `handle` and calls + this function automatically. Returns a reference to itself. + \endrst */ + const handle& inc_ref() const & { Py_XINCREF(m_ptr); return *this; } + + /** \rst + Manually decrease the reference count of the Python object. Usually, it is + preferable to use the `object` class which derives from `handle` and calls + this function automatically. Returns a reference to itself. + \endrst */ + const handle& dec_ref() const & { Py_XDECREF(m_ptr); return *this; } + + /** \rst + Attempt to cast the Python object into the given C++ type. A `cast_error` + will be throw upon failure. + \endrst */ + template T cast() const; + /// Return ``true`` when the `handle` wraps a valid Python object + explicit operator bool() const { return m_ptr != nullptr; } + /** \rst + Deprecated: Check that the underlying pointers are the same. + Equivalent to ``obj1 is obj2`` in Python. + \endrst */ + PYBIND11_DEPRECATED("Use obj1.is(obj2) instead") + bool operator==(const handle &h) const { return m_ptr == h.m_ptr; } + PYBIND11_DEPRECATED("Use !obj1.is(obj2) instead") + bool operator!=(const handle &h) const { return m_ptr != h.m_ptr; } + PYBIND11_DEPRECATED("Use handle::operator bool() instead") + bool check() const { return m_ptr != nullptr; } +protected: + PyObject *m_ptr = nullptr; +}; + +/** \rst + Holds a reference to a Python object (with reference counting) + + Like `handle`, the `object` class is a thin wrapper around an arbitrary Python + object (i.e. a ``PyObject *`` in Python's C API). In contrast to `handle`, it + optionally increases the object's reference count upon construction, and it + *always* decreases the reference count when the `object` instance goes out of + scope and is destructed. When using `object` instances consistently, it is much + easier to get reference counting right at the first attempt. +\endrst */ +class object : public handle { +public: + object() = default; + PYBIND11_DEPRECATED("Use reinterpret_borrow() or reinterpret_steal()") + object(handle h, bool is_borrowed) : handle(h) { if (is_borrowed) inc_ref(); } + /// Copy constructor; always increases the reference count + object(const object &o) : handle(o) { inc_ref(); } + /// Move constructor; steals the object from ``other`` and preserves its reference count + object(object &&other) noexcept { m_ptr = other.m_ptr; other.m_ptr = nullptr; } + /// Destructor; automatically calls `handle::dec_ref()` + ~object() { dec_ref(); } + + /** \rst + Resets the internal pointer to ``nullptr`` without without decreasing the + object's reference count. The function returns a raw handle to the original + Python object. + \endrst */ + handle release() { + PyObject *tmp = m_ptr; + m_ptr = nullptr; + return handle(tmp); + } + + object& operator=(const object &other) { + other.inc_ref(); + dec_ref(); + m_ptr = other.m_ptr; + return *this; + } + + object& operator=(object &&other) noexcept { + if (this != &other) { + handle temp(m_ptr); + m_ptr = other.m_ptr; + other.m_ptr = nullptr; + temp.dec_ref(); + } + return *this; + } + + // Calling cast() on an object lvalue just copies (via handle::cast) + template T cast() const &; + // Calling on an object rvalue does a move, if needed and/or possible + template T cast() &&; + +protected: + // Tags for choosing constructors from raw PyObject * + struct borrowed_t { }; + struct stolen_t { }; + + template friend T reinterpret_borrow(handle); + template friend T reinterpret_steal(handle); + +public: + // Only accessible from derived classes and the reinterpret_* functions + object(handle h, borrowed_t) : handle(h) { inc_ref(); } + object(handle h, stolen_t) : handle(h) { } +}; + +/** \rst + Declare that a `handle` or ``PyObject *`` is a certain type and borrow the reference. + The target type ``T`` must be `object` or one of its derived classes. The function + doesn't do any conversions or checks. It's up to the user to make sure that the + target type is correct. + + .. code-block:: cpp + + PyObject *p = PyList_GetItem(obj, index); + py::object o = reinterpret_borrow(p); + // or + py::tuple t = reinterpret_borrow(p); // <-- `p` must be already be a `tuple` +\endrst */ +template T reinterpret_borrow(handle h) { return {h, object::borrowed_t{}}; } + +/** \rst + Like `reinterpret_borrow`, but steals the reference. + + .. code-block:: cpp + + PyObject *p = PyObject_Str(obj); + py::str s = reinterpret_steal(p); // <-- `p` must be already be a `str` +\endrst */ +template T reinterpret_steal(handle h) { return {h, object::stolen_t{}}; } + +NAMESPACE_BEGIN(detail) +inline std::string error_string(); +NAMESPACE_END(detail) + +/// Fetch and hold an error which was already set in Python. An instance of this is typically +/// thrown to propagate python-side errors back through C++ which can either be caught manually or +/// else falls back to the function dispatcher (which then raises the captured error back to +/// python). +class error_already_set : public std::runtime_error { +public: + /// Constructs a new exception from the current Python error indicator, if any. The current + /// Python error indicator will be cleared. + error_already_set() : std::runtime_error(detail::error_string()) { + PyErr_Fetch(&m_type.ptr(), &m_value.ptr(), &m_trace.ptr()); + } + + error_already_set(const error_already_set &) = default; + error_already_set(error_already_set &&) = default; + + inline ~error_already_set(); + + /// Give the currently-held error back to Python, if any. If there is currently a Python error + /// already set it is cleared first. After this call, the current object no longer stores the + /// error variables (but the `.what()` string is still available). + void restore() { PyErr_Restore(m_type.release().ptr(), m_value.release().ptr(), m_trace.release().ptr()); } + + // Does nothing; provided for backwards compatibility. + PYBIND11_DEPRECATED("Use of error_already_set.clear() is deprecated") + void clear() {} + + /// Check if the currently trapped error type matches the given Python exception class (or a + /// subclass thereof). May also be passed a tuple to search for any exception class matches in + /// the given tuple. + bool matches(handle exc) const { return PyErr_GivenExceptionMatches(m_type.ptr(), exc.ptr()); } + + const object& type() const { return m_type; } + const object& value() const { return m_value; } + const object& trace() const { return m_trace; } + +private: + object m_type, m_value, m_trace; +}; + +/** \defgroup python_builtins _ + Unless stated otherwise, the following C++ functions behave the same + as their Python counterparts. + */ + +/** \ingroup python_builtins + \rst + Return true if ``obj`` is an instance of ``T``. Type ``T`` must be a subclass of + `object` or a class which was exposed to Python as ``py::class_``. +\endrst */ +template ::value, int> = 0> +bool isinstance(handle obj) { return T::check_(obj); } + +template ::value, int> = 0> +bool isinstance(handle obj) { return detail::isinstance_generic(obj, typeid(T)); } + +template <> inline bool isinstance(handle obj) = delete; +template <> inline bool isinstance(handle obj) { return obj.ptr() != nullptr; } + +/// \ingroup python_builtins +/// Return true if ``obj`` is an instance of the ``type``. +inline bool isinstance(handle obj, handle type) { + const auto result = PyObject_IsInstance(obj.ptr(), type.ptr()); + if (result == -1) + throw error_already_set(); + return result != 0; +} + +/// \addtogroup python_builtins +/// @{ +inline bool hasattr(handle obj, handle name) { + return PyObject_HasAttr(obj.ptr(), name.ptr()) == 1; +} + +inline bool hasattr(handle obj, const char *name) { + return PyObject_HasAttrString(obj.ptr(), name) == 1; +} + +inline void delattr(handle obj, handle name) { + if (PyObject_DelAttr(obj.ptr(), name.ptr()) != 0) { throw error_already_set(); } +} + +inline void delattr(handle obj, const char *name) { + if (PyObject_DelAttrString(obj.ptr(), name) != 0) { throw error_already_set(); } +} + +inline object getattr(handle obj, handle name) { + PyObject *result = PyObject_GetAttr(obj.ptr(), name.ptr()); + if (!result) { throw error_already_set(); } + return reinterpret_steal(result); +} + +inline object getattr(handle obj, const char *name) { + PyObject *result = PyObject_GetAttrString(obj.ptr(), name); + if (!result) { throw error_already_set(); } + return reinterpret_steal(result); +} + +inline object getattr(handle obj, handle name, handle default_) { + if (PyObject *result = PyObject_GetAttr(obj.ptr(), name.ptr())) { + return reinterpret_steal(result); + } else { + PyErr_Clear(); + return reinterpret_borrow(default_); + } +} + +inline object getattr(handle obj, const char *name, handle default_) { + if (PyObject *result = PyObject_GetAttrString(obj.ptr(), name)) { + return reinterpret_steal(result); + } else { + PyErr_Clear(); + return reinterpret_borrow(default_); + } +} + +inline void setattr(handle obj, handle name, handle value) { + if (PyObject_SetAttr(obj.ptr(), name.ptr(), value.ptr()) != 0) { throw error_already_set(); } +} + +inline void setattr(handle obj, const char *name, handle value) { + if (PyObject_SetAttrString(obj.ptr(), name, value.ptr()) != 0) { throw error_already_set(); } +} + +inline ssize_t hash(handle obj) { + auto h = PyObject_Hash(obj.ptr()); + if (h == -1) { throw error_already_set(); } + return h; +} + +/// @} python_builtins + +NAMESPACE_BEGIN(detail) +inline handle get_function(handle value) { + if (value) { +#if PY_MAJOR_VERSION >= 3 + if (PyInstanceMethod_Check(value.ptr())) + value = PyInstanceMethod_GET_FUNCTION(value.ptr()); + else +#endif + if (PyMethod_Check(value.ptr())) + value = PyMethod_GET_FUNCTION(value.ptr()); + } + return value; +} + +// Helper aliases/functions to support implicit casting of values given to python accessors/methods. +// When given a pyobject, this simply returns the pyobject as-is; for other C++ type, the value goes +// through pybind11::cast(obj) to convert it to an `object`. +template ::value, int> = 0> +auto object_or_cast(T &&o) -> decltype(std::forward(o)) { return std::forward(o); } +// The following casting version is implemented in cast.h: +template ::value, int> = 0> +object object_or_cast(T &&o); +// Match a PyObject*, which we want to convert directly to handle via its converting constructor +inline handle object_or_cast(PyObject *ptr) { return ptr; } + +template +class accessor : public object_api> { + using key_type = typename Policy::key_type; + +public: + accessor(handle obj, key_type key) : obj(obj), key(std::move(key)) { } + accessor(const accessor &) = default; + accessor(accessor &&) = default; + + // accessor overload required to override default assignment operator (templates are not allowed + // to replace default compiler-generated assignments). + void operator=(const accessor &a) && { std::move(*this).operator=(handle(a)); } + void operator=(const accessor &a) & { operator=(handle(a)); } + + template void operator=(T &&value) && { + Policy::set(obj, key, object_or_cast(std::forward(value))); + } + template void operator=(T &&value) & { + get_cache() = reinterpret_borrow(object_or_cast(std::forward(value))); + } + + template + PYBIND11_DEPRECATED("Use of obj.attr(...) as bool is deprecated in favor of pybind11::hasattr(obj, ...)") + explicit operator enable_if_t::value || + std::is_same::value, bool>() const { + return hasattr(obj, key); + } + template + PYBIND11_DEPRECATED("Use of obj[key] as bool is deprecated in favor of obj.contains(key)") + explicit operator enable_if_t::value, bool>() const { + return obj.contains(key); + } + + operator object() const { return get_cache(); } + PyObject *ptr() const { return get_cache().ptr(); } + template T cast() const { return get_cache().template cast(); } + +private: + object &get_cache() const { + if (!cache) { cache = Policy::get(obj, key); } + return cache; + } + +private: + handle obj; + key_type key; + mutable object cache; +}; + +NAMESPACE_BEGIN(accessor_policies) +struct obj_attr { + using key_type = object; + static object get(handle obj, handle key) { return getattr(obj, key); } + static void set(handle obj, handle key, handle val) { setattr(obj, key, val); } +}; + +struct str_attr { + using key_type = const char *; + static object get(handle obj, const char *key) { return getattr(obj, key); } + static void set(handle obj, const char *key, handle val) { setattr(obj, key, val); } +}; + +struct generic_item { + using key_type = object; + + static object get(handle obj, handle key) { + PyObject *result = PyObject_GetItem(obj.ptr(), key.ptr()); + if (!result) { throw error_already_set(); } + return reinterpret_steal(result); + } + + static void set(handle obj, handle key, handle val) { + if (PyObject_SetItem(obj.ptr(), key.ptr(), val.ptr()) != 0) { throw error_already_set(); } + } +}; + +struct sequence_item { + using key_type = size_t; + + static object get(handle obj, size_t index) { + PyObject *result = PySequence_GetItem(obj.ptr(), static_cast(index)); + if (!result) { throw error_already_set(); } + return reinterpret_steal(result); + } + + static void set(handle obj, size_t index, handle val) { + // PySequence_SetItem does not steal a reference to 'val' + if (PySequence_SetItem(obj.ptr(), static_cast(index), val.ptr()) != 0) { + throw error_already_set(); + } + } +}; + +struct list_item { + using key_type = size_t; + + static object get(handle obj, size_t index) { + PyObject *result = PyList_GetItem(obj.ptr(), static_cast(index)); + if (!result) { throw error_already_set(); } + return reinterpret_borrow(result); + } + + static void set(handle obj, size_t index, handle val) { + // PyList_SetItem steals a reference to 'val' + if (PyList_SetItem(obj.ptr(), static_cast(index), val.inc_ref().ptr()) != 0) { + throw error_already_set(); + } + } +}; + +struct tuple_item { + using key_type = size_t; + + static object get(handle obj, size_t index) { + PyObject *result = PyTuple_GetItem(obj.ptr(), static_cast(index)); + if (!result) { throw error_already_set(); } + return reinterpret_borrow(result); + } + + static void set(handle obj, size_t index, handle val) { + // PyTuple_SetItem steals a reference to 'val' + if (PyTuple_SetItem(obj.ptr(), static_cast(index), val.inc_ref().ptr()) != 0) { + throw error_already_set(); + } + } +}; +NAMESPACE_END(accessor_policies) + +/// STL iterator template used for tuple, list, sequence and dict +template +class generic_iterator : public Policy { + using It = generic_iterator; + +public: + using difference_type = ssize_t; + using iterator_category = typename Policy::iterator_category; + using value_type = typename Policy::value_type; + using reference = typename Policy::reference; + using pointer = typename Policy::pointer; + + generic_iterator() = default; + generic_iterator(handle seq, ssize_t index) : Policy(seq, index) { } + + reference operator*() const { return Policy::dereference(); } + reference operator[](difference_type n) const { return *(*this + n); } + pointer operator->() const { return **this; } + + It &operator++() { Policy::increment(); return *this; } + It operator++(int) { auto copy = *this; Policy::increment(); return copy; } + It &operator--() { Policy::decrement(); return *this; } + It operator--(int) { auto copy = *this; Policy::decrement(); return copy; } + It &operator+=(difference_type n) { Policy::advance(n); return *this; } + It &operator-=(difference_type n) { Policy::advance(-n); return *this; } + + friend It operator+(const It &a, difference_type n) { auto copy = a; return copy += n; } + friend It operator+(difference_type n, const It &b) { return b + n; } + friend It operator-(const It &a, difference_type n) { auto copy = a; return copy -= n; } + friend difference_type operator-(const It &a, const It &b) { return a.distance_to(b); } + + friend bool operator==(const It &a, const It &b) { return a.equal(b); } + friend bool operator!=(const It &a, const It &b) { return !(a == b); } + friend bool operator< (const It &a, const It &b) { return b - a > 0; } + friend bool operator> (const It &a, const It &b) { return b < a; } + friend bool operator>=(const It &a, const It &b) { return !(a < b); } + friend bool operator<=(const It &a, const It &b) { return !(a > b); } +}; + +NAMESPACE_BEGIN(iterator_policies) +/// Quick proxy class needed to implement ``operator->`` for iterators which can't return pointers +template +struct arrow_proxy { + T value; + + arrow_proxy(T &&value) : value(std::move(value)) { } + T *operator->() const { return &value; } +}; + +/// Lightweight iterator policy using just a simple pointer: see ``PySequence_Fast_ITEMS`` +class sequence_fast_readonly { +protected: + using iterator_category = std::random_access_iterator_tag; + using value_type = handle; + using reference = const handle; + using pointer = arrow_proxy; + + sequence_fast_readonly(handle obj, ssize_t n) : ptr(PySequence_Fast_ITEMS(obj.ptr()) + n) { } + + reference dereference() const { return *ptr; } + void increment() { ++ptr; } + void decrement() { --ptr; } + void advance(ssize_t n) { ptr += n; } + bool equal(const sequence_fast_readonly &b) const { return ptr == b.ptr; } + ssize_t distance_to(const sequence_fast_readonly &b) const { return ptr - b.ptr; } + +private: + PyObject **ptr; +}; + +/// Full read and write access using the sequence protocol: see ``detail::sequence_accessor`` +class sequence_slow_readwrite { +protected: + using iterator_category = std::random_access_iterator_tag; + using value_type = object; + using reference = sequence_accessor; + using pointer = arrow_proxy; + + sequence_slow_readwrite(handle obj, ssize_t index) : obj(obj), index(index) { } + + reference dereference() const { return {obj, static_cast(index)}; } + void increment() { ++index; } + void decrement() { --index; } + void advance(ssize_t n) { index += n; } + bool equal(const sequence_slow_readwrite &b) const { return index == b.index; } + ssize_t distance_to(const sequence_slow_readwrite &b) const { return index - b.index; } + +private: + handle obj; + ssize_t index; +}; + +/// Python's dictionary protocol permits this to be a forward iterator +class dict_readonly { +protected: + using iterator_category = std::forward_iterator_tag; + using value_type = std::pair; + using reference = const value_type; + using pointer = arrow_proxy; + + dict_readonly() = default; + dict_readonly(handle obj, ssize_t pos) : obj(obj), pos(pos) { increment(); } + + reference dereference() const { return {key, value}; } + void increment() { if (!PyDict_Next(obj.ptr(), &pos, &key, &value)) { pos = -1; } } + bool equal(const dict_readonly &b) const { return pos == b.pos; } + +private: + handle obj; + PyObject *key = nullptr, *value = nullptr; + ssize_t pos = -1; +}; +NAMESPACE_END(iterator_policies) + +#if !defined(PYPY_VERSION) +using tuple_iterator = generic_iterator; +using list_iterator = generic_iterator; +#else +using tuple_iterator = generic_iterator; +using list_iterator = generic_iterator; +#endif + +using sequence_iterator = generic_iterator; +using dict_iterator = generic_iterator; + +inline bool PyIterable_Check(PyObject *obj) { + PyObject *iter = PyObject_GetIter(obj); + if (iter) { + Py_DECREF(iter); + return true; + } else { + PyErr_Clear(); + return false; + } +} + +inline bool PyNone_Check(PyObject *o) { return o == Py_None; } +#if PY_MAJOR_VERSION >= 3 +inline bool PyEllipsis_Check(PyObject *o) { return o == Py_Ellipsis; } +#endif + +inline bool PyUnicode_Check_Permissive(PyObject *o) { return PyUnicode_Check(o) || PYBIND11_BYTES_CHECK(o); } + +inline bool PyStaticMethod_Check(PyObject *o) { return o->ob_type == &PyStaticMethod_Type; } + +class kwargs_proxy : public handle { +public: + explicit kwargs_proxy(handle h) : handle(h) { } +}; + +class args_proxy : public handle { +public: + explicit args_proxy(handle h) : handle(h) { } + kwargs_proxy operator*() const { return kwargs_proxy(*this); } +}; + +/// Python argument categories (using PEP 448 terms) +template using is_keyword = std::is_base_of; +template using is_s_unpacking = std::is_same; // * unpacking +template using is_ds_unpacking = std::is_same; // ** unpacking +template using is_positional = satisfies_none_of; +template using is_keyword_or_ds = satisfies_any_of; + +// Call argument collector forward declarations +template +class simple_collector; +template +class unpacking_collector; + +NAMESPACE_END(detail) + +// TODO: After the deprecated constructors are removed, this macro can be simplified by +// inheriting ctors: `using Parent::Parent`. It's not an option right now because +// the `using` statement triggers the parent deprecation warning even if the ctor +// isn't even used. +#define PYBIND11_OBJECT_COMMON(Name, Parent, CheckFun) \ + public: \ + PYBIND11_DEPRECATED("Use reinterpret_borrow<"#Name">() or reinterpret_steal<"#Name">()") \ + Name(handle h, bool is_borrowed) : Parent(is_borrowed ? Parent(h, borrowed_t{}) : Parent(h, stolen_t{})) { } \ + Name(handle h, borrowed_t) : Parent(h, borrowed_t{}) { } \ + Name(handle h, stolen_t) : Parent(h, stolen_t{}) { } \ + PYBIND11_DEPRECATED("Use py::isinstance(obj) instead") \ + bool check() const { return m_ptr != nullptr && (bool) CheckFun(m_ptr); } \ + static bool check_(handle h) { return h.ptr() != nullptr && CheckFun(h.ptr()); } + +#define PYBIND11_OBJECT_CVT(Name, Parent, CheckFun, ConvertFun) \ + PYBIND11_OBJECT_COMMON(Name, Parent, CheckFun) \ + /* This is deliberately not 'explicit' to allow implicit conversion from object: */ \ + Name(const object &o) \ + : Parent(check_(o) ? o.inc_ref().ptr() : ConvertFun(o.ptr()), stolen_t{}) \ + { if (!m_ptr) throw error_already_set(); } \ + Name(object &&o) \ + : Parent(check_(o) ? o.release().ptr() : ConvertFun(o.ptr()), stolen_t{}) \ + { if (!m_ptr) throw error_already_set(); } \ + template \ + Name(const ::pybind11::detail::accessor &a) : Name(object(a)) { } + +#define PYBIND11_OBJECT(Name, Parent, CheckFun) \ + PYBIND11_OBJECT_COMMON(Name, Parent, CheckFun) \ + /* This is deliberately not 'explicit' to allow implicit conversion from object: */ \ + Name(const object &o) : Parent(o) { } \ + Name(object &&o) : Parent(std::move(o)) { } + +#define PYBIND11_OBJECT_DEFAULT(Name, Parent, CheckFun) \ + PYBIND11_OBJECT(Name, Parent, CheckFun) \ + Name() : Parent() { } + +/// \addtogroup pytypes +/// @{ + +/** \rst + Wraps a Python iterator so that it can also be used as a C++ input iterator + + Caveat: copying an iterator does not (and cannot) clone the internal + state of the Python iterable. This also applies to the post-increment + operator. This iterator should only be used to retrieve the current + value using ``operator*()``. +\endrst */ +class iterator : public object { +public: + using iterator_category = std::input_iterator_tag; + using difference_type = ssize_t; + using value_type = handle; + using reference = const handle; + using pointer = const handle *; + + PYBIND11_OBJECT_DEFAULT(iterator, object, PyIter_Check) + + iterator& operator++() { + advance(); + return *this; + } + + iterator operator++(int) { + auto rv = *this; + advance(); + return rv; + } + + reference operator*() const { + if (m_ptr && !value.ptr()) { + auto& self = const_cast(*this); + self.advance(); + } + return value; + } + + pointer operator->() const { operator*(); return &value; } + + /** \rst + The value which marks the end of the iteration. ``it == iterator::sentinel()`` + is equivalent to catching ``StopIteration`` in Python. + + .. code-block:: cpp + + void foo(py::iterator it) { + while (it != py::iterator::sentinel()) { + // use `*it` + ++it; + } + } + \endrst */ + static iterator sentinel() { return {}; } + + friend bool operator==(const iterator &a, const iterator &b) { return a->ptr() == b->ptr(); } + friend bool operator!=(const iterator &a, const iterator &b) { return a->ptr() != b->ptr(); } + +private: + void advance() { + value = reinterpret_steal(PyIter_Next(m_ptr)); + if (PyErr_Occurred()) { throw error_already_set(); } + } + +private: + object value = {}; +}; + +class iterable : public object { +public: + PYBIND11_OBJECT_DEFAULT(iterable, object, detail::PyIterable_Check) +}; + +class bytes; + +class str : public object { +public: + PYBIND11_OBJECT_CVT(str, object, detail::PyUnicode_Check_Permissive, raw_str) + + str(const char *c, size_t n) + : object(PyUnicode_FromStringAndSize(c, (ssize_t) n), stolen_t{}) { + if (!m_ptr) pybind11_fail("Could not allocate string object!"); + } + + // 'explicit' is explicitly omitted from the following constructors to allow implicit conversion to py::str from C++ string-like objects + str(const char *c = "") + : object(PyUnicode_FromString(c), stolen_t{}) { + if (!m_ptr) pybind11_fail("Could not allocate string object!"); + } + + str(const std::string &s) : str(s.data(), s.size()) { } + + explicit str(const bytes &b); + + /** \rst + Return a string representation of the object. This is analogous to + the ``str()`` function in Python. + \endrst */ + explicit str(handle h) : object(raw_str(h.ptr()), stolen_t{}) { } + + operator std::string() const { + object temp = *this; + if (PyUnicode_Check(m_ptr)) { + temp = reinterpret_steal(PyUnicode_AsUTF8String(m_ptr)); + if (!temp) + pybind11_fail("Unable to extract string contents! (encoding issue)"); + } + char *buffer; + ssize_t length; + if (PYBIND11_BYTES_AS_STRING_AND_SIZE(temp.ptr(), &buffer, &length)) + pybind11_fail("Unable to extract string contents! (invalid type)"); + return std::string(buffer, (size_t) length); + } + + template + str format(Args &&...args) const { + return attr("format")(std::forward(args)...); + } + +private: + /// Return string representation -- always returns a new reference, even if already a str + static PyObject *raw_str(PyObject *op) { + PyObject *str_value = PyObject_Str(op); +#if PY_MAJOR_VERSION < 3 + if (!str_value) throw error_already_set(); + PyObject *unicode = PyUnicode_FromEncodedObject(str_value, "utf-8", nullptr); + Py_XDECREF(str_value); str_value = unicode; +#endif + return str_value; + } +}; +/// @} pytypes + +inline namespace literals { +/** \rst + String literal version of `str` + \endrst */ +inline str operator"" _s(const char *s, size_t size) { return {s, size}; } +} + +/// \addtogroup pytypes +/// @{ +class bytes : public object { +public: + PYBIND11_OBJECT(bytes, object, PYBIND11_BYTES_CHECK) + + // Allow implicit conversion: + bytes(const char *c = "") + : object(PYBIND11_BYTES_FROM_STRING(c), stolen_t{}) { + if (!m_ptr) pybind11_fail("Could not allocate bytes object!"); + } + + bytes(const char *c, size_t n) + : object(PYBIND11_BYTES_FROM_STRING_AND_SIZE(c, (ssize_t) n), stolen_t{}) { + if (!m_ptr) pybind11_fail("Could not allocate bytes object!"); + } + + // Allow implicit conversion: + bytes(const std::string &s) : bytes(s.data(), s.size()) { } + + explicit bytes(const pybind11::str &s); + + operator std::string() const { + char *buffer; + ssize_t length; + if (PYBIND11_BYTES_AS_STRING_AND_SIZE(m_ptr, &buffer, &length)) + pybind11_fail("Unable to extract bytes contents!"); + return std::string(buffer, (size_t) length); + } +}; + +inline bytes::bytes(const pybind11::str &s) { + object temp = s; + if (PyUnicode_Check(s.ptr())) { + temp = reinterpret_steal(PyUnicode_AsUTF8String(s.ptr())); + if (!temp) + pybind11_fail("Unable to extract string contents! (encoding issue)"); + } + char *buffer; + ssize_t length; + if (PYBIND11_BYTES_AS_STRING_AND_SIZE(temp.ptr(), &buffer, &length)) + pybind11_fail("Unable to extract string contents! (invalid type)"); + auto obj = reinterpret_steal(PYBIND11_BYTES_FROM_STRING_AND_SIZE(buffer, length)); + if (!obj) + pybind11_fail("Could not allocate bytes object!"); + m_ptr = obj.release().ptr(); +} + +inline str::str(const bytes& b) { + char *buffer; + ssize_t length; + if (PYBIND11_BYTES_AS_STRING_AND_SIZE(b.ptr(), &buffer, &length)) + pybind11_fail("Unable to extract bytes contents!"); + auto obj = reinterpret_steal(PyUnicode_FromStringAndSize(buffer, (ssize_t) length)); + if (!obj) + pybind11_fail("Could not allocate string object!"); + m_ptr = obj.release().ptr(); +} + +class none : public object { +public: + PYBIND11_OBJECT(none, object, detail::PyNone_Check) + none() : object(Py_None, borrowed_t{}) { } +}; + +#if PY_MAJOR_VERSION >= 3 +class ellipsis : public object { +public: + PYBIND11_OBJECT(ellipsis, object, detail::PyEllipsis_Check) + ellipsis() : object(Py_Ellipsis, borrowed_t{}) { } +}; +#endif + +class bool_ : public object { +public: + PYBIND11_OBJECT_CVT(bool_, object, PyBool_Check, raw_bool) + bool_() : object(Py_False, borrowed_t{}) { } + // Allow implicit conversion from and to `bool`: + bool_(bool value) : object(value ? Py_True : Py_False, borrowed_t{}) { } + operator bool() const { return m_ptr && PyLong_AsLong(m_ptr) != 0; } + +private: + /// Return the truth value of an object -- always returns a new reference + static PyObject *raw_bool(PyObject *op) { + const auto value = PyObject_IsTrue(op); + if (value == -1) return nullptr; + return handle(value ? Py_True : Py_False).inc_ref().ptr(); + } +}; + +NAMESPACE_BEGIN(detail) +// Converts a value to the given unsigned type. If an error occurs, you get back (Unsigned) -1; +// otherwise you get back the unsigned long or unsigned long long value cast to (Unsigned). +// (The distinction is critically important when casting a returned -1 error value to some other +// unsigned type: (A)-1 != (B)-1 when A and B are unsigned types of different sizes). +template +Unsigned as_unsigned(PyObject *o) { + if (sizeof(Unsigned) <= sizeof(unsigned long) +#if PY_VERSION_HEX < 0x03000000 + || PyInt_Check(o) +#endif + ) { + unsigned long v = PyLong_AsUnsignedLong(o); + return v == (unsigned long) -1 && PyErr_Occurred() ? (Unsigned) -1 : (Unsigned) v; + } + else { + unsigned long long v = PyLong_AsUnsignedLongLong(o); + return v == (unsigned long long) -1 && PyErr_Occurred() ? (Unsigned) -1 : (Unsigned) v; + } +} +NAMESPACE_END(detail) + +class int_ : public object { +public: + PYBIND11_OBJECT_CVT(int_, object, PYBIND11_LONG_CHECK, PyNumber_Long) + int_() : object(PyLong_FromLong(0), stolen_t{}) { } + // Allow implicit conversion from C++ integral types: + template ::value, int> = 0> + int_(T value) { + if (sizeof(T) <= sizeof(long)) { + if (std::is_signed::value) + m_ptr = PyLong_FromLong((long) value); + else + m_ptr = PyLong_FromUnsignedLong((unsigned long) value); + } else { + if (std::is_signed::value) + m_ptr = PyLong_FromLongLong((long long) value); + else + m_ptr = PyLong_FromUnsignedLongLong((unsigned long long) value); + } + if (!m_ptr) pybind11_fail("Could not allocate int object!"); + } + + template ::value, int> = 0> + operator T() const { + return std::is_unsigned::value + ? detail::as_unsigned(m_ptr) + : sizeof(T) <= sizeof(long) + ? (T) PyLong_AsLong(m_ptr) + : (T) PYBIND11_LONG_AS_LONGLONG(m_ptr); + } +}; + +class float_ : public object { +public: + PYBIND11_OBJECT_CVT(float_, object, PyFloat_Check, PyNumber_Float) + // Allow implicit conversion from float/double: + float_(float value) : object(PyFloat_FromDouble((double) value), stolen_t{}) { + if (!m_ptr) pybind11_fail("Could not allocate float object!"); + } + float_(double value = .0) : object(PyFloat_FromDouble((double) value), stolen_t{}) { + if (!m_ptr) pybind11_fail("Could not allocate float object!"); + } + operator float() const { return (float) PyFloat_AsDouble(m_ptr); } + operator double() const { return (double) PyFloat_AsDouble(m_ptr); } +}; + +class weakref : public object { +public: + PYBIND11_OBJECT_DEFAULT(weakref, object, PyWeakref_Check) + explicit weakref(handle obj, handle callback = {}) + : object(PyWeakref_NewRef(obj.ptr(), callback.ptr()), stolen_t{}) { + if (!m_ptr) pybind11_fail("Could not allocate weak reference!"); + } +}; + +class slice : public object { +public: + PYBIND11_OBJECT_DEFAULT(slice, object, PySlice_Check) + slice(ssize_t start_, ssize_t stop_, ssize_t step_) { + int_ start(start_), stop(stop_), step(step_); + m_ptr = PySlice_New(start.ptr(), stop.ptr(), step.ptr()); + if (!m_ptr) pybind11_fail("Could not allocate slice object!"); + } + bool compute(size_t length, size_t *start, size_t *stop, size_t *step, + size_t *slicelength) const { + return PySlice_GetIndicesEx((PYBIND11_SLICE_OBJECT *) m_ptr, + (ssize_t) length, (ssize_t *) start, + (ssize_t *) stop, (ssize_t *) step, + (ssize_t *) slicelength) == 0; + } + bool compute(ssize_t length, ssize_t *start, ssize_t *stop, ssize_t *step, + ssize_t *slicelength) const { + return PySlice_GetIndicesEx((PYBIND11_SLICE_OBJECT *) m_ptr, + length, start, + stop, step, + slicelength) == 0; + } +}; + +class capsule : public object { +public: + PYBIND11_OBJECT_DEFAULT(capsule, object, PyCapsule_CheckExact) + PYBIND11_DEPRECATED("Use reinterpret_borrow() or reinterpret_steal()") + capsule(PyObject *ptr, bool is_borrowed) : object(is_borrowed ? object(ptr, borrowed_t{}) : object(ptr, stolen_t{})) { } + + explicit capsule(const void *value, const char *name = nullptr, void (*destructor)(PyObject *) = nullptr) + : object(PyCapsule_New(const_cast(value), name, destructor), stolen_t{}) { + if (!m_ptr) + pybind11_fail("Could not allocate capsule object!"); + } + + PYBIND11_DEPRECATED("Please pass a destructor that takes a void pointer as input") + capsule(const void *value, void (*destruct)(PyObject *)) + : object(PyCapsule_New(const_cast(value), nullptr, destruct), stolen_t{}) { + if (!m_ptr) + pybind11_fail("Could not allocate capsule object!"); + } + + capsule(const void *value, void (*destructor)(void *)) { + m_ptr = PyCapsule_New(const_cast(value), nullptr, [](PyObject *o) { + auto destructor = reinterpret_cast(PyCapsule_GetContext(o)); + void *ptr = PyCapsule_GetPointer(o, nullptr); + destructor(ptr); + }); + + if (!m_ptr) + pybind11_fail("Could not allocate capsule object!"); + + if (PyCapsule_SetContext(m_ptr, (void *) destructor) != 0) + pybind11_fail("Could not set capsule context!"); + } + + capsule(void (*destructor)()) { + m_ptr = PyCapsule_New(reinterpret_cast(destructor), nullptr, [](PyObject *o) { + auto destructor = reinterpret_cast(PyCapsule_GetPointer(o, nullptr)); + destructor(); + }); + + if (!m_ptr) + pybind11_fail("Could not allocate capsule object!"); + } + + template operator T *() const { + auto name = this->name(); + T * result = static_cast(PyCapsule_GetPointer(m_ptr, name)); + if (!result) pybind11_fail("Unable to extract capsule contents!"); + return result; + } + + const char *name() const { return PyCapsule_GetName(m_ptr); } +}; + +class tuple : public object { +public: + PYBIND11_OBJECT_CVT(tuple, object, PyTuple_Check, PySequence_Tuple) + explicit tuple(size_t size = 0) : object(PyTuple_New((ssize_t) size), stolen_t{}) { + if (!m_ptr) pybind11_fail("Could not allocate tuple object!"); + } + size_t size() const { return (size_t) PyTuple_Size(m_ptr); } + detail::tuple_accessor operator[](size_t index) const { return {*this, index}; } + detail::item_accessor operator[](handle h) const { return object::operator[](h); } + detail::tuple_iterator begin() const { return {*this, 0}; } + detail::tuple_iterator end() const { return {*this, PyTuple_GET_SIZE(m_ptr)}; } +}; + +class dict : public object { +public: + PYBIND11_OBJECT_CVT(dict, object, PyDict_Check, raw_dict) + dict() : object(PyDict_New(), stolen_t{}) { + if (!m_ptr) pybind11_fail("Could not allocate dict object!"); + } + template ...>::value>, + // MSVC workaround: it can't compile an out-of-line definition, so defer the collector + typename collector = detail::deferred_t, Args...>> + explicit dict(Args &&...args) : dict(collector(std::forward(args)...).kwargs()) { } + + size_t size() const { return (size_t) PyDict_Size(m_ptr); } + detail::dict_iterator begin() const { return {*this, 0}; } + detail::dict_iterator end() const { return {}; } + void clear() const { PyDict_Clear(ptr()); } + bool contains(handle key) const { return PyDict_Contains(ptr(), key.ptr()) == 1; } + bool contains(const char *key) const { return PyDict_Contains(ptr(), pybind11::str(key).ptr()) == 1; } + +private: + /// Call the `dict` Python type -- always returns a new reference + static PyObject *raw_dict(PyObject *op) { + if (PyDict_Check(op)) + return handle(op).inc_ref().ptr(); + return PyObject_CallFunctionObjArgs((PyObject *) &PyDict_Type, op, nullptr); + } +}; + +class sequence : public object { +public: + PYBIND11_OBJECT_DEFAULT(sequence, object, PySequence_Check) + size_t size() const { return (size_t) PySequence_Size(m_ptr); } + detail::sequence_accessor operator[](size_t index) const { return {*this, index}; } + detail::item_accessor operator[](handle h) const { return object::operator[](h); } + detail::sequence_iterator begin() const { return {*this, 0}; } + detail::sequence_iterator end() const { return {*this, PySequence_Size(m_ptr)}; } +}; + +class list : public object { +public: + PYBIND11_OBJECT_CVT(list, object, PyList_Check, PySequence_List) + explicit list(size_t size = 0) : object(PyList_New((ssize_t) size), stolen_t{}) { + if (!m_ptr) pybind11_fail("Could not allocate list object!"); + } + size_t size() const { return (size_t) PyList_Size(m_ptr); } + detail::list_accessor operator[](size_t index) const { return {*this, index}; } + detail::item_accessor operator[](handle h) const { return object::operator[](h); } + detail::list_iterator begin() const { return {*this, 0}; } + detail::list_iterator end() const { return {*this, PyList_GET_SIZE(m_ptr)}; } + template void append(T &&val) const { + PyList_Append(m_ptr, detail::object_or_cast(std::forward(val)).ptr()); + } +}; + +class args : public tuple { PYBIND11_OBJECT_DEFAULT(args, tuple, PyTuple_Check) }; +class kwargs : public dict { PYBIND11_OBJECT_DEFAULT(kwargs, dict, PyDict_Check) }; + +class set : public object { +public: + PYBIND11_OBJECT_CVT(set, object, PySet_Check, PySet_New) + set() : object(PySet_New(nullptr), stolen_t{}) { + if (!m_ptr) pybind11_fail("Could not allocate set object!"); + } + size_t size() const { return (size_t) PySet_Size(m_ptr); } + template bool add(T &&val) const { + return PySet_Add(m_ptr, detail::object_or_cast(std::forward(val)).ptr()) == 0; + } + void clear() const { PySet_Clear(m_ptr); } +}; + +class function : public object { +public: + PYBIND11_OBJECT_DEFAULT(function, object, PyCallable_Check) + handle cpp_function() const { + handle fun = detail::get_function(m_ptr); + if (fun && PyCFunction_Check(fun.ptr())) + return fun; + return handle(); + } + bool is_cpp_function() const { return (bool) cpp_function(); } +}; + +class staticmethod : public object { +public: + PYBIND11_OBJECT_CVT(staticmethod, object, detail::PyStaticMethod_Check, PyStaticMethod_New) +}; + +class buffer : public object { +public: + PYBIND11_OBJECT_DEFAULT(buffer, object, PyObject_CheckBuffer) + + buffer_info request(bool writable = false) { + int flags = PyBUF_STRIDES | PyBUF_FORMAT; + if (writable) flags |= PyBUF_WRITABLE; + Py_buffer *view = new Py_buffer(); + if (PyObject_GetBuffer(m_ptr, view, flags) != 0) { + delete view; + throw error_already_set(); + } + return buffer_info(view); + } +}; + +class memoryview : public object { +public: + explicit memoryview(const buffer_info& info) { + static Py_buffer buf { }; + // Py_buffer uses signed sizes, strides and shape!.. + static std::vector py_strides { }; + static std::vector py_shape { }; + buf.buf = info.ptr; + buf.itemsize = info.itemsize; + buf.format = const_cast(info.format.c_str()); + buf.ndim = (int) info.ndim; + buf.len = info.size; + py_strides.clear(); + py_shape.clear(); + for (size_t i = 0; i < (size_t) info.ndim; ++i) { + py_strides.push_back(info.strides[i]); + py_shape.push_back(info.shape[i]); + } + buf.strides = py_strides.data(); + buf.shape = py_shape.data(); + buf.suboffsets = nullptr; + buf.readonly = false; + buf.internal = nullptr; + + m_ptr = PyMemoryView_FromBuffer(&buf); + if (!m_ptr) + pybind11_fail("Unable to create memoryview from buffer descriptor"); + } + + PYBIND11_OBJECT_CVT(memoryview, object, PyMemoryView_Check, PyMemoryView_FromObject) +}; +/// @} pytypes + +/// \addtogroup python_builtins +/// @{ +inline size_t len(handle h) { + ssize_t result = PyObject_Length(h.ptr()); + if (result < 0) + pybind11_fail("Unable to compute length of object"); + return (size_t) result; +} + +inline size_t len_hint(handle h) { +#if PY_VERSION_HEX >= 0x03040000 + ssize_t result = PyObject_LengthHint(h.ptr(), 0); +#else + ssize_t result = PyObject_Length(h.ptr()); +#endif + if (result < 0) { + // Sometimes a length can't be determined at all (eg generators) + // In which case simply return 0 + PyErr_Clear(); + return 0; + } + return (size_t) result; +} + +inline str repr(handle h) { + PyObject *str_value = PyObject_Repr(h.ptr()); + if (!str_value) throw error_already_set(); +#if PY_MAJOR_VERSION < 3 + PyObject *unicode = PyUnicode_FromEncodedObject(str_value, "utf-8", nullptr); + Py_XDECREF(str_value); str_value = unicode; + if (!str_value) throw error_already_set(); +#endif + return reinterpret_steal(str_value); +} + +inline iterator iter(handle obj) { + PyObject *result = PyObject_GetIter(obj.ptr()); + if (!result) { throw error_already_set(); } + return reinterpret_steal(result); +} +/// @} python_builtins + +NAMESPACE_BEGIN(detail) +template iterator object_api::begin() const { return iter(derived()); } +template iterator object_api::end() const { return iterator::sentinel(); } +template item_accessor object_api::operator[](handle key) const { + return {derived(), reinterpret_borrow(key)}; +} +template item_accessor object_api::operator[](const char *key) const { + return {derived(), pybind11::str(key)}; +} +template obj_attr_accessor object_api::attr(handle key) const { + return {derived(), reinterpret_borrow(key)}; +} +template str_attr_accessor object_api::attr(const char *key) const { + return {derived(), key}; +} +template args_proxy object_api::operator*() const { + return args_proxy(derived().ptr()); +} +template template bool object_api::contains(T &&item) const { + return attr("__contains__")(std::forward(item)).template cast(); +} + +template +pybind11::str object_api::str() const { return pybind11::str(derived()); } + +template +str_attr_accessor object_api::doc() const { return attr("__doc__"); } + +template +handle object_api::get_type() const { return (PyObject *) Py_TYPE(derived().ptr()); } + +template +bool object_api::rich_compare(object_api const &other, int value) const { + int rv = PyObject_RichCompareBool(derived().ptr(), other.derived().ptr(), value); + if (rv == -1) + throw error_already_set(); + return rv == 1; +} + +#define PYBIND11_MATH_OPERATOR_UNARY(op, fn) \ + template object object_api::op() const { \ + object result = reinterpret_steal(fn(derived().ptr())); \ + if (!result.ptr()) \ + throw error_already_set(); \ + return result; \ + } + +#define PYBIND11_MATH_OPERATOR_BINARY(op, fn) \ + template \ + object object_api::op(object_api const &other) const { \ + object result = reinterpret_steal( \ + fn(derived().ptr(), other.derived().ptr())); \ + if (!result.ptr()) \ + throw error_already_set(); \ + return result; \ + } + +PYBIND11_MATH_OPERATOR_UNARY (operator~, PyNumber_Invert) +PYBIND11_MATH_OPERATOR_UNARY (operator-, PyNumber_Negative) +PYBIND11_MATH_OPERATOR_BINARY(operator+, PyNumber_Add) +PYBIND11_MATH_OPERATOR_BINARY(operator+=, PyNumber_InPlaceAdd) +PYBIND11_MATH_OPERATOR_BINARY(operator-, PyNumber_Subtract) +PYBIND11_MATH_OPERATOR_BINARY(operator-=, PyNumber_InPlaceSubtract) +PYBIND11_MATH_OPERATOR_BINARY(operator*, PyNumber_Multiply) +PYBIND11_MATH_OPERATOR_BINARY(operator*=, PyNumber_InPlaceMultiply) +PYBIND11_MATH_OPERATOR_BINARY(operator/, PyNumber_TrueDivide) +PYBIND11_MATH_OPERATOR_BINARY(operator/=, PyNumber_InPlaceTrueDivide) +PYBIND11_MATH_OPERATOR_BINARY(operator|, PyNumber_Or) +PYBIND11_MATH_OPERATOR_BINARY(operator|=, PyNumber_InPlaceOr) +PYBIND11_MATH_OPERATOR_BINARY(operator&, PyNumber_And) +PYBIND11_MATH_OPERATOR_BINARY(operator&=, PyNumber_InPlaceAnd) +PYBIND11_MATH_OPERATOR_BINARY(operator^, PyNumber_Xor) +PYBIND11_MATH_OPERATOR_BINARY(operator^=, PyNumber_InPlaceXor) +PYBIND11_MATH_OPERATOR_BINARY(operator<<, PyNumber_Lshift) +PYBIND11_MATH_OPERATOR_BINARY(operator<<=, PyNumber_InPlaceLshift) +PYBIND11_MATH_OPERATOR_BINARY(operator>>, PyNumber_Rshift) +PYBIND11_MATH_OPERATOR_BINARY(operator>>=, PyNumber_InPlaceRshift) + +#undef PYBIND11_MATH_OPERATOR_UNARY +#undef PYBIND11_MATH_OPERATOR_BINARY + +NAMESPACE_END(detail) +NAMESPACE_END(PYBIND11_NAMESPACE) diff --git a/wrap/python/pybind11/include/pybind11/stl.h b/wrap/python/pybind11/include/pybind11/stl.h new file mode 100644 index 000000000..32f8d294a --- /dev/null +++ b/wrap/python/pybind11/include/pybind11/stl.h @@ -0,0 +1,386 @@ +/* + pybind11/stl.h: Transparent conversion for STL data types + + Copyright (c) 2016 Wenzel Jakob + + All rights reserved. Use of this source code is governed by a + BSD-style license that can be found in the LICENSE file. +*/ + +#pragma once + +#include "pybind11.h" +#include +#include +#include +#include +#include +#include +#include +#include + +#if defined(_MSC_VER) +#pragma warning(push) +#pragma warning(disable: 4127) // warning C4127: Conditional expression is constant +#endif + +#ifdef __has_include +// std::optional (but including it in c++14 mode isn't allowed) +# if defined(PYBIND11_CPP17) && __has_include() +# include +# define PYBIND11_HAS_OPTIONAL 1 +# endif +// std::experimental::optional (but not allowed in c++11 mode) +# if defined(PYBIND11_CPP14) && (__has_include() && \ + !__has_include()) +# include +# define PYBIND11_HAS_EXP_OPTIONAL 1 +# endif +// std::variant +# if defined(PYBIND11_CPP17) && __has_include() +# include +# define PYBIND11_HAS_VARIANT 1 +# endif +#elif defined(_MSC_VER) && defined(PYBIND11_CPP17) +# include +# include +# define PYBIND11_HAS_OPTIONAL 1 +# define PYBIND11_HAS_VARIANT 1 +#endif + +NAMESPACE_BEGIN(PYBIND11_NAMESPACE) +NAMESPACE_BEGIN(detail) + +/// Extracts an const lvalue reference or rvalue reference for U based on the type of T (e.g. for +/// forwarding a container element). Typically used indirect via forwarded_type(), below. +template +using forwarded_type = conditional_t< + std::is_lvalue_reference::value, remove_reference_t &, remove_reference_t &&>; + +/// Forwards a value U as rvalue or lvalue according to whether T is rvalue or lvalue; typically +/// used for forwarding a container's elements. +template +forwarded_type forward_like(U &&u) { + return std::forward>(std::forward(u)); +} + +template struct set_caster { + using type = Type; + using key_conv = make_caster; + + bool load(handle src, bool convert) { + if (!isinstance(src)) + return false; + auto s = reinterpret_borrow(src); + value.clear(); + for (auto entry : s) { + key_conv conv; + if (!conv.load(entry, convert)) + return false; + value.insert(cast_op(std::move(conv))); + } + return true; + } + + template + static handle cast(T &&src, return_value_policy policy, handle parent) { + if (!std::is_lvalue_reference::value) + policy = return_value_policy_override::policy(policy); + pybind11::set s; + for (auto &&value : src) { + auto value_ = reinterpret_steal(key_conv::cast(forward_like(value), policy, parent)); + if (!value_ || !s.add(value_)) + return handle(); + } + return s.release(); + } + + PYBIND11_TYPE_CASTER(type, _("Set[") + key_conv::name + _("]")); +}; + +template struct map_caster { + using key_conv = make_caster; + using value_conv = make_caster; + + bool load(handle src, bool convert) { + if (!isinstance(src)) + return false; + auto d = reinterpret_borrow(src); + value.clear(); + for (auto it : d) { + key_conv kconv; + value_conv vconv; + if (!kconv.load(it.first.ptr(), convert) || + !vconv.load(it.second.ptr(), convert)) + return false; + value.emplace(cast_op(std::move(kconv)), cast_op(std::move(vconv))); + } + return true; + } + + template + static handle cast(T &&src, return_value_policy policy, handle parent) { + dict d; + return_value_policy policy_key = policy; + return_value_policy policy_value = policy; + if (!std::is_lvalue_reference::value) { + policy_key = return_value_policy_override::policy(policy_key); + policy_value = return_value_policy_override::policy(policy_value); + } + for (auto &&kv : src) { + auto key = reinterpret_steal(key_conv::cast(forward_like(kv.first), policy_key, parent)); + auto value = reinterpret_steal(value_conv::cast(forward_like(kv.second), policy_value, parent)); + if (!key || !value) + return handle(); + d[key] = value; + } + return d.release(); + } + + PYBIND11_TYPE_CASTER(Type, _("Dict[") + key_conv::name + _(", ") + value_conv::name + _("]")); +}; + +template struct list_caster { + using value_conv = make_caster; + + bool load(handle src, bool convert) { + if (!isinstance(src) || isinstance(src)) + return false; + auto s = reinterpret_borrow(src); + value.clear(); + reserve_maybe(s, &value); + for (auto it : s) { + value_conv conv; + if (!conv.load(it, convert)) + return false; + value.push_back(cast_op(std::move(conv))); + } + return true; + } + +private: + template ().reserve(0)), void>::value, int> = 0> + void reserve_maybe(sequence s, Type *) { value.reserve(s.size()); } + void reserve_maybe(sequence, void *) { } + +public: + template + static handle cast(T &&src, return_value_policy policy, handle parent) { + if (!std::is_lvalue_reference::value) + policy = return_value_policy_override::policy(policy); + list l(src.size()); + size_t index = 0; + for (auto &&value : src) { + auto value_ = reinterpret_steal(value_conv::cast(forward_like(value), policy, parent)); + if (!value_) + return handle(); + PyList_SET_ITEM(l.ptr(), (ssize_t) index++, value_.release().ptr()); // steals a reference + } + return l.release(); + } + + PYBIND11_TYPE_CASTER(Type, _("List[") + value_conv::name + _("]")); +}; + +template struct type_caster> + : list_caster, Type> { }; + +template struct type_caster> + : list_caster, Type> { }; + +template struct type_caster> + : list_caster, Type> { }; + +template struct array_caster { + using value_conv = make_caster; + +private: + template + bool require_size(enable_if_t size) { + if (value.size() != size) + value.resize(size); + return true; + } + template + bool require_size(enable_if_t size) { + return size == Size; + } + +public: + bool load(handle src, bool convert) { + if (!isinstance(src)) + return false; + auto l = reinterpret_borrow(src); + if (!require_size(l.size())) + return false; + size_t ctr = 0; + for (auto it : l) { + value_conv conv; + if (!conv.load(it, convert)) + return false; + value[ctr++] = cast_op(std::move(conv)); + } + return true; + } + + template + static handle cast(T &&src, return_value_policy policy, handle parent) { + list l(src.size()); + size_t index = 0; + for (auto &&value : src) { + auto value_ = reinterpret_steal(value_conv::cast(forward_like(value), policy, parent)); + if (!value_) + return handle(); + PyList_SET_ITEM(l.ptr(), (ssize_t) index++, value_.release().ptr()); // steals a reference + } + return l.release(); + } + + PYBIND11_TYPE_CASTER(ArrayType, _("List[") + value_conv::name + _(_(""), _("[") + _() + _("]")) + _("]")); +}; + +template struct type_caster> + : array_caster, Type, false, Size> { }; + +template struct type_caster> + : array_caster, Type, true> { }; + +template struct type_caster> + : set_caster, Key> { }; + +template struct type_caster> + : set_caster, Key> { }; + +template struct type_caster> + : map_caster, Key, Value> { }; + +template struct type_caster> + : map_caster, Key, Value> { }; + +// This type caster is intended to be used for std::optional and std::experimental::optional +template struct optional_caster { + using value_conv = make_caster; + + template + static handle cast(T_ &&src, return_value_policy policy, handle parent) { + if (!src) + return none().inc_ref(); + policy = return_value_policy_override::policy(policy); + return value_conv::cast(*std::forward(src), policy, parent); + } + + bool load(handle src, bool convert) { + if (!src) { + return false; + } else if (src.is_none()) { + return true; // default-constructed value is already empty + } + value_conv inner_caster; + if (!inner_caster.load(src, convert)) + return false; + + value.emplace(cast_op(std::move(inner_caster))); + return true; + } + + PYBIND11_TYPE_CASTER(T, _("Optional[") + value_conv::name + _("]")); +}; + +#if PYBIND11_HAS_OPTIONAL +template struct type_caster> + : public optional_caster> {}; + +template<> struct type_caster + : public void_caster {}; +#endif + +#if PYBIND11_HAS_EXP_OPTIONAL +template struct type_caster> + : public optional_caster> {}; + +template<> struct type_caster + : public void_caster {}; +#endif + +/// Visit a variant and cast any found type to Python +struct variant_caster_visitor { + return_value_policy policy; + handle parent; + + using result_type = handle; // required by boost::variant in C++11 + + template + result_type operator()(T &&src) const { + return make_caster::cast(std::forward(src), policy, parent); + } +}; + +/// Helper class which abstracts away variant's `visit` function. `std::variant` and similar +/// `namespace::variant` types which provide a `namespace::visit()` function are handled here +/// automatically using argument-dependent lookup. Users can provide specializations for other +/// variant-like classes, e.g. `boost::variant` and `boost::apply_visitor`. +template class Variant> +struct visit_helper { + template + static auto call(Args &&...args) -> decltype(visit(std::forward(args)...)) { + return visit(std::forward(args)...); + } +}; + +/// Generic variant caster +template struct variant_caster; + +template class V, typename... Ts> +struct variant_caster> { + static_assert(sizeof...(Ts) > 0, "Variant must consist of at least one alternative."); + + template + bool load_alternative(handle src, bool convert, type_list) { + auto caster = make_caster(); + if (caster.load(src, convert)) { + value = cast_op(caster); + return true; + } + return load_alternative(src, convert, type_list{}); + } + + bool load_alternative(handle, bool, type_list<>) { return false; } + + bool load(handle src, bool convert) { + // Do a first pass without conversions to improve constructor resolution. + // E.g. `py::int_(1).cast>()` needs to fill the `int` + // slot of the variant. Without two-pass loading `double` would be filled + // because it appears first and a conversion is possible. + if (convert && load_alternative(src, false, type_list{})) + return true; + return load_alternative(src, convert, type_list{}); + } + + template + static handle cast(Variant &&src, return_value_policy policy, handle parent) { + return visit_helper::call(variant_caster_visitor{policy, parent}, + std::forward(src)); + } + + using Type = V; + PYBIND11_TYPE_CASTER(Type, _("Union[") + detail::concat(make_caster::name...) + _("]")); +}; + +#if PYBIND11_HAS_VARIANT +template +struct type_caster> : variant_caster> { }; +#endif + +NAMESPACE_END(detail) + +inline std::ostream &operator<<(std::ostream &os, const handle &obj) { + os << (std::string) str(obj); + return os; +} + +NAMESPACE_END(PYBIND11_NAMESPACE) + +#if defined(_MSC_VER) +#pragma warning(pop) +#endif diff --git a/wrap/python/pybind11/include/pybind11/stl_bind.h b/wrap/python/pybind11/include/pybind11/stl_bind.h new file mode 100644 index 000000000..1f8725260 --- /dev/null +++ b/wrap/python/pybind11/include/pybind11/stl_bind.h @@ -0,0 +1,630 @@ +/* + pybind11/std_bind.h: Binding generators for STL data types + + Copyright (c) 2016 Sergey Lyskov and Wenzel Jakob + + All rights reserved. Use of this source code is governed by a + BSD-style license that can be found in the LICENSE file. +*/ + +#pragma once + +#include "detail/common.h" +#include "operators.h" + +#include +#include + +NAMESPACE_BEGIN(PYBIND11_NAMESPACE) +NAMESPACE_BEGIN(detail) + +/* SFINAE helper class used by 'is_comparable */ +template struct container_traits { + template static std::true_type test_comparable(decltype(std::declval() == std::declval())*); + template static std::false_type test_comparable(...); + template static std::true_type test_value(typename T2::value_type *); + template static std::false_type test_value(...); + template static std::true_type test_pair(typename T2::first_type *, typename T2::second_type *); + template static std::false_type test_pair(...); + + static constexpr const bool is_comparable = std::is_same(nullptr))>::value; + static constexpr const bool is_pair = std::is_same(nullptr, nullptr))>::value; + static constexpr const bool is_vector = std::is_same(nullptr))>::value; + static constexpr const bool is_element = !is_pair && !is_vector; +}; + +/* Default: is_comparable -> std::false_type */ +template +struct is_comparable : std::false_type { }; + +/* For non-map data structures, check whether operator== can be instantiated */ +template +struct is_comparable< + T, enable_if_t::is_element && + container_traits::is_comparable>> + : std::true_type { }; + +/* For a vector/map data structure, recursively check the value type (which is std::pair for maps) */ +template +struct is_comparable::is_vector>> { + static constexpr const bool value = + is_comparable::value; +}; + +/* For pairs, recursively check the two data types */ +template +struct is_comparable::is_pair>> { + static constexpr const bool value = + is_comparable::value && + is_comparable::value; +}; + +/* Fallback functions */ +template void vector_if_copy_constructible(const Args &...) { } +template void vector_if_equal_operator(const Args &...) { } +template void vector_if_insertion_operator(const Args &...) { } +template void vector_modifiers(const Args &...) { } + +template +void vector_if_copy_constructible(enable_if_t::value, Class_> &cl) { + cl.def(init(), "Copy constructor"); +} + +template +void vector_if_equal_operator(enable_if_t::value, Class_> &cl) { + using T = typename Vector::value_type; + + cl.def(self == self); + cl.def(self != self); + + cl.def("count", + [](const Vector &v, const T &x) { + return std::count(v.begin(), v.end(), x); + }, + arg("x"), + "Return the number of times ``x`` appears in the list" + ); + + cl.def("remove", [](Vector &v, const T &x) { + auto p = std::find(v.begin(), v.end(), x); + if (p != v.end()) + v.erase(p); + else + throw value_error(); + }, + arg("x"), + "Remove the first item from the list whose value is x. " + "It is an error if there is no such item." + ); + + cl.def("__contains__", + [](const Vector &v, const T &x) { + return std::find(v.begin(), v.end(), x) != v.end(); + }, + arg("x"), + "Return true the container contains ``x``" + ); +} + +// Vector modifiers -- requires a copyable vector_type: +// (Technically, some of these (pop and __delitem__) don't actually require copyability, but it seems +// silly to allow deletion but not insertion, so include them here too.) +template +void vector_modifiers(enable_if_t::value, Class_> &cl) { + using T = typename Vector::value_type; + using SizeType = typename Vector::size_type; + using DiffType = typename Vector::difference_type; + + cl.def("append", + [](Vector &v, const T &value) { v.push_back(value); }, + arg("x"), + "Add an item to the end of the list"); + + cl.def(init([](iterable it) { + auto v = std::unique_ptr(new Vector()); + v->reserve(len_hint(it)); + for (handle h : it) + v->push_back(h.cast()); + return v.release(); + })); + + cl.def("extend", + [](Vector &v, const Vector &src) { + v.insert(v.end(), src.begin(), src.end()); + }, + arg("L"), + "Extend the list by appending all the items in the given list" + ); + + cl.def("extend", + [](Vector &v, iterable it) { + const size_t old_size = v.size(); + v.reserve(old_size + len_hint(it)); + try { + for (handle h : it) { + v.push_back(h.cast()); + } + } catch (const cast_error &) { + v.erase(v.begin() + static_cast(old_size), v.end()); + try { + v.shrink_to_fit(); + } catch (const std::exception &) { + // Do nothing + } + throw; + } + }, + arg("L"), + "Extend the list by appending all the items in the given list" + ); + + cl.def("insert", + [](Vector &v, SizeType i, const T &x) { + if (i > v.size()) + throw index_error(); + v.insert(v.begin() + (DiffType) i, x); + }, + arg("i") , arg("x"), + "Insert an item at a given position." + ); + + cl.def("pop", + [](Vector &v) { + if (v.empty()) + throw index_error(); + T t = v.back(); + v.pop_back(); + return t; + }, + "Remove and return the last item" + ); + + cl.def("pop", + [](Vector &v, SizeType i) { + if (i >= v.size()) + throw index_error(); + T t = v[i]; + v.erase(v.begin() + (DiffType) i); + return t; + }, + arg("i"), + "Remove and return the item at index ``i``" + ); + + cl.def("__setitem__", + [](Vector &v, SizeType i, const T &t) { + if (i >= v.size()) + throw index_error(); + v[i] = t; + } + ); + + /// Slicing protocol + cl.def("__getitem__", + [](const Vector &v, slice slice) -> Vector * { + size_t start, stop, step, slicelength; + + if (!slice.compute(v.size(), &start, &stop, &step, &slicelength)) + throw error_already_set(); + + Vector *seq = new Vector(); + seq->reserve((size_t) slicelength); + + for (size_t i=0; ipush_back(v[start]); + start += step; + } + return seq; + }, + arg("s"), + "Retrieve list elements using a slice object" + ); + + cl.def("__setitem__", + [](Vector &v, slice slice, const Vector &value) { + size_t start, stop, step, slicelength; + if (!slice.compute(v.size(), &start, &stop, &step, &slicelength)) + throw error_already_set(); + + if (slicelength != value.size()) + throw std::runtime_error("Left and right hand size of slice assignment have different sizes!"); + + for (size_t i=0; i= v.size()) + throw index_error(); + v.erase(v.begin() + DiffType(i)); + }, + "Delete the list elements at index ``i``" + ); + + cl.def("__delitem__", + [](Vector &v, slice slice) { + size_t start, stop, step, slicelength; + + if (!slice.compute(v.size(), &start, &stop, &step, &slicelength)) + throw error_already_set(); + + if (step == 1 && false) { + v.erase(v.begin() + (DiffType) start, v.begin() + DiffType(start + slicelength)); + } else { + for (size_t i = 0; i < slicelength; ++i) { + v.erase(v.begin() + DiffType(start)); + start += step - 1; + } + } + }, + "Delete list elements using a slice object" + ); + +} + +// If the type has an operator[] that doesn't return a reference (most notably std::vector), +// we have to access by copying; otherwise we return by reference. +template using vector_needs_copy = negation< + std::is_same()[typename Vector::size_type()]), typename Vector::value_type &>>; + +// The usual case: access and iterate by reference +template +void vector_accessor(enable_if_t::value, Class_> &cl) { + using T = typename Vector::value_type; + using SizeType = typename Vector::size_type; + using ItType = typename Vector::iterator; + + cl.def("__getitem__", + [](Vector &v, SizeType i) -> T & { + if (i >= v.size()) + throw index_error(); + return v[i]; + }, + return_value_policy::reference_internal // ref + keepalive + ); + + cl.def("__iter__", + [](Vector &v) { + return make_iterator< + return_value_policy::reference_internal, ItType, ItType, T&>( + v.begin(), v.end()); + }, + keep_alive<0, 1>() /* Essential: keep list alive while iterator exists */ + ); +} + +// The case for special objects, like std::vector, that have to be returned-by-copy: +template +void vector_accessor(enable_if_t::value, Class_> &cl) { + using T = typename Vector::value_type; + using SizeType = typename Vector::size_type; + using ItType = typename Vector::iterator; + cl.def("__getitem__", + [](const Vector &v, SizeType i) -> T { + if (i >= v.size()) + throw index_error(); + return v[i]; + } + ); + + cl.def("__iter__", + [](Vector &v) { + return make_iterator< + return_value_policy::copy, ItType, ItType, T>( + v.begin(), v.end()); + }, + keep_alive<0, 1>() /* Essential: keep list alive while iterator exists */ + ); +} + +template auto vector_if_insertion_operator(Class_ &cl, std::string const &name) + -> decltype(std::declval() << std::declval(), void()) { + using size_type = typename Vector::size_type; + + cl.def("__repr__", + [name](Vector &v) { + std::ostringstream s; + s << name << '['; + for (size_type i=0; i < v.size(); ++i) { + s << v[i]; + if (i != v.size() - 1) + s << ", "; + } + s << ']'; + return s.str(); + }, + "Return the canonical string representation of this list." + ); +} + +// Provide the buffer interface for vectors if we have data() and we have a format for it +// GCC seems to have "void std::vector::data()" - doing SFINAE on the existence of data() is insufficient, we need to check it returns an appropriate pointer +template +struct vector_has_data_and_format : std::false_type {}; +template +struct vector_has_data_and_format::format(), std::declval().data()), typename Vector::value_type*>::value>> : std::true_type {}; + +// Add the buffer interface to a vector +template +enable_if_t...>::value> +vector_buffer(Class_& cl) { + using T = typename Vector::value_type; + + static_assert(vector_has_data_and_format::value, "There is not an appropriate format descriptor for this vector"); + + // numpy.h declares this for arbitrary types, but it may raise an exception and crash hard at runtime if PYBIND11_NUMPY_DTYPE hasn't been called, so check here + format_descriptor::format(); + + cl.def_buffer([](Vector& v) -> buffer_info { + return buffer_info(v.data(), static_cast(sizeof(T)), format_descriptor::format(), 1, {v.size()}, {sizeof(T)}); + }); + + cl.def(init([](buffer buf) { + auto info = buf.request(); + if (info.ndim != 1 || info.strides[0] % static_cast(sizeof(T))) + throw type_error("Only valid 1D buffers can be copied to a vector"); + if (!detail::compare_buffer_info::compare(info) || (ssize_t) sizeof(T) != info.itemsize) + throw type_error("Format mismatch (Python: " + info.format + " C++: " + format_descriptor::format() + ")"); + + auto vec = std::unique_ptr(new Vector()); + vec->reserve((size_t) info.shape[0]); + T *p = static_cast(info.ptr); + ssize_t step = info.strides[0] / static_cast(sizeof(T)); + T *end = p + info.shape[0] * step; + for (; p != end; p += step) + vec->push_back(*p); + return vec.release(); + })); + + return; +} + +template +enable_if_t...>::value> vector_buffer(Class_&) {} + +NAMESPACE_END(detail) + +// +// std::vector +// +template , typename... Args> +class_ bind_vector(handle scope, std::string const &name, Args&&... args) { + using Class_ = class_; + + // If the value_type is unregistered (e.g. a converting type) or is itself registered + // module-local then make the vector binding module-local as well: + using vtype = typename Vector::value_type; + auto vtype_info = detail::get_type_info(typeid(vtype)); + bool local = !vtype_info || vtype_info->module_local; + + Class_ cl(scope, name.c_str(), pybind11::module_local(local), std::forward(args)...); + + // Declare the buffer interface if a buffer_protocol() is passed in + detail::vector_buffer(cl); + + cl.def(init<>()); + + // Register copy constructor (if possible) + detail::vector_if_copy_constructible(cl); + + // Register comparison-related operators and functions (if possible) + detail::vector_if_equal_operator(cl); + + // Register stream insertion operator (if possible) + detail::vector_if_insertion_operator(cl, name); + + // Modifiers require copyable vector value type + detail::vector_modifiers(cl); + + // Accessor and iterator; return by value if copyable, otherwise we return by ref + keep-alive + detail::vector_accessor(cl); + + cl.def("__bool__", + [](const Vector &v) -> bool { + return !v.empty(); + }, + "Check whether the list is nonempty" + ); + + cl.def("__len__", &Vector::size); + + + + +#if 0 + // C++ style functions deprecated, leaving it here as an example + cl.def(init()); + + cl.def("resize", + (void (Vector::*) (size_type count)) & Vector::resize, + "changes the number of elements stored"); + + cl.def("erase", + [](Vector &v, SizeType i) { + if (i >= v.size()) + throw index_error(); + v.erase(v.begin() + i); + }, "erases element at index ``i``"); + + cl.def("empty", &Vector::empty, "checks whether the container is empty"); + cl.def("size", &Vector::size, "returns the number of elements"); + cl.def("push_back", (void (Vector::*)(const T&)) &Vector::push_back, "adds an element to the end"); + cl.def("pop_back", &Vector::pop_back, "removes the last element"); + + cl.def("max_size", &Vector::max_size, "returns the maximum possible number of elements"); + cl.def("reserve", &Vector::reserve, "reserves storage"); + cl.def("capacity", &Vector::capacity, "returns the number of elements that can be held in currently allocated storage"); + cl.def("shrink_to_fit", &Vector::shrink_to_fit, "reduces memory usage by freeing unused memory"); + + cl.def("clear", &Vector::clear, "clears the contents"); + cl.def("swap", &Vector::swap, "swaps the contents"); + + cl.def("front", [](Vector &v) { + if (v.size()) return v.front(); + else throw index_error(); + }, "access the first element"); + + cl.def("back", [](Vector &v) { + if (v.size()) return v.back(); + else throw index_error(); + }, "access the last element "); + +#endif + + return cl; +} + + + +// +// std::map, std::unordered_map +// + +NAMESPACE_BEGIN(detail) + +/* Fallback functions */ +template void map_if_insertion_operator(const Args &...) { } +template void map_assignment(const Args &...) { } + +// Map assignment when copy-assignable: just copy the value +template +void map_assignment(enable_if_t::value, Class_> &cl) { + using KeyType = typename Map::key_type; + using MappedType = typename Map::mapped_type; + + cl.def("__setitem__", + [](Map &m, const KeyType &k, const MappedType &v) { + auto it = m.find(k); + if (it != m.end()) it->second = v; + else m.emplace(k, v); + } + ); +} + +// Not copy-assignable, but still copy-constructible: we can update the value by erasing and reinserting +template +void map_assignment(enable_if_t< + !std::is_copy_assignable::value && + is_copy_constructible::value, + Class_> &cl) { + using KeyType = typename Map::key_type; + using MappedType = typename Map::mapped_type; + + cl.def("__setitem__", + [](Map &m, const KeyType &k, const MappedType &v) { + // We can't use m[k] = v; because value type might not be default constructable + auto r = m.emplace(k, v); + if (!r.second) { + // value type is not copy assignable so the only way to insert it is to erase it first... + m.erase(r.first); + m.emplace(k, v); + } + } + ); +} + + +template auto map_if_insertion_operator(Class_ &cl, std::string const &name) +-> decltype(std::declval() << std::declval() << std::declval(), void()) { + + cl.def("__repr__", + [name](Map &m) { + std::ostringstream s; + s << name << '{'; + bool f = false; + for (auto const &kv : m) { + if (f) + s << ", "; + s << kv.first << ": " << kv.second; + f = true; + } + s << '}'; + return s.str(); + }, + "Return the canonical string representation of this map." + ); +} + + +NAMESPACE_END(detail) + +template , typename... Args> +class_ bind_map(handle scope, const std::string &name, Args&&... args) { + using KeyType = typename Map::key_type; + using MappedType = typename Map::mapped_type; + using Class_ = class_; + + // If either type is a non-module-local bound type then make the map binding non-local as well; + // otherwise (e.g. both types are either module-local or converting) the map will be + // module-local. + auto tinfo = detail::get_type_info(typeid(MappedType)); + bool local = !tinfo || tinfo->module_local; + if (local) { + tinfo = detail::get_type_info(typeid(KeyType)); + local = !tinfo || tinfo->module_local; + } + + Class_ cl(scope, name.c_str(), pybind11::module_local(local), std::forward(args)...); + + cl.def(init<>()); + + // Register stream insertion operator (if possible) + detail::map_if_insertion_operator(cl, name); + + cl.def("__bool__", + [](const Map &m) -> bool { return !m.empty(); }, + "Check whether the map is nonempty" + ); + + cl.def("__iter__", + [](Map &m) { return make_key_iterator(m.begin(), m.end()); }, + keep_alive<0, 1>() /* Essential: keep list alive while iterator exists */ + ); + + cl.def("items", + [](Map &m) { return make_iterator(m.begin(), m.end()); }, + keep_alive<0, 1>() /* Essential: keep list alive while iterator exists */ + ); + + cl.def("__getitem__", + [](Map &m, const KeyType &k) -> MappedType & { + auto it = m.find(k); + if (it == m.end()) + throw key_error(); + return it->second; + }, + return_value_policy::reference_internal // ref + keepalive + ); + + cl.def("__contains__", + [](Map &m, const KeyType &k) -> bool { + auto it = m.find(k); + if (it == m.end()) + return false; + return true; + } + ); + + // Assignment provided only if the type is copyable + detail::map_assignment(cl); + + cl.def("__delitem__", + [](Map &m, const KeyType &k) { + auto it = m.find(k); + if (it == m.end()) + throw key_error(); + m.erase(it); + } + ); + + cl.def("__len__", &Map::size); + + return cl; +} + +NAMESPACE_END(PYBIND11_NAMESPACE) diff --git a/wrap/python/pybind11/pybind11/__init__.py b/wrap/python/pybind11/pybind11/__init__.py new file mode 100644 index 000000000..5782ffea2 --- /dev/null +++ b/wrap/python/pybind11/pybind11/__init__.py @@ -0,0 +1,28 @@ +from ._version import version_info, __version__ # noqa: F401 imported but unused + + +def get_include(user=False): + from distutils.dist import Distribution + import os + import sys + + # Are we running in a virtual environment? + virtualenv = hasattr(sys, 'real_prefix') or \ + sys.prefix != getattr(sys, "base_prefix", sys.prefix) + + if virtualenv: + return os.path.join(sys.prefix, 'include', 'site', + 'python' + sys.version[:3]) + else: + dist = Distribution({'name': 'pybind11'}) + dist.parse_config_files() + + dist_cobj = dist.get_command_obj('install', create=True) + + # Search for packages in user's home directory? + if user: + dist_cobj.user = user + dist_cobj.prefix = "" + dist_cobj.finalize_options() + + return os.path.dirname(dist_cobj.install_headers) diff --git a/wrap/python/pybind11/pybind11/__main__.py b/wrap/python/pybind11/pybind11/__main__.py new file mode 100644 index 000000000..9ef837802 --- /dev/null +++ b/wrap/python/pybind11/pybind11/__main__.py @@ -0,0 +1,37 @@ +from __future__ import print_function + +import argparse +import sys +import sysconfig + +from . import get_include + + +def print_includes(): + dirs = [sysconfig.get_path('include'), + sysconfig.get_path('platinclude'), + get_include(), + get_include(True)] + + # Make unique but preserve order + unique_dirs = [] + for d in dirs: + if d not in unique_dirs: + unique_dirs.append(d) + + print(' '.join('-I' + d for d in unique_dirs)) + + +def main(): + parser = argparse.ArgumentParser(prog='python -m pybind11') + parser.add_argument('--includes', action='store_true', + help='Include flags for both pybind11 and Python headers.') + args = parser.parse_args() + if not sys.argv[1:]: + parser.print_help() + if args.includes: + print_includes() + + +if __name__ == '__main__': + main() diff --git a/wrap/python/pybind11/pybind11/_version.py b/wrap/python/pybind11/pybind11/_version.py new file mode 100644 index 000000000..fef541bdb --- /dev/null +++ b/wrap/python/pybind11/pybind11/_version.py @@ -0,0 +1,2 @@ +version_info = (2, 3, 'dev1') +__version__ = '.'.join(map(str, version_info)) diff --git a/wrap/python/pybind11/setup.cfg b/wrap/python/pybind11/setup.cfg new file mode 100644 index 000000000..002f38d10 --- /dev/null +++ b/wrap/python/pybind11/setup.cfg @@ -0,0 +1,12 @@ +[bdist_wheel] +universal=1 + +[flake8] +max-line-length = 99 +show_source = True +exclude = .git, __pycache__, build, dist, docs, tools, venv +ignore = + # required for pretty matrix formatting: multiple spaces after `,` and `[` + E201, E241, W504, + # camelcase 'cPickle' imported as lowercase 'pickle' + N813 diff --git a/wrap/python/pybind11/setup.py b/wrap/python/pybind11/setup.py new file mode 100644 index 000000000..f677f2af4 --- /dev/null +++ b/wrap/python/pybind11/setup.py @@ -0,0 +1,108 @@ +#!/usr/bin/env python + +# Setup script for PyPI; use CMakeFile.txt to build extension modules + +from setuptools import setup +from distutils.command.install_headers import install_headers +from pybind11 import __version__ +import os + +# Prevent installation of pybind11 headers by setting +# PYBIND11_USE_CMAKE. +if os.environ.get('PYBIND11_USE_CMAKE'): + headers = [] +else: + headers = [ + 'include/pybind11/detail/class.h', + 'include/pybind11/detail/common.h', + 'include/pybind11/detail/descr.h', + 'include/pybind11/detail/init.h', + 'include/pybind11/detail/internals.h', + 'include/pybind11/detail/typeid.h', + 'include/pybind11/attr.h', + 'include/pybind11/buffer_info.h', + 'include/pybind11/cast.h', + 'include/pybind11/chrono.h', + 'include/pybind11/common.h', + 'include/pybind11/complex.h', + 'include/pybind11/eigen.h', + 'include/pybind11/embed.h', + 'include/pybind11/eval.h', + 'include/pybind11/functional.h', + 'include/pybind11/iostream.h', + 'include/pybind11/numpy.h', + 'include/pybind11/operators.h', + 'include/pybind11/options.h', + 'include/pybind11/pybind11.h', + 'include/pybind11/pytypes.h', + 'include/pybind11/stl.h', + 'include/pybind11/stl_bind.h', + ] + + +class InstallHeaders(install_headers): + """Use custom header installer because the default one flattens subdirectories""" + def run(self): + if not self.distribution.headers: + return + + for header in self.distribution.headers: + subdir = os.path.dirname(os.path.relpath(header, 'include/pybind11')) + install_dir = os.path.join(self.install_dir, subdir) + self.mkpath(install_dir) + + (out, _) = self.copy_file(header, install_dir) + self.outfiles.append(out) + + +setup( + name='pybind11', + version=__version__, + description='Seamless operability between C++11 and Python', + author='Wenzel Jakob', + author_email='wenzel.jakob@epfl.ch', + url='https://github.com/pybind/pybind11', + download_url='https://github.com/pybind/pybind11/tarball/v' + __version__, + packages=['pybind11'], + license='BSD', + headers=headers, + cmdclass=dict(install_headers=InstallHeaders), + classifiers=[ + 'Development Status :: 5 - Production/Stable', + 'Intended Audience :: Developers', + 'Topic :: Software Development :: Libraries :: Python Modules', + 'Topic :: Utilities', + 'Programming Language :: C++', + 'Programming Language :: Python :: 2.7', + 'Programming Language :: Python :: 3', + 'Programming Language :: Python :: 3.2', + 'Programming Language :: Python :: 3.3', + 'Programming Language :: Python :: 3.4', + 'Programming Language :: Python :: 3.5', + 'Programming Language :: Python :: 3.6', + 'License :: OSI Approved :: BSD License' + ], + keywords='C++11, Python bindings', + long_description="""pybind11 is a lightweight header-only library that +exposes C++ types in Python and vice versa, mainly to create Python bindings of +existing C++ code. Its goals and syntax are similar to the excellent +Boost.Python by David Abrahams: to minimize boilerplate code in traditional +extension modules by inferring type information using compile-time +introspection. + +The main issue with Boost.Python-and the reason for creating such a similar +project-is Boost. Boost is an enormously large and complex suite of utility +libraries that works with almost every C++ compiler in existence. This +compatibility has its cost: arcane template tricks and workarounds are +necessary to support the oldest and buggiest of compiler specimens. Now that +C++11-compatible compilers are widely available, this heavy machinery has +become an excessively large and unnecessary dependency. + +Think of this library as a tiny self-contained version of Boost.Python with +everything stripped away that isn't relevant for binding generation. Without +comments, the core header files only require ~4K lines of code and depend on +Python (2.7 or 3.x, or PyPy2.7 >= 5.7) and the C++ standard library. This +compact implementation was possible thanks to some of the new C++11 language +features (specifically: tuples, lambda functions and variadic templates). Since +its creation, this library has grown beyond Boost.Python in many ways, leading +to dramatically simpler binding code in many common situations.""") diff --git a/wrap/python/pybind11/tests/CMakeLists.txt b/wrap/python/pybind11/tests/CMakeLists.txt new file mode 100644 index 000000000..9a701108c --- /dev/null +++ b/wrap/python/pybind11/tests/CMakeLists.txt @@ -0,0 +1,239 @@ +# CMakeLists.txt -- Build system for the pybind11 test suite +# +# Copyright (c) 2015 Wenzel Jakob +# +# All rights reserved. Use of this source code is governed by a +# BSD-style license that can be found in the LICENSE file. + +cmake_minimum_required(VERSION 2.8.12) + +option(PYBIND11_WERROR "Report all warnings as errors" OFF) + +if (CMAKE_CURRENT_SOURCE_DIR STREQUAL CMAKE_SOURCE_DIR) + # We're being loaded directly, i.e. not via add_subdirectory, so make this + # work as its own project and load the pybind11Config to get the tools we need + project(pybind11_tests CXX) + + find_package(pybind11 REQUIRED CONFIG) +endif() + +if(NOT CMAKE_BUILD_TYPE AND NOT CMAKE_CONFIGURATION_TYPES) + message(STATUS "Setting tests build type to MinSizeRel as none was specified") + set(CMAKE_BUILD_TYPE MinSizeRel CACHE STRING "Choose the type of build." FORCE) + set_property(CACHE CMAKE_BUILD_TYPE PROPERTY STRINGS "Debug" "Release" + "MinSizeRel" "RelWithDebInfo") +endif() + +# Full set of test files (you can override these; see below) +set(PYBIND11_TEST_FILES + test_buffers.cpp + test_builtin_casters.cpp + test_call_policies.cpp + test_callbacks.cpp + test_chrono.cpp + test_class.cpp + test_constants_and_functions.cpp + test_copy_move.cpp + test_docstring_options.cpp + test_eigen.cpp + test_enum.cpp + test_eval.cpp + test_exceptions.cpp + test_factory_constructors.cpp + test_gil_scoped.cpp + test_iostream.cpp + test_kwargs_and_defaults.cpp + test_local_bindings.cpp + test_methods_and_attributes.cpp + test_modules.cpp + test_multiple_inheritance.cpp + test_numpy_array.cpp + test_numpy_dtypes.cpp + test_numpy_vectorize.cpp + test_opaque_types.cpp + test_operator_overloading.cpp + test_pickling.cpp + test_pytypes.cpp + test_sequences_and_iterators.cpp + test_smart_ptr.cpp + test_stl.cpp + test_stl_binders.cpp + test_tagbased_polymorphic.cpp + test_union.cpp + test_virtual_functions.cpp +) + +# Invoking cmake with something like: +# cmake -DPYBIND11_TEST_OVERRIDE="test_callbacks.cpp;test_picking.cpp" .. +# lets you override the tests that get compiled and run. You can restore to all tests with: +# cmake -DPYBIND11_TEST_OVERRIDE= .. +if (PYBIND11_TEST_OVERRIDE) + set(PYBIND11_TEST_FILES ${PYBIND11_TEST_OVERRIDE}) +endif() + +string(REPLACE ".cpp" ".py" PYBIND11_PYTEST_FILES "${PYBIND11_TEST_FILES}") + +# Contains the set of test files that require pybind11_cross_module_tests to be +# built; if none of these are built (i.e. because TEST_OVERRIDE is used and +# doesn't include them) the second module doesn't get built. +set(PYBIND11_CROSS_MODULE_TESTS + test_exceptions.py + test_local_bindings.py + test_stl.py + test_stl_binders.py +) + +# Check if Eigen is available; if not, remove from PYBIND11_TEST_FILES (but +# keep it in PYBIND11_PYTEST_FILES, so that we get the "eigen is not installed" +# skip message). +list(FIND PYBIND11_TEST_FILES test_eigen.cpp PYBIND11_TEST_FILES_EIGEN_I) +if(PYBIND11_TEST_FILES_EIGEN_I GREATER -1) + # Try loading via newer Eigen's Eigen3Config first (bypassing tools/FindEigen3.cmake). + # Eigen 3.3.1+ exports a cmake 3.0+ target for handling dependency requirements, but also + # produces a fatal error if loaded from a pre-3.0 cmake. + if (NOT CMAKE_VERSION VERSION_LESS 3.0) + find_package(Eigen3 3.2.7 QUIET CONFIG) + if (EIGEN3_FOUND) + if (EIGEN3_VERSION_STRING AND NOT EIGEN3_VERSION_STRING VERSION_LESS 3.3.1) + set(PYBIND11_EIGEN_VIA_TARGET 1) + endif() + endif() + endif() + if (NOT EIGEN3_FOUND) + # Couldn't load via target, so fall back to allowing module mode finding, which will pick up + # tools/FindEigen3.cmake + find_package(Eigen3 3.2.7 QUIET) + endif() + + if(EIGEN3_FOUND) + # Eigen 3.3.1+ cmake sets EIGEN3_VERSION_STRING (and hard codes the version when installed + # rather than looking it up in the cmake script); older versions, and the + # tools/FindEigen3.cmake, set EIGEN3_VERSION instead. + if(NOT EIGEN3_VERSION AND EIGEN3_VERSION_STRING) + set(EIGEN3_VERSION ${EIGEN3_VERSION_STRING}) + endif() + message(STATUS "Building tests with Eigen v${EIGEN3_VERSION}") + else() + list(REMOVE_AT PYBIND11_TEST_FILES ${PYBIND11_TEST_FILES_EIGEN_I}) + message(STATUS "Building tests WITHOUT Eigen") + endif() +endif() + +# Optional dependency for some tests (boost::variant is only supported with version >= 1.56) +find_package(Boost 1.56) + +# Compile with compiler warnings turned on +function(pybind11_enable_warnings target_name) + if(MSVC) + target_compile_options(${target_name} PRIVATE /W4) + elseif(CMAKE_CXX_COMPILER_ID MATCHES "(GNU|Intel|Clang)") + target_compile_options(${target_name} PRIVATE -Wall -Wextra -Wconversion -Wcast-qual -Wdeprecated) + endif() + + if(PYBIND11_WERROR) + if(MSVC) + target_compile_options(${target_name} PRIVATE /WX) + elseif(CMAKE_CXX_COMPILER_ID MATCHES "(GNU|Intel|Clang)") + target_compile_options(${target_name} PRIVATE -Werror) + endif() + endif() +endfunction() + +set(test_targets pybind11_tests) + +# Build pybind11_cross_module_tests if any test_whatever.py are being built that require it +foreach(t ${PYBIND11_CROSS_MODULE_TESTS}) + list(FIND PYBIND11_PYTEST_FILES ${t} i) + if (i GREATER -1) + list(APPEND test_targets pybind11_cross_module_tests) + break() + endif() +endforeach() + +set(testdir ${CMAKE_CURRENT_SOURCE_DIR}) +foreach(target ${test_targets}) + set(test_files ${PYBIND11_TEST_FILES}) + if(NOT target STREQUAL "pybind11_tests") + set(test_files "") + endif() + + # Create the binding library + pybind11_add_module(${target} THIN_LTO ${target}.cpp ${test_files} ${PYBIND11_HEADERS}) + pybind11_enable_warnings(${target}) + + if(MSVC) + target_compile_options(${target} PRIVATE /utf-8) + endif() + + if(EIGEN3_FOUND) + if (PYBIND11_EIGEN_VIA_TARGET) + target_link_libraries(${target} PRIVATE Eigen3::Eigen) + else() + target_include_directories(${target} PRIVATE ${EIGEN3_INCLUDE_DIR}) + endif() + target_compile_definitions(${target} PRIVATE -DPYBIND11_TEST_EIGEN) + endif() + + if(Boost_FOUND) + target_include_directories(${target} PRIVATE ${Boost_INCLUDE_DIRS}) + target_compile_definitions(${target} PRIVATE -DPYBIND11_TEST_BOOST) + endif() + + # Always write the output file directly into the 'tests' directory (even on MSVC) + if(NOT CMAKE_LIBRARY_OUTPUT_DIRECTORY) + set_target_properties(${target} PROPERTIES LIBRARY_OUTPUT_DIRECTORY ${testdir}) + foreach(config ${CMAKE_CONFIGURATION_TYPES}) + string(TOUPPER ${config} config) + set_target_properties(${target} PROPERTIES LIBRARY_OUTPUT_DIRECTORY_${config} ${testdir}) + endforeach() + endif() +endforeach() + +# Make sure pytest is found or produce a fatal error +if(NOT PYBIND11_PYTEST_FOUND) + execute_process(COMMAND ${PYTHON_EXECUTABLE} -c "import pytest; print(pytest.__version__)" + RESULT_VARIABLE pytest_not_found OUTPUT_VARIABLE pytest_version ERROR_QUIET) + if(pytest_not_found) + message(FATAL_ERROR "Running the tests requires pytest. Please install it manually" + " (try: ${PYTHON_EXECUTABLE} -m pip install pytest)") + elseif(pytest_version VERSION_LESS 3.0) + message(FATAL_ERROR "Running the tests requires pytest >= 3.0. Found: ${pytest_version}" + "Please update it (try: ${PYTHON_EXECUTABLE} -m pip install -U pytest)") + endif() + set(PYBIND11_PYTEST_FOUND TRUE CACHE INTERNAL "") +endif() + +if(CMAKE_VERSION VERSION_LESS 3.2) + set(PYBIND11_USES_TERMINAL "") +else() + set(PYBIND11_USES_TERMINAL "USES_TERMINAL") +endif() + +# A single command to compile and run the tests +add_custom_target(pytest COMMAND ${PYTHON_EXECUTABLE} -m pytest ${PYBIND11_PYTEST_FILES} + DEPENDS ${test_targets} WORKING_DIRECTORY ${testdir} ${PYBIND11_USES_TERMINAL}) + +if(PYBIND11_TEST_OVERRIDE) + add_custom_command(TARGET pytest POST_BUILD + COMMAND ${CMAKE_COMMAND} -E echo "Note: not all tests run: -DPYBIND11_TEST_OVERRIDE is in effect") +endif() + +# Add a check target to run all the tests, starting with pytest (we add dependencies to this below) +add_custom_target(check DEPENDS pytest) + +# The remaining tests only apply when being built as part of the pybind11 project, but not if the +# tests are being built independently. +if (NOT PROJECT_NAME STREQUAL "pybind11") + return() +endif() + +# Add a post-build comment to show the primary test suite .so size and, if a previous size, compare it: +add_custom_command(TARGET pybind11_tests POST_BUILD + COMMAND ${PYTHON_EXECUTABLE} ${PROJECT_SOURCE_DIR}/tools/libsize.py + $ ${CMAKE_CURRENT_BINARY_DIR}/sosize-$.txt) + +# Test embedding the interpreter. Provides the `cpptest` target. +add_subdirectory(test_embed) + +# Test CMake build using functions and targets from subdirectory or installed location +add_subdirectory(test_cmake_build) diff --git a/wrap/python/pybind11/tests/conftest.py b/wrap/python/pybind11/tests/conftest.py new file mode 100644 index 000000000..55d9d0d53 --- /dev/null +++ b/wrap/python/pybind11/tests/conftest.py @@ -0,0 +1,239 @@ +"""pytest configuration + +Extends output capture as needed by pybind11: ignore constructors, optional unordered lines. +Adds docstring and exceptions message sanitizers: ignore Python 2 vs 3 differences. +""" + +import pytest +import textwrap +import difflib +import re +import sys +import contextlib +import platform +import gc + +_unicode_marker = re.compile(r'u(\'[^\']*\')') +_long_marker = re.compile(r'([0-9])L') +_hexadecimal = re.compile(r'0x[0-9a-fA-F]+') + + +def _strip_and_dedent(s): + """For triple-quote strings""" + return textwrap.dedent(s.lstrip('\n').rstrip()) + + +def _split_and_sort(s): + """For output which does not require specific line order""" + return sorted(_strip_and_dedent(s).splitlines()) + + +def _make_explanation(a, b): + """Explanation for a failed assert -- the a and b arguments are List[str]""" + return ["--- actual / +++ expected"] + [line.strip('\n') for line in difflib.ndiff(a, b)] + + +class Output(object): + """Basic output post-processing and comparison""" + def __init__(self, string): + self.string = string + self.explanation = [] + + def __str__(self): + return self.string + + def __eq__(self, other): + # Ignore constructor/destructor output which is prefixed with "###" + a = [line for line in self.string.strip().splitlines() if not line.startswith("###")] + b = _strip_and_dedent(other).splitlines() + if a == b: + return True + else: + self.explanation = _make_explanation(a, b) + return False + + +class Unordered(Output): + """Custom comparison for output without strict line ordering""" + def __eq__(self, other): + a = _split_and_sort(self.string) + b = _split_and_sort(other) + if a == b: + return True + else: + self.explanation = _make_explanation(a, b) + return False + + +class Capture(object): + def __init__(self, capfd): + self.capfd = capfd + self.out = "" + self.err = "" + + def __enter__(self): + self.capfd.readouterr() + return self + + def __exit__(self, *args): + self.out, self.err = self.capfd.readouterr() + + def __eq__(self, other): + a = Output(self.out) + b = other + if a == b: + return True + else: + self.explanation = a.explanation + return False + + def __str__(self): + return self.out + + def __contains__(self, item): + return item in self.out + + @property + def unordered(self): + return Unordered(self.out) + + @property + def stderr(self): + return Output(self.err) + + +@pytest.fixture +def capture(capsys): + """Extended `capsys` with context manager and custom equality operators""" + return Capture(capsys) + + +class SanitizedString(object): + def __init__(self, sanitizer): + self.sanitizer = sanitizer + self.string = "" + self.explanation = [] + + def __call__(self, thing): + self.string = self.sanitizer(thing) + return self + + def __eq__(self, other): + a = self.string + b = _strip_and_dedent(other) + if a == b: + return True + else: + self.explanation = _make_explanation(a.splitlines(), b.splitlines()) + return False + + +def _sanitize_general(s): + s = s.strip() + s = s.replace("pybind11_tests.", "m.") + s = s.replace("unicode", "str") + s = _long_marker.sub(r"\1", s) + s = _unicode_marker.sub(r"\1", s) + return s + + +def _sanitize_docstring(thing): + s = thing.__doc__ + s = _sanitize_general(s) + return s + + +@pytest.fixture +def doc(): + """Sanitize docstrings and add custom failure explanation""" + return SanitizedString(_sanitize_docstring) + + +def _sanitize_message(thing): + s = str(thing) + s = _sanitize_general(s) + s = _hexadecimal.sub("0", s) + return s + + +@pytest.fixture +def msg(): + """Sanitize messages and add custom failure explanation""" + return SanitizedString(_sanitize_message) + + +# noinspection PyUnusedLocal +def pytest_assertrepr_compare(op, left, right): + """Hook to insert custom failure explanation""" + if hasattr(left, 'explanation'): + return left.explanation + + +@contextlib.contextmanager +def suppress(exception): + """Suppress the desired exception""" + try: + yield + except exception: + pass + + +def gc_collect(): + ''' Run the garbage collector twice (needed when running + reference counting tests with PyPy) ''' + gc.collect() + gc.collect() + + +def pytest_configure(): + """Add import suppression and test requirements to `pytest` namespace""" + try: + import numpy as np + except ImportError: + np = None + try: + import scipy + except ImportError: + scipy = None + try: + from pybind11_tests.eigen import have_eigen + except ImportError: + have_eigen = False + pypy = platform.python_implementation() == "PyPy" + + skipif = pytest.mark.skipif + pytest.suppress = suppress + pytest.requires_numpy = skipif(not np, reason="numpy is not installed") + pytest.requires_scipy = skipif(not np, reason="scipy is not installed") + pytest.requires_eigen_and_numpy = skipif(not have_eigen or not np, + reason="eigen and/or numpy are not installed") + pytest.requires_eigen_and_scipy = skipif( + not have_eigen or not scipy, reason="eigen and/or scipy are not installed") + pytest.unsupported_on_pypy = skipif(pypy, reason="unsupported on PyPy") + pytest.unsupported_on_py2 = skipif(sys.version_info.major < 3, + reason="unsupported on Python 2.x") + pytest.gc_collect = gc_collect + + +def _test_import_pybind11(): + """Early diagnostic for test module initialization errors + + When there is an error during initialization, the first import will report the + real error while all subsequent imports will report nonsense. This import test + is done early (in the pytest configuration file, before any tests) in order to + avoid the noise of having all tests fail with identical error messages. + + Any possible exception is caught here and reported manually *without* the stack + trace. This further reduces noise since the trace would only show pytest internals + which are not useful for debugging pybind11 module issues. + """ + # noinspection PyBroadException + try: + import pybind11_tests # noqa: F401 imported but unused + except Exception as e: + print("Failed to import pybind11_tests from pytest:") + print(" {}: {}".format(type(e).__name__, e)) + sys.exit(1) + + +_test_import_pybind11() diff --git a/wrap/python/pybind11/tests/constructor_stats.h b/wrap/python/pybind11/tests/constructor_stats.h new file mode 100644 index 000000000..f026e70f9 --- /dev/null +++ b/wrap/python/pybind11/tests/constructor_stats.h @@ -0,0 +1,276 @@ +#pragma once +/* + tests/constructor_stats.h -- framework for printing and tracking object + instance lifetimes in example/test code. + + Copyright (c) 2016 Jason Rhinelander + + All rights reserved. Use of this source code is governed by a + BSD-style license that can be found in the LICENSE file. + +This header provides a few useful tools for writing examples or tests that want to check and/or +display object instance lifetimes. It requires that you include this header and add the following +function calls to constructors: + + class MyClass { + MyClass() { ...; print_default_created(this); } + ~MyClass() { ...; print_destroyed(this); } + MyClass(const MyClass &c) { ...; print_copy_created(this); } + MyClass(MyClass &&c) { ...; print_move_created(this); } + MyClass(int a, int b) { ...; print_created(this, a, b); } + MyClass &operator=(const MyClass &c) { ...; print_copy_assigned(this); } + MyClass &operator=(MyClass &&c) { ...; print_move_assigned(this); } + + ... + } + +You can find various examples of these in several of the existing testing .cpp files. (Of course +you don't need to add any of the above constructors/operators that you don't actually have, except +for the destructor). + +Each of these will print an appropriate message such as: + + ### MyClass @ 0x2801910 created via default constructor + ### MyClass @ 0x27fa780 created 100 200 + ### MyClass @ 0x2801910 destroyed + ### MyClass @ 0x27fa780 destroyed + +You can also include extra arguments (such as the 100, 200 in the output above, coming from the +value constructor) for all of the above methods which will be included in the output. + +For testing, each of these also keeps track the created instances and allows you to check how many +of the various constructors have been invoked from the Python side via code such as: + + from pybind11_tests import ConstructorStats + cstats = ConstructorStats.get(MyClass) + print(cstats.alive()) + print(cstats.default_constructions) + +Note that `.alive()` should usually be the first thing you call as it invokes Python's garbage +collector to actually destroy objects that aren't yet referenced. + +For everything except copy and move constructors and destructors, any extra values given to the +print_...() function is stored in a class-specific values list which you can retrieve and inspect +from the ConstructorStats instance `.values()` method. + +In some cases, when you need to track instances of a C++ class not registered with pybind11, you +need to add a function returning the ConstructorStats for the C++ class; this can be done with: + + m.def("get_special_cstats", &ConstructorStats::get, py::return_value_policy::reference) + +Finally, you can suppress the output messages, but keep the constructor tracking (for +inspection/testing in python) by using the functions with `print_` replaced with `track_` (e.g. +`track_copy_created(this)`). + +*/ + +#include "pybind11_tests.h" +#include +#include +#include +#include + +class ConstructorStats { +protected: + std::unordered_map _instances; // Need a map rather than set because members can shared address with parents + std::list _values; // Used to track values (e.g. of value constructors) +public: + int default_constructions = 0; + int copy_constructions = 0; + int move_constructions = 0; + int copy_assignments = 0; + int move_assignments = 0; + + void copy_created(void *inst) { + created(inst); + copy_constructions++; + } + + void move_created(void *inst) { + created(inst); + move_constructions++; + } + + void default_created(void *inst) { + created(inst); + default_constructions++; + } + + void created(void *inst) { + ++_instances[inst]; + } + + void destroyed(void *inst) { + if (--_instances[inst] < 0) + throw std::runtime_error("cstats.destroyed() called with unknown " + "instance; potential double-destruction " + "or a missing cstats.created()"); + } + + static void gc() { + // Force garbage collection to ensure any pending destructors are invoked: +#if defined(PYPY_VERSION) + PyObject *globals = PyEval_GetGlobals(); + PyObject *result = PyRun_String( + "import gc\n" + "for i in range(2):" + " gc.collect()\n", + Py_file_input, globals, globals); + if (result == nullptr) + throw py::error_already_set(); + Py_DECREF(result); +#else + py::module::import("gc").attr("collect")(); +#endif + } + + int alive() { + gc(); + int total = 0; + for (const auto &p : _instances) + if (p.second > 0) + total += p.second; + return total; + } + + void value() {} // Recursion terminator + // Takes one or more values, converts them to strings, then stores them. + template void value(const T &v, Tmore &&...args) { + std::ostringstream oss; + oss << v; + _values.push_back(oss.str()); + value(std::forward(args)...); + } + + // Move out stored values + py::list values() { + py::list l; + for (const auto &v : _values) l.append(py::cast(v)); + _values.clear(); + return l; + } + + // Gets constructor stats from a C++ type index + static ConstructorStats& get(std::type_index type) { + static std::unordered_map all_cstats; + return all_cstats[type]; + } + + // Gets constructor stats from a C++ type + template static ConstructorStats& get() { +#if defined(PYPY_VERSION) + gc(); +#endif + return get(typeid(T)); + } + + // Gets constructor stats from a Python class + static ConstructorStats& get(py::object class_) { + auto &internals = py::detail::get_internals(); + const std::type_index *t1 = nullptr, *t2 = nullptr; + try { + auto *type_info = internals.registered_types_py.at((PyTypeObject *) class_.ptr()).at(0); + for (auto &p : internals.registered_types_cpp) { + if (p.second == type_info) { + if (t1) { + t2 = &p.first; + break; + } + t1 = &p.first; + } + } + } + catch (const std::out_of_range &) {} + if (!t1) throw std::runtime_error("Unknown class passed to ConstructorStats::get()"); + auto &cs1 = get(*t1); + // If we have both a t1 and t2 match, one is probably the trampoline class; return whichever + // has more constructions (typically one or the other will be 0) + if (t2) { + auto &cs2 = get(*t2); + int cs1_total = cs1.default_constructions + cs1.copy_constructions + cs1.move_constructions + (int) cs1._values.size(); + int cs2_total = cs2.default_constructions + cs2.copy_constructions + cs2.move_constructions + (int) cs2._values.size(); + if (cs2_total > cs1_total) return cs2; + } + return cs1; + } +}; + +// To track construction/destruction, you need to call these methods from the various +// constructors/operators. The ones that take extra values record the given values in the +// constructor stats values for later inspection. +template void track_copy_created(T *inst) { ConstructorStats::get().copy_created(inst); } +template void track_move_created(T *inst) { ConstructorStats::get().move_created(inst); } +template void track_copy_assigned(T *, Values &&...values) { + auto &cst = ConstructorStats::get(); + cst.copy_assignments++; + cst.value(std::forward(values)...); +} +template void track_move_assigned(T *, Values &&...values) { + auto &cst = ConstructorStats::get(); + cst.move_assignments++; + cst.value(std::forward(values)...); +} +template void track_default_created(T *inst, Values &&...values) { + auto &cst = ConstructorStats::get(); + cst.default_created(inst); + cst.value(std::forward(values)...); +} +template void track_created(T *inst, Values &&...values) { + auto &cst = ConstructorStats::get(); + cst.created(inst); + cst.value(std::forward(values)...); +} +template void track_destroyed(T *inst) { + ConstructorStats::get().destroyed(inst); +} +template void track_values(T *, Values &&...values) { + ConstructorStats::get().value(std::forward(values)...); +} + +/// Don't cast pointers to Python, print them as strings +inline const char *format_ptrs(const char *p) { return p; } +template +py::str format_ptrs(T *p) { return "{:#x}"_s.format(reinterpret_cast(p)); } +template +auto format_ptrs(T &&x) -> decltype(std::forward(x)) { return std::forward(x); } + +template +void print_constr_details(T *inst, const std::string &action, Output &&...output) { + py::print("###", py::type_id(), "@", format_ptrs(inst), action, + format_ptrs(std::forward(output))...); +} + +// Verbose versions of the above: +template void print_copy_created(T *inst, Values &&...values) { // NB: this prints, but doesn't store, given values + print_constr_details(inst, "created via copy constructor", values...); + track_copy_created(inst); +} +template void print_move_created(T *inst, Values &&...values) { // NB: this prints, but doesn't store, given values + print_constr_details(inst, "created via move constructor", values...); + track_move_created(inst); +} +template void print_copy_assigned(T *inst, Values &&...values) { + print_constr_details(inst, "assigned via copy assignment", values...); + track_copy_assigned(inst, values...); +} +template void print_move_assigned(T *inst, Values &&...values) { + print_constr_details(inst, "assigned via move assignment", values...); + track_move_assigned(inst, values...); +} +template void print_default_created(T *inst, Values &&...values) { + print_constr_details(inst, "created via default constructor", values...); + track_default_created(inst, values...); +} +template void print_created(T *inst, Values &&...values) { + print_constr_details(inst, "created", values...); + track_created(inst, values...); +} +template void print_destroyed(T *inst, Values &&...values) { // Prints but doesn't store given values + print_constr_details(inst, "destroyed", values...); + track_destroyed(inst); +} +template void print_values(T *inst, Values &&...values) { + print_constr_details(inst, ":", values...); + track_values(inst, values...); +} + diff --git a/wrap/python/pybind11/tests/local_bindings.h b/wrap/python/pybind11/tests/local_bindings.h new file mode 100644 index 000000000..b6afb8086 --- /dev/null +++ b/wrap/python/pybind11/tests/local_bindings.h @@ -0,0 +1,64 @@ +#pragma once +#include "pybind11_tests.h" + +/// Simple class used to test py::local: +template class LocalBase { +public: + LocalBase(int i) : i(i) { } + int i = -1; +}; + +/// Registered with py::module_local in both main and secondary modules: +using LocalType = LocalBase<0>; +/// Registered without py::module_local in both modules: +using NonLocalType = LocalBase<1>; +/// A second non-local type (for stl_bind tests): +using NonLocal2 = LocalBase<2>; +/// Tests within-module, different-compilation-unit local definition conflict: +using LocalExternal = LocalBase<3>; +/// Mixed: registered local first, then global +using MixedLocalGlobal = LocalBase<4>; +/// Mixed: global first, then local +using MixedGlobalLocal = LocalBase<5>; + +/// Registered with py::module_local only in the secondary module: +using ExternalType1 = LocalBase<6>; +using ExternalType2 = LocalBase<7>; + +using LocalVec = std::vector; +using LocalVec2 = std::vector; +using LocalMap = std::unordered_map; +using NonLocalVec = std::vector; +using NonLocalVec2 = std::vector; +using NonLocalMap = std::unordered_map; +using NonLocalMap2 = std::unordered_map; + +PYBIND11_MAKE_OPAQUE(LocalVec); +PYBIND11_MAKE_OPAQUE(LocalVec2); +PYBIND11_MAKE_OPAQUE(LocalMap); +PYBIND11_MAKE_OPAQUE(NonLocalVec); +//PYBIND11_MAKE_OPAQUE(NonLocalVec2); // same type as LocalVec2 +PYBIND11_MAKE_OPAQUE(NonLocalMap); +PYBIND11_MAKE_OPAQUE(NonLocalMap2); + + +// Simple bindings (used with the above): +template +py::class_ bind_local(Args && ...args) { + return py::class_(std::forward(args)...) + .def(py::init()) + .def("get", [](T &i) { return i.i + Adjust; }); +}; + +// Simulate a foreign library base class (to match the example in the docs): +namespace pets { +class Pet { +public: + Pet(std::string name) : name_(name) {} + std::string name_; + const std::string &name() { return name_; } +}; +} + +struct MixGL { int i; MixGL(int i) : i{i} {} }; +struct MixGL2 { int i; MixGL2(int i) : i{i} {} }; diff --git a/wrap/python/pybind11/tests/object.h b/wrap/python/pybind11/tests/object.h new file mode 100644 index 000000000..9235f19c2 --- /dev/null +++ b/wrap/python/pybind11/tests/object.h @@ -0,0 +1,175 @@ +#if !defined(__OBJECT_H) +#define __OBJECT_H + +#include +#include "constructor_stats.h" + +/// Reference counted object base class +class Object { +public: + /// Default constructor + Object() { print_default_created(this); } + + /// Copy constructor + Object(const Object &) : m_refCount(0) { print_copy_created(this); } + + /// Return the current reference count + int getRefCount() const { return m_refCount; }; + + /// Increase the object's reference count by one + void incRef() const { ++m_refCount; } + + /** \brief Decrease the reference count of + * the object and possibly deallocate it. + * + * The object will automatically be deallocated once + * the reference count reaches zero. + */ + void decRef(bool dealloc = true) const { + --m_refCount; + if (m_refCount == 0 && dealloc) + delete this; + else if (m_refCount < 0) + throw std::runtime_error("Internal error: reference count < 0!"); + } + + virtual std::string toString() const = 0; +protected: + /** \brief Virtual protected deconstructor. + * (Will only be called by \ref ref) + */ + virtual ~Object() { print_destroyed(this); } +private: + mutable std::atomic m_refCount { 0 }; +}; + +// Tag class used to track constructions of ref objects. When we track constructors, below, we +// track and print out the actual class (e.g. ref), and *also* add a fake tracker for +// ref_tag. This lets us check that the total number of ref constructors/destructors is +// correct without having to check each individual ref type individually. +class ref_tag {}; + +/** + * \brief Reference counting helper + * + * The \a ref refeference template is a simple wrapper to store a + * pointer to an object. It takes care of increasing and decreasing + * the reference count of the object. When the last reference goes + * out of scope, the associated object will be deallocated. + * + * \ingroup libcore + */ +template class ref { +public: + /// Create a nullptr reference + ref() : m_ptr(nullptr) { print_default_created(this); track_default_created((ref_tag*) this); } + + /// Construct a reference from a pointer + ref(T *ptr) : m_ptr(ptr) { + if (m_ptr) ((Object *) m_ptr)->incRef(); + + print_created(this, "from pointer", m_ptr); track_created((ref_tag*) this, "from pointer"); + + } + + /// Copy constructor + ref(const ref &r) : m_ptr(r.m_ptr) { + if (m_ptr) + ((Object *) m_ptr)->incRef(); + + print_copy_created(this, "with pointer", m_ptr); track_copy_created((ref_tag*) this); + } + + /// Move constructor + ref(ref &&r) : m_ptr(r.m_ptr) { + r.m_ptr = nullptr; + + print_move_created(this, "with pointer", m_ptr); track_move_created((ref_tag*) this); + } + + /// Destroy this reference + ~ref() { + if (m_ptr) + ((Object *) m_ptr)->decRef(); + + print_destroyed(this); track_destroyed((ref_tag*) this); + } + + /// Move another reference into the current one + ref& operator=(ref&& r) { + print_move_assigned(this, "pointer", r.m_ptr); track_move_assigned((ref_tag*) this); + + if (*this == r) + return *this; + if (m_ptr) + ((Object *) m_ptr)->decRef(); + m_ptr = r.m_ptr; + r.m_ptr = nullptr; + return *this; + } + + /// Overwrite this reference with another reference + ref& operator=(const ref& r) { + print_copy_assigned(this, "pointer", r.m_ptr); track_copy_assigned((ref_tag*) this); + + if (m_ptr == r.m_ptr) + return *this; + if (m_ptr) + ((Object *) m_ptr)->decRef(); + m_ptr = r.m_ptr; + if (m_ptr) + ((Object *) m_ptr)->incRef(); + return *this; + } + + /// Overwrite this reference with a pointer to another object + ref& operator=(T *ptr) { + print_values(this, "assigned pointer"); track_values((ref_tag*) this, "assigned pointer"); + + if (m_ptr == ptr) + return *this; + if (m_ptr) + ((Object *) m_ptr)->decRef(); + m_ptr = ptr; + if (m_ptr) + ((Object *) m_ptr)->incRef(); + return *this; + } + + /// Compare this reference with another reference + bool operator==(const ref &r) const { return m_ptr == r.m_ptr; } + + /// Compare this reference with another reference + bool operator!=(const ref &r) const { return m_ptr != r.m_ptr; } + + /// Compare this reference with a pointer + bool operator==(const T* ptr) const { return m_ptr == ptr; } + + /// Compare this reference with a pointer + bool operator!=(const T* ptr) const { return m_ptr != ptr; } + + /// Access the object referenced by this reference + T* operator->() { return m_ptr; } + + /// Access the object referenced by this reference + const T* operator->() const { return m_ptr; } + + /// Return a C++ reference to the referenced object + T& operator*() { return *m_ptr; } + + /// Return a const C++ reference to the referenced object + const T& operator*() const { return *m_ptr; } + + /// Return a pointer to the referenced object + operator T* () { return m_ptr; } + + /// Return a const pointer to the referenced object + T* get_ptr() { return m_ptr; } + + /// Return a pointer to the referenced object + const T* get_ptr() const { return m_ptr; } +private: + T *m_ptr; +}; + +#endif /* __OBJECT_H */ diff --git a/wrap/python/pybind11/tests/pybind11_cross_module_tests.cpp b/wrap/python/pybind11/tests/pybind11_cross_module_tests.cpp new file mode 100644 index 000000000..f705e3106 --- /dev/null +++ b/wrap/python/pybind11/tests/pybind11_cross_module_tests.cpp @@ -0,0 +1,123 @@ +/* + tests/pybind11_cross_module_tests.cpp -- contains tests that require multiple modules + + Copyright (c) 2017 Jason Rhinelander + + All rights reserved. Use of this source code is governed by a + BSD-style license that can be found in the LICENSE file. +*/ + +#include "pybind11_tests.h" +#include "local_bindings.h" +#include +#include + +PYBIND11_MODULE(pybind11_cross_module_tests, m) { + m.doc() = "pybind11 cross-module test module"; + + // test_local_bindings.py tests: + // + // Definitions here are tested by importing both this module and the + // relevant pybind11_tests submodule from a test_whatever.py + + // test_load_external + bind_local(m, "ExternalType1", py::module_local()); + bind_local(m, "ExternalType2", py::module_local()); + + // test_exceptions.py + m.def("raise_runtime_error", []() { PyErr_SetString(PyExc_RuntimeError, "My runtime error"); throw py::error_already_set(); }); + m.def("raise_value_error", []() { PyErr_SetString(PyExc_ValueError, "My value error"); throw py::error_already_set(); }); + m.def("throw_pybind_value_error", []() { throw py::value_error("pybind11 value error"); }); + m.def("throw_pybind_type_error", []() { throw py::type_error("pybind11 type error"); }); + m.def("throw_stop_iteration", []() { throw py::stop_iteration(); }); + + // test_local_bindings.py + // Local to both: + bind_local(m, "LocalType", py::module_local()) + .def("get2", [](LocalType &t) { return t.i + 2; }) + ; + + // Can only be called with our python type: + m.def("local_value", [](LocalType &l) { return l.i; }); + + // test_nonlocal_failure + // This registration will fail (global registration when LocalFail is already registered + // globally in the main test module): + m.def("register_nonlocal", [m]() { + bind_local(m, "NonLocalType"); + }); + + // test_stl_bind_local + // stl_bind.h binders defaults to py::module_local if the types are local or converting: + py::bind_vector(m, "LocalVec"); + py::bind_map(m, "LocalMap"); + + // test_stl_bind_global + // and global if the type (or one of the types, for the map) is global (so these will fail, + // assuming pybind11_tests is already loaded): + m.def("register_nonlocal_vec", [m]() { + py::bind_vector(m, "NonLocalVec"); + }); + m.def("register_nonlocal_map", [m]() { + py::bind_map(m, "NonLocalMap"); + }); + // The default can, however, be overridden to global using `py::module_local()` or + // `py::module_local(false)`. + // Explicitly made local: + py::bind_vector(m, "NonLocalVec2", py::module_local()); + // Explicitly made global (and so will fail to bind): + m.def("register_nonlocal_map2", [m]() { + py::bind_map(m, "NonLocalMap2", py::module_local(false)); + }); + + // test_mixed_local_global + // We try this both with the global type registered first and vice versa (the order shouldn't + // matter). + m.def("register_mixed_global_local", [m]() { + bind_local(m, "MixedGlobalLocal", py::module_local()); + }); + m.def("register_mixed_local_global", [m]() { + bind_local(m, "MixedLocalGlobal", py::module_local(false)); + }); + m.def("get_mixed_gl", [](int i) { return MixedGlobalLocal(i); }); + m.def("get_mixed_lg", [](int i) { return MixedLocalGlobal(i); }); + + // test_internal_locals_differ + m.def("local_cpp_types_addr", []() { return (uintptr_t) &py::detail::registered_local_types_cpp(); }); + + // test_stl_caster_vs_stl_bind + py::bind_vector>(m, "VectorInt"); + + m.def("load_vector_via_binding", [](std::vector &v) { + return std::accumulate(v.begin(), v.end(), 0); + }); + + // test_cross_module_calls + m.def("return_self", [](LocalVec *v) { return v; }); + m.def("return_copy", [](const LocalVec &v) { return LocalVec(v); }); + + class Dog : public pets::Pet { public: Dog(std::string name) : Pet(name) {}; }; + py::class_(m, "Pet", py::module_local()) + .def("name", &pets::Pet::name); + // Binding for local extending class: + py::class_(m, "Dog") + .def(py::init()); + m.def("pet_name", [](pets::Pet &p) { return p.name(); }); + + py::class_(m, "MixGL", py::module_local()).def(py::init()); + m.def("get_gl_value", [](MixGL &o) { return o.i + 100; }); + + py::class_(m, "MixGL2", py::module_local()).def(py::init()); + + // test_vector_bool + // We can't test both stl.h and stl_bind.h conversions of `std::vector` within + // the same module (it would be an ODR violation). Therefore `bind_vector` of `bool` + // is defined here and tested in `test_stl_binders.py`. + py::bind_vector>(m, "VectorBool"); + + // test_missing_header_message + // The main module already includes stl.h, but we need to test the error message + // which appears when this header is missing. + m.def("missing_header_arg", [](std::vector) { }); + m.def("missing_header_return", []() { return std::vector(); }); +} diff --git a/wrap/python/pybind11/tests/pybind11_tests.cpp b/wrap/python/pybind11/tests/pybind11_tests.cpp new file mode 100644 index 000000000..bc7d2c3e7 --- /dev/null +++ b/wrap/python/pybind11/tests/pybind11_tests.cpp @@ -0,0 +1,93 @@ +/* + tests/pybind11_tests.cpp -- pybind example plugin + + Copyright (c) 2016 Wenzel Jakob + + All rights reserved. Use of this source code is governed by a + BSD-style license that can be found in the LICENSE file. +*/ + +#include "pybind11_tests.h" +#include "constructor_stats.h" + +#include +#include + +/* +For testing purposes, we define a static global variable here in a function that each individual +test .cpp calls with its initialization lambda. It's convenient here because we can just not +compile some test files to disable/ignore some of the test code. + +It is NOT recommended as a way to use pybind11 in practice, however: the initialization order will +be essentially random, which is okay for our test scripts (there are no dependencies between the +individual pybind11 test .cpp files), but most likely not what you want when using pybind11 +productively. + +Instead, see the "How can I reduce the build time?" question in the "Frequently asked questions" +section of the documentation for good practice on splitting binding code over multiple files. +*/ +std::list> &initializers() { + static std::list> inits; + return inits; +} + +test_initializer::test_initializer(Initializer init) { + initializers().push_back(init); +} + +test_initializer::test_initializer(const char *submodule_name, Initializer init) { + initializers().push_back([=](py::module &parent) { + auto m = parent.def_submodule(submodule_name); + init(m); + }); +} + +void bind_ConstructorStats(py::module &m) { + py::class_(m, "ConstructorStats") + .def("alive", &ConstructorStats::alive) + .def("values", &ConstructorStats::values) + .def_readwrite("default_constructions", &ConstructorStats::default_constructions) + .def_readwrite("copy_assignments", &ConstructorStats::copy_assignments) + .def_readwrite("move_assignments", &ConstructorStats::move_assignments) + .def_readwrite("copy_constructions", &ConstructorStats::copy_constructions) + .def_readwrite("move_constructions", &ConstructorStats::move_constructions) + .def_static("get", (ConstructorStats &(*)(py::object)) &ConstructorStats::get, py::return_value_policy::reference_internal) + + // Not exactly ConstructorStats, but related: expose the internal pybind number of registered instances + // to allow instance cleanup checks (invokes a GC first) + .def_static("detail_reg_inst", []() { + ConstructorStats::gc(); + return py::detail::get_internals().registered_instances.size(); + }) + ; +} + +PYBIND11_MODULE(pybind11_tests, m) { + m.doc() = "pybind11 test module"; + + bind_ConstructorStats(m); + +#if !defined(NDEBUG) + m.attr("debug_enabled") = true; +#else + m.attr("debug_enabled") = false; +#endif + + py::class_(m, "UserType", "A `py::class_` type for testing") + .def(py::init<>()) + .def(py::init()) + .def("get_value", &UserType::value, "Get value using a method") + .def("set_value", &UserType::set, "Set value using a method") + .def_property("value", &UserType::value, &UserType::set, "Get/set value using a property") + .def("__repr__", [](const UserType& u) { return "UserType({})"_s.format(u.value()); }); + + py::class_(m, "IncType") + .def(py::init<>()) + .def(py::init()) + .def("__repr__", [](const IncType& u) { return "IncType({})"_s.format(u.value()); }); + + for (const auto &initializer : initializers()) + initializer(m); + + if (!py::hasattr(m, "have_eigen")) m.attr("have_eigen") = false; +} diff --git a/wrap/python/pybind11/tests/pybind11_tests.h b/wrap/python/pybind11/tests/pybind11_tests.h new file mode 100644 index 000000000..90963a5de --- /dev/null +++ b/wrap/python/pybind11/tests/pybind11_tests.h @@ -0,0 +1,65 @@ +#pragma once +#include + +#if defined(_MSC_VER) && _MSC_VER < 1910 +// We get some really long type names here which causes MSVC 2015 to emit warnings +# pragma warning(disable: 4503) // warning C4503: decorated name length exceeded, name was truncated +#endif + +namespace py = pybind11; +using namespace pybind11::literals; + +class test_initializer { + using Initializer = void (*)(py::module &); + +public: + test_initializer(Initializer init); + test_initializer(const char *submodule_name, Initializer init); +}; + +#define TEST_SUBMODULE(name, variable) \ + void test_submodule_##name(py::module &); \ + test_initializer name(#name, test_submodule_##name); \ + void test_submodule_##name(py::module &variable) + + +/// Dummy type which is not exported anywhere -- something to trigger a conversion error +struct UnregisteredType { }; + +/// A user-defined type which is exported and can be used by any test +class UserType { +public: + UserType() = default; + UserType(int i) : i(i) { } + + int value() const { return i; } + void set(int set) { i = set; } + +private: + int i = -1; +}; + +/// Like UserType, but increments `value` on copy for quick reference vs. copy tests +class IncType : public UserType { +public: + using UserType::UserType; + IncType() = default; + IncType(const IncType &other) : IncType(other.value() + 1) { } + IncType(IncType &&) = delete; + IncType &operator=(const IncType &) = delete; + IncType &operator=(IncType &&) = delete; +}; + +/// Custom cast-only type that casts to a string "rvalue" or "lvalue" depending on the cast context. +/// Used to test recursive casters (e.g. std::tuple, stl containers). +struct RValueCaster {}; +NAMESPACE_BEGIN(pybind11) +NAMESPACE_BEGIN(detail) +template<> class type_caster { +public: + PYBIND11_TYPE_CASTER(RValueCaster, _("RValueCaster")); + static handle cast(RValueCaster &&, return_value_policy, handle) { return py::str("rvalue").release(); } + static handle cast(const RValueCaster &, return_value_policy, handle) { return py::str("lvalue").release(); } +}; +NAMESPACE_END(detail) +NAMESPACE_END(pybind11) diff --git a/wrap/python/pybind11/tests/pytest.ini b/wrap/python/pybind11/tests/pytest.ini new file mode 100644 index 000000000..f209964a4 --- /dev/null +++ b/wrap/python/pybind11/tests/pytest.ini @@ -0,0 +1,16 @@ +[pytest] +minversion = 3.0 +norecursedirs = test_cmake_build test_embed +addopts = + # show summary of skipped tests + -rs + # capture only Python print and C++ py::print, but not C output (low-level Python errors) + --capture=sys +filterwarnings = + # make warnings into errors but ignore certain third-party extension issues + error + # importing scipy submodules on some version of Python + ignore::ImportWarning + # bogus numpy ABI warning (see numpy/#432) + ignore:.*numpy.dtype size changed.*:RuntimeWarning + ignore:.*numpy.ufunc size changed.*:RuntimeWarning diff --git a/wrap/python/pybind11/tests/test_buffers.cpp b/wrap/python/pybind11/tests/test_buffers.cpp new file mode 100644 index 000000000..5199cf646 --- /dev/null +++ b/wrap/python/pybind11/tests/test_buffers.cpp @@ -0,0 +1,169 @@ +/* + tests/test_buffers.cpp -- supporting Pythons' buffer protocol + + Copyright (c) 2016 Wenzel Jakob + + All rights reserved. Use of this source code is governed by a + BSD-style license that can be found in the LICENSE file. +*/ + +#include "pybind11_tests.h" +#include "constructor_stats.h" + +TEST_SUBMODULE(buffers, m) { + // test_from_python / test_to_python: + class Matrix { + public: + Matrix(ssize_t rows, ssize_t cols) : m_rows(rows), m_cols(cols) { + print_created(this, std::to_string(m_rows) + "x" + std::to_string(m_cols) + " matrix"); + m_data = new float[(size_t) (rows*cols)]; + memset(m_data, 0, sizeof(float) * (size_t) (rows * cols)); + } + + Matrix(const Matrix &s) : m_rows(s.m_rows), m_cols(s.m_cols) { + print_copy_created(this, std::to_string(m_rows) + "x" + std::to_string(m_cols) + " matrix"); + m_data = new float[(size_t) (m_rows * m_cols)]; + memcpy(m_data, s.m_data, sizeof(float) * (size_t) (m_rows * m_cols)); + } + + Matrix(Matrix &&s) : m_rows(s.m_rows), m_cols(s.m_cols), m_data(s.m_data) { + print_move_created(this); + s.m_rows = 0; + s.m_cols = 0; + s.m_data = nullptr; + } + + ~Matrix() { + print_destroyed(this, std::to_string(m_rows) + "x" + std::to_string(m_cols) + " matrix"); + delete[] m_data; + } + + Matrix &operator=(const Matrix &s) { + print_copy_assigned(this, std::to_string(m_rows) + "x" + std::to_string(m_cols) + " matrix"); + delete[] m_data; + m_rows = s.m_rows; + m_cols = s.m_cols; + m_data = new float[(size_t) (m_rows * m_cols)]; + memcpy(m_data, s.m_data, sizeof(float) * (size_t) (m_rows * m_cols)); + return *this; + } + + Matrix &operator=(Matrix &&s) { + print_move_assigned(this, std::to_string(m_rows) + "x" + std::to_string(m_cols) + " matrix"); + if (&s != this) { + delete[] m_data; + m_rows = s.m_rows; m_cols = s.m_cols; m_data = s.m_data; + s.m_rows = 0; s.m_cols = 0; s.m_data = nullptr; + } + return *this; + } + + float operator()(ssize_t i, ssize_t j) const { + return m_data[(size_t) (i*m_cols + j)]; + } + + float &operator()(ssize_t i, ssize_t j) { + return m_data[(size_t) (i*m_cols + j)]; + } + + float *data() { return m_data; } + + ssize_t rows() const { return m_rows; } + ssize_t cols() const { return m_cols; } + private: + ssize_t m_rows; + ssize_t m_cols; + float *m_data; + }; + py::class_(m, "Matrix", py::buffer_protocol()) + .def(py::init()) + /// Construct from a buffer + .def(py::init([](py::buffer b) { + py::buffer_info info = b.request(); + if (info.format != py::format_descriptor::format() || info.ndim != 2) + throw std::runtime_error("Incompatible buffer format!"); + + auto v = new Matrix(info.shape[0], info.shape[1]); + memcpy(v->data(), info.ptr, sizeof(float) * (size_t) (v->rows() * v->cols())); + return v; + })) + + .def("rows", &Matrix::rows) + .def("cols", &Matrix::cols) + + /// Bare bones interface + .def("__getitem__", [](const Matrix &m, std::pair i) { + if (i.first >= m.rows() || i.second >= m.cols()) + throw py::index_error(); + return m(i.first, i.second); + }) + .def("__setitem__", [](Matrix &m, std::pair i, float v) { + if (i.first >= m.rows() || i.second >= m.cols()) + throw py::index_error(); + m(i.first, i.second) = v; + }) + /// Provide buffer access + .def_buffer([](Matrix &m) -> py::buffer_info { + return py::buffer_info( + m.data(), /* Pointer to buffer */ + { m.rows(), m.cols() }, /* Buffer dimensions */ + { sizeof(float) * size_t(m.cols()), /* Strides (in bytes) for each index */ + sizeof(float) } + ); + }) + ; + + + // test_inherited_protocol + class SquareMatrix : public Matrix { + public: + SquareMatrix(ssize_t n) : Matrix(n, n) { } + }; + // Derived classes inherit the buffer protocol and the buffer access function + py::class_(m, "SquareMatrix") + .def(py::init()); + + + // test_pointer_to_member_fn + // Tests that passing a pointer to member to the base class works in + // the derived class. + struct Buffer { + int32_t value = 0; + + py::buffer_info get_buffer_info() { + return py::buffer_info(&value, sizeof(value), + py::format_descriptor::format(), 1); + } + }; + py::class_(m, "Buffer", py::buffer_protocol()) + .def(py::init<>()) + .def_readwrite("value", &Buffer::value) + .def_buffer(&Buffer::get_buffer_info); + + + class ConstBuffer { + std::unique_ptr value; + + public: + int32_t get_value() const { return *value; } + void set_value(int32_t v) { *value = v; } + + py::buffer_info get_buffer_info() const { + return py::buffer_info(value.get(), sizeof(*value), + py::format_descriptor::format(), 1); + } + + ConstBuffer() : value(new int32_t{0}) { }; + }; + py::class_(m, "ConstBuffer", py::buffer_protocol()) + .def(py::init<>()) + .def_property("value", &ConstBuffer::get_value, &ConstBuffer::set_value) + .def_buffer(&ConstBuffer::get_buffer_info); + + struct DerivedBuffer : public Buffer { }; + py::class_(m, "DerivedBuffer", py::buffer_protocol()) + .def(py::init<>()) + .def_readwrite("value", (int32_t DerivedBuffer::*) &DerivedBuffer::value) + .def_buffer(&DerivedBuffer::get_buffer_info); + +} diff --git a/wrap/python/pybind11/tests/test_buffers.py b/wrap/python/pybind11/tests/test_buffers.py new file mode 100644 index 000000000..f006552bf --- /dev/null +++ b/wrap/python/pybind11/tests/test_buffers.py @@ -0,0 +1,87 @@ +import struct +import pytest +from pybind11_tests import buffers as m +from pybind11_tests import ConstructorStats + +pytestmark = pytest.requires_numpy + +with pytest.suppress(ImportError): + import numpy as np + + +def test_from_python(): + with pytest.raises(RuntimeError) as excinfo: + m.Matrix(np.array([1, 2, 3])) # trying to assign a 1D array + assert str(excinfo.value) == "Incompatible buffer format!" + + m3 = np.array([[1, 2, 3], [4, 5, 6]]).astype(np.float32) + m4 = m.Matrix(m3) + + for i in range(m4.rows()): + for j in range(m4.cols()): + assert m3[i, j] == m4[i, j] + + cstats = ConstructorStats.get(m.Matrix) + assert cstats.alive() == 1 + del m3, m4 + assert cstats.alive() == 0 + assert cstats.values() == ["2x3 matrix"] + assert cstats.copy_constructions == 0 + # assert cstats.move_constructions >= 0 # Don't invoke any + assert cstats.copy_assignments == 0 + assert cstats.move_assignments == 0 + + +# PyPy: Memory leak in the "np.array(m, copy=False)" call +# https://bitbucket.org/pypy/pypy/issues/2444 +@pytest.unsupported_on_pypy +def test_to_python(): + mat = m.Matrix(5, 4) + assert memoryview(mat).shape == (5, 4) + + assert mat[2, 3] == 0 + mat[2, 3] = 4.0 + mat[3, 2] = 7.0 + assert mat[2, 3] == 4 + assert mat[3, 2] == 7 + assert struct.unpack_from('f', mat, (3 * 4 + 2) * 4) == (7, ) + assert struct.unpack_from('f', mat, (2 * 4 + 3) * 4) == (4, ) + + mat2 = np.array(mat, copy=False) + assert mat2.shape == (5, 4) + assert abs(mat2).sum() == 11 + assert mat2[2, 3] == 4 and mat2[3, 2] == 7 + mat2[2, 3] = 5 + assert mat2[2, 3] == 5 + + cstats = ConstructorStats.get(m.Matrix) + assert cstats.alive() == 1 + del mat + pytest.gc_collect() + assert cstats.alive() == 1 + del mat2 # holds a mat reference + pytest.gc_collect() + assert cstats.alive() == 0 + assert cstats.values() == ["5x4 matrix"] + assert cstats.copy_constructions == 0 + # assert cstats.move_constructions >= 0 # Don't invoke any + assert cstats.copy_assignments == 0 + assert cstats.move_assignments == 0 + + +@pytest.unsupported_on_pypy +def test_inherited_protocol(): + """SquareMatrix is derived from Matrix and inherits the buffer protocol""" + + matrix = m.SquareMatrix(5) + assert memoryview(matrix).shape == (5, 5) + assert np.asarray(matrix).shape == (5, 5) + + +@pytest.unsupported_on_pypy +def test_pointer_to_member_fn(): + for cls in [m.Buffer, m.ConstBuffer, m.DerivedBuffer]: + buf = cls() + buf.value = 0x12345678 + value = struct.unpack('i', bytearray(buf))[0] + assert value == 0x12345678 diff --git a/wrap/python/pybind11/tests/test_builtin_casters.cpp b/wrap/python/pybind11/tests/test_builtin_casters.cpp new file mode 100644 index 000000000..e026127f8 --- /dev/null +++ b/wrap/python/pybind11/tests/test_builtin_casters.cpp @@ -0,0 +1,170 @@ +/* + tests/test_builtin_casters.cpp -- Casters available without any additional headers + + Copyright (c) 2017 Wenzel Jakob + + All rights reserved. Use of this source code is governed by a + BSD-style license that can be found in the LICENSE file. +*/ + +#include "pybind11_tests.h" +#include + +#if defined(_MSC_VER) +# pragma warning(push) +# pragma warning(disable: 4127) // warning C4127: Conditional expression is constant +#endif + +TEST_SUBMODULE(builtin_casters, m) { + // test_simple_string + m.def("string_roundtrip", [](const char *s) { return s; }); + + // test_unicode_conversion + // Some test characters in utf16 and utf32 encodings. The last one (the 𝐀) contains a null byte + char32_t a32 = 0x61 /*a*/, z32 = 0x7a /*z*/, ib32 = 0x203d /*‽*/, cake32 = 0x1f382 /*🎂*/, mathbfA32 = 0x1d400 /*𝐀*/; + char16_t b16 = 0x62 /*b*/, z16 = 0x7a, ib16 = 0x203d, cake16_1 = 0xd83c, cake16_2 = 0xdf82, mathbfA16_1 = 0xd835, mathbfA16_2 = 0xdc00; + std::wstring wstr; + wstr.push_back(0x61); // a + wstr.push_back(0x2e18); // ⸘ + if (sizeof(wchar_t) == 2) { wstr.push_back(mathbfA16_1); wstr.push_back(mathbfA16_2); } // 𝐀, utf16 + else { wstr.push_back((wchar_t) mathbfA32); } // 𝐀, utf32 + wstr.push_back(0x7a); // z + + m.def("good_utf8_string", []() { return std::string(u8"Say utf8\u203d \U0001f382 \U0001d400"); }); // Say utf8‽ 🎂 𝐀 + m.def("good_utf16_string", [=]() { return std::u16string({ b16, ib16, cake16_1, cake16_2, mathbfA16_1, mathbfA16_2, z16 }); }); // b‽🎂𝐀z + m.def("good_utf32_string", [=]() { return std::u32string({ a32, mathbfA32, cake32, ib32, z32 }); }); // a𝐀🎂‽z + m.def("good_wchar_string", [=]() { return wstr; }); // a‽𝐀z + m.def("bad_utf8_string", []() { return std::string("abc\xd0" "def"); }); + m.def("bad_utf16_string", [=]() { return std::u16string({ b16, char16_t(0xd800), z16 }); }); + // Under Python 2.7, invalid unicode UTF-32 characters don't appear to trigger UnicodeDecodeError + if (PY_MAJOR_VERSION >= 3) + m.def("bad_utf32_string", [=]() { return std::u32string({ a32, char32_t(0xd800), z32 }); }); + if (PY_MAJOR_VERSION >= 3 || sizeof(wchar_t) == 2) + m.def("bad_wchar_string", [=]() { return std::wstring({ wchar_t(0x61), wchar_t(0xd800) }); }); + m.def("u8_Z", []() -> char { return 'Z'; }); + m.def("u8_eacute", []() -> char { return '\xe9'; }); + m.def("u16_ibang", [=]() -> char16_t { return ib16; }); + m.def("u32_mathbfA", [=]() -> char32_t { return mathbfA32; }); + m.def("wchar_heart", []() -> wchar_t { return 0x2665; }); + + // test_single_char_arguments + m.attr("wchar_size") = py::cast(sizeof(wchar_t)); + m.def("ord_char", [](char c) -> int { return static_cast(c); }); + m.def("ord_char_lv", [](char &c) -> int { return static_cast(c); }); + m.def("ord_char16", [](char16_t c) -> uint16_t { return c; }); + m.def("ord_char16_lv", [](char16_t &c) -> uint16_t { return c; }); + m.def("ord_char32", [](char32_t c) -> uint32_t { return c; }); + m.def("ord_wchar", [](wchar_t c) -> int { return c; }); + + // test_bytes_to_string + m.def("strlen", [](char *s) { return strlen(s); }); + m.def("string_length", [](std::string s) { return s.length(); }); + + // test_string_view +#ifdef PYBIND11_HAS_STRING_VIEW + m.attr("has_string_view") = true; + m.def("string_view_print", [](std::string_view s) { py::print(s, s.size()); }); + m.def("string_view16_print", [](std::u16string_view s) { py::print(s, s.size()); }); + m.def("string_view32_print", [](std::u32string_view s) { py::print(s, s.size()); }); + m.def("string_view_chars", [](std::string_view s) { py::list l; for (auto c : s) l.append((std::uint8_t) c); return l; }); + m.def("string_view16_chars", [](std::u16string_view s) { py::list l; for (auto c : s) l.append((int) c); return l; }); + m.def("string_view32_chars", [](std::u32string_view s) { py::list l; for (auto c : s) l.append((int) c); return l; }); + m.def("string_view_return", []() { return std::string_view(u8"utf8 secret \U0001f382"); }); + m.def("string_view16_return", []() { return std::u16string_view(u"utf16 secret \U0001f382"); }); + m.def("string_view32_return", []() { return std::u32string_view(U"utf32 secret \U0001f382"); }); +#endif + + // test_integer_casting + m.def("i32_str", [](std::int32_t v) { return std::to_string(v); }); + m.def("u32_str", [](std::uint32_t v) { return std::to_string(v); }); + m.def("i64_str", [](std::int64_t v) { return std::to_string(v); }); + m.def("u64_str", [](std::uint64_t v) { return std::to_string(v); }); + + // test_tuple + m.def("pair_passthrough", [](std::pair input) { + return std::make_pair(input.second, input.first); + }, "Return a pair in reversed order"); + m.def("tuple_passthrough", [](std::tuple input) { + return std::make_tuple(std::get<2>(input), std::get<1>(input), std::get<0>(input)); + }, "Return a triple in reversed order"); + m.def("empty_tuple", []() { return std::tuple<>(); }); + static std::pair lvpair; + static std::tuple lvtuple; + static std::pair>> lvnested; + m.def("rvalue_pair", []() { return std::make_pair(RValueCaster{}, RValueCaster{}); }); + m.def("lvalue_pair", []() -> const decltype(lvpair) & { return lvpair; }); + m.def("rvalue_tuple", []() { return std::make_tuple(RValueCaster{}, RValueCaster{}, RValueCaster{}); }); + m.def("lvalue_tuple", []() -> const decltype(lvtuple) & { return lvtuple; }); + m.def("rvalue_nested", []() { + return std::make_pair(RValueCaster{}, std::make_tuple(RValueCaster{}, std::make_pair(RValueCaster{}, RValueCaster{}))); }); + m.def("lvalue_nested", []() -> const decltype(lvnested) & { return lvnested; }); + + // test_builtins_cast_return_none + m.def("return_none_string", []() -> std::string * { return nullptr; }); + m.def("return_none_char", []() -> const char * { return nullptr; }); + m.def("return_none_bool", []() -> bool * { return nullptr; }); + m.def("return_none_int", []() -> int * { return nullptr; }); + m.def("return_none_float", []() -> float * { return nullptr; }); + + // test_none_deferred + m.def("defer_none_cstring", [](char *) { return false; }); + m.def("defer_none_cstring", [](py::none) { return true; }); + m.def("defer_none_custom", [](UserType *) { return false; }); + m.def("defer_none_custom", [](py::none) { return true; }); + m.def("nodefer_none_void", [](void *) { return true; }); + m.def("nodefer_none_void", [](py::none) { return false; }); + + // test_void_caster + m.def("load_nullptr_t", [](std::nullptr_t) {}); // not useful, but it should still compile + m.def("cast_nullptr_t", []() { return std::nullptr_t{}; }); + + // test_bool_caster + m.def("bool_passthrough", [](bool arg) { return arg; }); + m.def("bool_passthrough_noconvert", [](bool arg) { return arg; }, py::arg().noconvert()); + + // test_reference_wrapper + m.def("refwrap_builtin", [](std::reference_wrapper p) { return 10 * p.get(); }); + m.def("refwrap_usertype", [](std::reference_wrapper p) { return p.get().value(); }); + // Not currently supported (std::pair caster has return-by-value cast operator); + // triggers static_assert failure. + //m.def("refwrap_pair", [](std::reference_wrapper>) { }); + + m.def("refwrap_list", [](bool copy) { + static IncType x1(1), x2(2); + py::list l; + for (auto &f : {std::ref(x1), std::ref(x2)}) { + l.append(py::cast(f, copy ? py::return_value_policy::copy + : py::return_value_policy::reference)); + } + return l; + }, "copy"_a); + + m.def("refwrap_iiw", [](const IncType &w) { return w.value(); }); + m.def("refwrap_call_iiw", [](IncType &w, py::function f) { + py::list l; + l.append(f(std::ref(w))); + l.append(f(std::cref(w))); + IncType x(w.value()); + l.append(f(std::ref(x))); + IncType y(w.value()); + auto r3 = std::ref(y); + l.append(f(r3)); + return l; + }); + + // test_complex + m.def("complex_cast", [](float x) { return "{}"_s.format(x); }); + m.def("complex_cast", [](std::complex x) { return "({}, {})"_s.format(x.real(), x.imag()); }); + + // test int vs. long (Python 2) + m.def("int_cast", []() {return (int) 42;}); + m.def("long_cast", []() {return (long) 42;}); + m.def("longlong_cast", []() {return ULLONG_MAX;}); + + /// test void* cast operator + m.def("test_void_caster", []() -> bool { + void *v = (void *) 0xabcd; + py::object o = py::cast(v); + return py::cast(o) == v; + }); +} diff --git a/wrap/python/pybind11/tests/test_builtin_casters.py b/wrap/python/pybind11/tests/test_builtin_casters.py new file mode 100644 index 000000000..73cc465f5 --- /dev/null +++ b/wrap/python/pybind11/tests/test_builtin_casters.py @@ -0,0 +1,342 @@ +# Python < 3 needs this: coding=utf-8 +import pytest + +from pybind11_tests import builtin_casters as m +from pybind11_tests import UserType, IncType + + +def test_simple_string(): + assert m.string_roundtrip("const char *") == "const char *" + + +def test_unicode_conversion(): + """Tests unicode conversion and error reporting.""" + assert m.good_utf8_string() == u"Say utf8‽ 🎂 𝐀" + assert m.good_utf16_string() == u"b‽🎂𝐀z" + assert m.good_utf32_string() == u"a𝐀🎂‽z" + assert m.good_wchar_string() == u"a⸘𝐀z" + + with pytest.raises(UnicodeDecodeError): + m.bad_utf8_string() + + with pytest.raises(UnicodeDecodeError): + m.bad_utf16_string() + + # These are provided only if they actually fail (they don't when 32-bit and under Python 2.7) + if hasattr(m, "bad_utf32_string"): + with pytest.raises(UnicodeDecodeError): + m.bad_utf32_string() + if hasattr(m, "bad_wchar_string"): + with pytest.raises(UnicodeDecodeError): + m.bad_wchar_string() + + assert m.u8_Z() == 'Z' + assert m.u8_eacute() == u'é' + assert m.u16_ibang() == u'‽' + assert m.u32_mathbfA() == u'𝐀' + assert m.wchar_heart() == u'♥' + + +def test_single_char_arguments(): + """Tests failures for passing invalid inputs to char-accepting functions""" + def toobig_message(r): + return "Character code point not in range({0:#x})".format(r) + toolong_message = "Expected a character, but multi-character string found" + + assert m.ord_char(u'a') == 0x61 # simple ASCII + assert m.ord_char_lv(u'b') == 0x62 + assert m.ord_char(u'é') == 0xE9 # requires 2 bytes in utf-8, but can be stuffed in a char + with pytest.raises(ValueError) as excinfo: + assert m.ord_char(u'Ā') == 0x100 # requires 2 bytes, doesn't fit in a char + assert str(excinfo.value) == toobig_message(0x100) + with pytest.raises(ValueError) as excinfo: + assert m.ord_char(u'ab') + assert str(excinfo.value) == toolong_message + + assert m.ord_char16(u'a') == 0x61 + assert m.ord_char16(u'é') == 0xE9 + assert m.ord_char16_lv(u'ê') == 0xEA + assert m.ord_char16(u'Ā') == 0x100 + assert m.ord_char16(u'‽') == 0x203d + assert m.ord_char16(u'♥') == 0x2665 + assert m.ord_char16_lv(u'♡') == 0x2661 + with pytest.raises(ValueError) as excinfo: + assert m.ord_char16(u'🎂') == 0x1F382 # requires surrogate pair + assert str(excinfo.value) == toobig_message(0x10000) + with pytest.raises(ValueError) as excinfo: + assert m.ord_char16(u'aa') + assert str(excinfo.value) == toolong_message + + assert m.ord_char32(u'a') == 0x61 + assert m.ord_char32(u'é') == 0xE9 + assert m.ord_char32(u'Ā') == 0x100 + assert m.ord_char32(u'‽') == 0x203d + assert m.ord_char32(u'♥') == 0x2665 + assert m.ord_char32(u'🎂') == 0x1F382 + with pytest.raises(ValueError) as excinfo: + assert m.ord_char32(u'aa') + assert str(excinfo.value) == toolong_message + + assert m.ord_wchar(u'a') == 0x61 + assert m.ord_wchar(u'é') == 0xE9 + assert m.ord_wchar(u'Ā') == 0x100 + assert m.ord_wchar(u'‽') == 0x203d + assert m.ord_wchar(u'♥') == 0x2665 + if m.wchar_size == 2: + with pytest.raises(ValueError) as excinfo: + assert m.ord_wchar(u'🎂') == 0x1F382 # requires surrogate pair + assert str(excinfo.value) == toobig_message(0x10000) + else: + assert m.ord_wchar(u'🎂') == 0x1F382 + with pytest.raises(ValueError) as excinfo: + assert m.ord_wchar(u'aa') + assert str(excinfo.value) == toolong_message + + +def test_bytes_to_string(): + """Tests the ability to pass bytes to C++ string-accepting functions. Note that this is + one-way: the only way to return bytes to Python is via the pybind11::bytes class.""" + # Issue #816 + import sys + byte = bytes if sys.version_info[0] < 3 else str + + assert m.strlen(byte("hi")) == 2 + assert m.string_length(byte("world")) == 5 + assert m.string_length(byte("a\x00b")) == 3 + assert m.strlen(byte("a\x00b")) == 1 # C-string limitation + + # passing in a utf8 encoded string should work + assert m.string_length(u'💩'.encode("utf8")) == 4 + + +@pytest.mark.skipif(not hasattr(m, "has_string_view"), reason="no ") +def test_string_view(capture): + """Tests support for C++17 string_view arguments and return values""" + assert m.string_view_chars("Hi") == [72, 105] + assert m.string_view_chars("Hi 🎂") == [72, 105, 32, 0xf0, 0x9f, 0x8e, 0x82] + assert m.string_view16_chars("Hi 🎂") == [72, 105, 32, 0xd83c, 0xdf82] + assert m.string_view32_chars("Hi 🎂") == [72, 105, 32, 127874] + + assert m.string_view_return() == "utf8 secret 🎂" + assert m.string_view16_return() == "utf16 secret 🎂" + assert m.string_view32_return() == "utf32 secret 🎂" + + with capture: + m.string_view_print("Hi") + m.string_view_print("utf8 🎂") + m.string_view16_print("utf16 🎂") + m.string_view32_print("utf32 🎂") + assert capture == """ + Hi 2 + utf8 🎂 9 + utf16 🎂 8 + utf32 🎂 7 + """ + + with capture: + m.string_view_print("Hi, ascii") + m.string_view_print("Hi, utf8 🎂") + m.string_view16_print("Hi, utf16 🎂") + m.string_view32_print("Hi, utf32 🎂") + assert capture == """ + Hi, ascii 9 + Hi, utf8 🎂 13 + Hi, utf16 🎂 12 + Hi, utf32 🎂 11 + """ + + +def test_integer_casting(): + """Issue #929 - out-of-range integer values shouldn't be accepted""" + import sys + assert m.i32_str(-1) == "-1" + assert m.i64_str(-1) == "-1" + assert m.i32_str(2000000000) == "2000000000" + assert m.u32_str(2000000000) == "2000000000" + if sys.version_info < (3,): + assert m.i32_str(long(-1)) == "-1" # noqa: F821 undefined name 'long' + assert m.i64_str(long(-1)) == "-1" # noqa: F821 undefined name 'long' + assert m.i64_str(long(-999999999999)) == "-999999999999" # noqa: F821 undefined name + assert m.u64_str(long(999999999999)) == "999999999999" # noqa: F821 undefined name 'long' + else: + assert m.i64_str(-999999999999) == "-999999999999" + assert m.u64_str(999999999999) == "999999999999" + + with pytest.raises(TypeError) as excinfo: + m.u32_str(-1) + assert "incompatible function arguments" in str(excinfo.value) + with pytest.raises(TypeError) as excinfo: + m.u64_str(-1) + assert "incompatible function arguments" in str(excinfo.value) + with pytest.raises(TypeError) as excinfo: + m.i32_str(-3000000000) + assert "incompatible function arguments" in str(excinfo.value) + with pytest.raises(TypeError) as excinfo: + m.i32_str(3000000000) + assert "incompatible function arguments" in str(excinfo.value) + + if sys.version_info < (3,): + with pytest.raises(TypeError) as excinfo: + m.u32_str(long(-1)) # noqa: F821 undefined name 'long' + assert "incompatible function arguments" in str(excinfo.value) + with pytest.raises(TypeError) as excinfo: + m.u64_str(long(-1)) # noqa: F821 undefined name 'long' + assert "incompatible function arguments" in str(excinfo.value) + + +def test_tuple(doc): + """std::pair <-> tuple & std::tuple <-> tuple""" + assert m.pair_passthrough((True, "test")) == ("test", True) + assert m.tuple_passthrough((True, "test", 5)) == (5, "test", True) + # Any sequence can be cast to a std::pair or std::tuple + assert m.pair_passthrough([True, "test"]) == ("test", True) + assert m.tuple_passthrough([True, "test", 5]) == (5, "test", True) + assert m.empty_tuple() == () + + assert doc(m.pair_passthrough) == """ + pair_passthrough(arg0: Tuple[bool, str]) -> Tuple[str, bool] + + Return a pair in reversed order + """ + assert doc(m.tuple_passthrough) == """ + tuple_passthrough(arg0: Tuple[bool, str, int]) -> Tuple[int, str, bool] + + Return a triple in reversed order + """ + + assert m.rvalue_pair() == ("rvalue", "rvalue") + assert m.lvalue_pair() == ("lvalue", "lvalue") + assert m.rvalue_tuple() == ("rvalue", "rvalue", "rvalue") + assert m.lvalue_tuple() == ("lvalue", "lvalue", "lvalue") + assert m.rvalue_nested() == ("rvalue", ("rvalue", ("rvalue", "rvalue"))) + assert m.lvalue_nested() == ("lvalue", ("lvalue", ("lvalue", "lvalue"))) + + +def test_builtins_cast_return_none(): + """Casters produced with PYBIND11_TYPE_CASTER() should convert nullptr to None""" + assert m.return_none_string() is None + assert m.return_none_char() is None + assert m.return_none_bool() is None + assert m.return_none_int() is None + assert m.return_none_float() is None + + +def test_none_deferred(): + """None passed as various argument types should defer to other overloads""" + assert not m.defer_none_cstring("abc") + assert m.defer_none_cstring(None) + assert not m.defer_none_custom(UserType()) + assert m.defer_none_custom(None) + assert m.nodefer_none_void(None) + + +def test_void_caster(): + assert m.load_nullptr_t(None) is None + assert m.cast_nullptr_t() is None + + +def test_reference_wrapper(): + """std::reference_wrapper for builtin and user types""" + assert m.refwrap_builtin(42) == 420 + assert m.refwrap_usertype(UserType(42)) == 42 + + with pytest.raises(TypeError) as excinfo: + m.refwrap_builtin(None) + assert "incompatible function arguments" in str(excinfo.value) + + with pytest.raises(TypeError) as excinfo: + m.refwrap_usertype(None) + assert "incompatible function arguments" in str(excinfo.value) + + a1 = m.refwrap_list(copy=True) + a2 = m.refwrap_list(copy=True) + assert [x.value for x in a1] == [2, 3] + assert [x.value for x in a2] == [2, 3] + assert not a1[0] is a2[0] and not a1[1] is a2[1] + + b1 = m.refwrap_list(copy=False) + b2 = m.refwrap_list(copy=False) + assert [x.value for x in b1] == [1, 2] + assert [x.value for x in b2] == [1, 2] + assert b1[0] is b2[0] and b1[1] is b2[1] + + assert m.refwrap_iiw(IncType(5)) == 5 + assert m.refwrap_call_iiw(IncType(10), m.refwrap_iiw) == [10, 10, 10, 10] + + +def test_complex_cast(): + """std::complex casts""" + assert m.complex_cast(1) == "1.0" + assert m.complex_cast(2j) == "(0.0, 2.0)" + + +def test_bool_caster(): + """Test bool caster implicit conversions.""" + convert, noconvert = m.bool_passthrough, m.bool_passthrough_noconvert + + def require_implicit(v): + pytest.raises(TypeError, noconvert, v) + + def cant_convert(v): + pytest.raises(TypeError, convert, v) + + # straight up bool + assert convert(True) is True + assert convert(False) is False + assert noconvert(True) is True + assert noconvert(False) is False + + # None requires implicit conversion + require_implicit(None) + assert convert(None) is False + + class A(object): + def __init__(self, x): + self.x = x + + def __nonzero__(self): + return self.x + + def __bool__(self): + return self.x + + class B(object): + pass + + # Arbitrary objects are not accepted + cant_convert(object()) + cant_convert(B()) + + # Objects with __nonzero__ / __bool__ defined can be converted + require_implicit(A(True)) + assert convert(A(True)) is True + assert convert(A(False)) is False + + +@pytest.requires_numpy +def test_numpy_bool(): + import numpy as np + convert, noconvert = m.bool_passthrough, m.bool_passthrough_noconvert + + # np.bool_ is not considered implicit + assert convert(np.bool_(True)) is True + assert convert(np.bool_(False)) is False + assert noconvert(np.bool_(True)) is True + assert noconvert(np.bool_(False)) is False + + +def test_int_long(): + """In Python 2, a C++ int should return a Python int rather than long + if possible: longs are not always accepted where ints are used (such + as the argument to sys.exit()). A C++ long long is always a Python + long.""" + + import sys + must_be_long = type(getattr(sys, 'maxint', 1) + 1) + assert isinstance(m.int_cast(), int) + assert isinstance(m.long_cast(), int) + assert isinstance(m.longlong_cast(), must_be_long) + + +def test_void_caster_2(): + assert m.test_void_caster() diff --git a/wrap/python/pybind11/tests/test_call_policies.cpp b/wrap/python/pybind11/tests/test_call_policies.cpp new file mode 100644 index 000000000..fd2455783 --- /dev/null +++ b/wrap/python/pybind11/tests/test_call_policies.cpp @@ -0,0 +1,100 @@ +/* + tests/test_call_policies.cpp -- keep_alive and call_guard + + Copyright (c) 2016 Wenzel Jakob + + All rights reserved. Use of this source code is governed by a + BSD-style license that can be found in the LICENSE file. +*/ + +#include "pybind11_tests.h" + +struct CustomGuard { + static bool enabled; + + CustomGuard() { enabled = true; } + ~CustomGuard() { enabled = false; } + + static const char *report_status() { return enabled ? "guarded" : "unguarded"; } +}; +bool CustomGuard::enabled = false; + +struct DependentGuard { + static bool enabled; + + DependentGuard() { enabled = CustomGuard::enabled; } + ~DependentGuard() { enabled = false; } + + static const char *report_status() { return enabled ? "guarded" : "unguarded"; } +}; +bool DependentGuard::enabled = false; + +TEST_SUBMODULE(call_policies, m) { + // Parent/Child are used in: + // test_keep_alive_argument, test_keep_alive_return_value, test_alive_gc_derived, + // test_alive_gc_multi_derived, test_return_none, test_keep_alive_constructor + class Child { + public: + Child() { py::print("Allocating child."); } + Child(const Child &) = default; + Child(Child &&) = default; + ~Child() { py::print("Releasing child."); } + }; + py::class_(m, "Child") + .def(py::init<>()); + + class Parent { + public: + Parent() { py::print("Allocating parent."); } + ~Parent() { py::print("Releasing parent."); } + void addChild(Child *) { } + Child *returnChild() { return new Child(); } + Child *returnNullChild() { return nullptr; } + }; + py::class_(m, "Parent") + .def(py::init<>()) + .def(py::init([](Child *) { return new Parent(); }), py::keep_alive<1, 2>()) + .def("addChild", &Parent::addChild) + .def("addChildKeepAlive", &Parent::addChild, py::keep_alive<1, 2>()) + .def("returnChild", &Parent::returnChild) + .def("returnChildKeepAlive", &Parent::returnChild, py::keep_alive<1, 0>()) + .def("returnNullChildKeepAliveChild", &Parent::returnNullChild, py::keep_alive<1, 0>()) + .def("returnNullChildKeepAliveParent", &Parent::returnNullChild, py::keep_alive<0, 1>()); + +#if !defined(PYPY_VERSION) + // test_alive_gc + class ParentGC : public Parent { + public: + using Parent::Parent; + }; + py::class_(m, "ParentGC", py::dynamic_attr()) + .def(py::init<>()); +#endif + + // test_call_guard + m.def("unguarded_call", &CustomGuard::report_status); + m.def("guarded_call", &CustomGuard::report_status, py::call_guard()); + + m.def("multiple_guards_correct_order", []() { + return CustomGuard::report_status() + std::string(" & ") + DependentGuard::report_status(); + }, py::call_guard()); + + m.def("multiple_guards_wrong_order", []() { + return DependentGuard::report_status() + std::string(" & ") + CustomGuard::report_status(); + }, py::call_guard()); + +#if defined(WITH_THREAD) && !defined(PYPY_VERSION) + // `py::call_guard()` should work in PyPy as well, + // but it's unclear how to test it without `PyGILState_GetThisThreadState`. + auto report_gil_status = []() { + auto is_gil_held = false; + if (auto tstate = py::detail::get_thread_state_unchecked()) + is_gil_held = (tstate == PyGILState_GetThisThreadState()); + + return is_gil_held ? "GIL held" : "GIL released"; + }; + + m.def("with_gil", report_gil_status); + m.def("without_gil", report_gil_status, py::call_guard()); +#endif +} diff --git a/wrap/python/pybind11/tests/test_call_policies.py b/wrap/python/pybind11/tests/test_call_policies.py new file mode 100644 index 000000000..7c835599c --- /dev/null +++ b/wrap/python/pybind11/tests/test_call_policies.py @@ -0,0 +1,187 @@ +import pytest +from pybind11_tests import call_policies as m +from pybind11_tests import ConstructorStats + + +def test_keep_alive_argument(capture): + n_inst = ConstructorStats.detail_reg_inst() + with capture: + p = m.Parent() + assert capture == "Allocating parent." + with capture: + p.addChild(m.Child()) + assert ConstructorStats.detail_reg_inst() == n_inst + 1 + assert capture == """ + Allocating child. + Releasing child. + """ + with capture: + del p + assert ConstructorStats.detail_reg_inst() == n_inst + assert capture == "Releasing parent." + + with capture: + p = m.Parent() + assert capture == "Allocating parent." + with capture: + p.addChildKeepAlive(m.Child()) + assert ConstructorStats.detail_reg_inst() == n_inst + 2 + assert capture == "Allocating child." + with capture: + del p + assert ConstructorStats.detail_reg_inst() == n_inst + assert capture == """ + Releasing parent. + Releasing child. + """ + + +def test_keep_alive_return_value(capture): + n_inst = ConstructorStats.detail_reg_inst() + with capture: + p = m.Parent() + assert capture == "Allocating parent." + with capture: + p.returnChild() + assert ConstructorStats.detail_reg_inst() == n_inst + 1 + assert capture == """ + Allocating child. + Releasing child. + """ + with capture: + del p + assert ConstructorStats.detail_reg_inst() == n_inst + assert capture == "Releasing parent." + + with capture: + p = m.Parent() + assert capture == "Allocating parent." + with capture: + p.returnChildKeepAlive() + assert ConstructorStats.detail_reg_inst() == n_inst + 2 + assert capture == "Allocating child." + with capture: + del p + assert ConstructorStats.detail_reg_inst() == n_inst + assert capture == """ + Releasing parent. + Releasing child. + """ + + +# https://bitbucket.org/pypy/pypy/issues/2447 +@pytest.unsupported_on_pypy +def test_alive_gc(capture): + n_inst = ConstructorStats.detail_reg_inst() + p = m.ParentGC() + p.addChildKeepAlive(m.Child()) + assert ConstructorStats.detail_reg_inst() == n_inst + 2 + lst = [p] + lst.append(lst) # creates a circular reference + with capture: + del p, lst + assert ConstructorStats.detail_reg_inst() == n_inst + assert capture == """ + Releasing parent. + Releasing child. + """ + + +def test_alive_gc_derived(capture): + class Derived(m.Parent): + pass + + n_inst = ConstructorStats.detail_reg_inst() + p = Derived() + p.addChildKeepAlive(m.Child()) + assert ConstructorStats.detail_reg_inst() == n_inst + 2 + lst = [p] + lst.append(lst) # creates a circular reference + with capture: + del p, lst + assert ConstructorStats.detail_reg_inst() == n_inst + assert capture == """ + Releasing parent. + Releasing child. + """ + + +def test_alive_gc_multi_derived(capture): + class Derived(m.Parent, m.Child): + def __init__(self): + m.Parent.__init__(self) + m.Child.__init__(self) + + n_inst = ConstructorStats.detail_reg_inst() + p = Derived() + p.addChildKeepAlive(m.Child()) + # +3 rather than +2 because Derived corresponds to two registered instances + assert ConstructorStats.detail_reg_inst() == n_inst + 3 + lst = [p] + lst.append(lst) # creates a circular reference + with capture: + del p, lst + assert ConstructorStats.detail_reg_inst() == n_inst + assert capture == """ + Releasing parent. + Releasing child. + Releasing child. + """ + + +def test_return_none(capture): + n_inst = ConstructorStats.detail_reg_inst() + with capture: + p = m.Parent() + assert capture == "Allocating parent." + with capture: + p.returnNullChildKeepAliveChild() + assert ConstructorStats.detail_reg_inst() == n_inst + 1 + assert capture == "" + with capture: + del p + assert ConstructorStats.detail_reg_inst() == n_inst + assert capture == "Releasing parent." + + with capture: + p = m.Parent() + assert capture == "Allocating parent." + with capture: + p.returnNullChildKeepAliveParent() + assert ConstructorStats.detail_reg_inst() == n_inst + 1 + assert capture == "" + with capture: + del p + assert ConstructorStats.detail_reg_inst() == n_inst + assert capture == "Releasing parent." + + +def test_keep_alive_constructor(capture): + n_inst = ConstructorStats.detail_reg_inst() + + with capture: + p = m.Parent(m.Child()) + assert ConstructorStats.detail_reg_inst() == n_inst + 2 + assert capture == """ + Allocating child. + Allocating parent. + """ + with capture: + del p + assert ConstructorStats.detail_reg_inst() == n_inst + assert capture == """ + Releasing parent. + Releasing child. + """ + + +def test_call_guard(): + assert m.unguarded_call() == "unguarded" + assert m.guarded_call() == "guarded" + + assert m.multiple_guards_correct_order() == "guarded & guarded" + assert m.multiple_guards_wrong_order() == "unguarded & guarded" + + if hasattr(m, "with_gil"): + assert m.with_gil() == "GIL held" + assert m.without_gil() == "GIL released" diff --git a/wrap/python/pybind11/tests/test_callbacks.cpp b/wrap/python/pybind11/tests/test_callbacks.cpp new file mode 100644 index 000000000..71b88c44c --- /dev/null +++ b/wrap/python/pybind11/tests/test_callbacks.cpp @@ -0,0 +1,168 @@ +/* + tests/test_callbacks.cpp -- callbacks + + Copyright (c) 2016 Wenzel Jakob + + All rights reserved. Use of this source code is governed by a + BSD-style license that can be found in the LICENSE file. +*/ + +#include "pybind11_tests.h" +#include "constructor_stats.h" +#include +#include + + +int dummy_function(int i) { return i + 1; } + +TEST_SUBMODULE(callbacks, m) { + // test_callbacks, test_function_signatures + m.def("test_callback1", [](py::object func) { return func(); }); + m.def("test_callback2", [](py::object func) { return func("Hello", 'x', true, 5); }); + m.def("test_callback3", [](const std::function &func) { + return "func(43) = " + std::to_string(func(43)); }); + m.def("test_callback4", []() -> std::function { return [](int i) { return i+1; }; }); + m.def("test_callback5", []() { + return py::cpp_function([](int i) { return i+1; }, py::arg("number")); + }); + + // test_keyword_args_and_generalized_unpacking + m.def("test_tuple_unpacking", [](py::function f) { + auto t1 = py::make_tuple(2, 3); + auto t2 = py::make_tuple(5, 6); + return f("positional", 1, *t1, 4, *t2); + }); + + m.def("test_dict_unpacking", [](py::function f) { + auto d1 = py::dict("key"_a="value", "a"_a=1); + auto d2 = py::dict(); + auto d3 = py::dict("b"_a=2); + return f("positional", 1, **d1, **d2, **d3); + }); + + m.def("test_keyword_args", [](py::function f) { + return f("x"_a=10, "y"_a=20); + }); + + m.def("test_unpacking_and_keywords1", [](py::function f) { + auto args = py::make_tuple(2); + auto kwargs = py::dict("d"_a=4); + return f(1, *args, "c"_a=3, **kwargs); + }); + + m.def("test_unpacking_and_keywords2", [](py::function f) { + auto kwargs1 = py::dict("a"_a=1); + auto kwargs2 = py::dict("c"_a=3, "d"_a=4); + return f("positional", *py::make_tuple(1), 2, *py::make_tuple(3, 4), 5, + "key"_a="value", **kwargs1, "b"_a=2, **kwargs2, "e"_a=5); + }); + + m.def("test_unpacking_error1", [](py::function f) { + auto kwargs = py::dict("x"_a=3); + return f("x"_a=1, "y"_a=2, **kwargs); // duplicate ** after keyword + }); + + m.def("test_unpacking_error2", [](py::function f) { + auto kwargs = py::dict("x"_a=3); + return f(**kwargs, "x"_a=1); // duplicate keyword after ** + }); + + m.def("test_arg_conversion_error1", [](py::function f) { + f(234, UnregisteredType(), "kw"_a=567); + }); + + m.def("test_arg_conversion_error2", [](py::function f) { + f(234, "expected_name"_a=UnregisteredType(), "kw"_a=567); + }); + + // test_lambda_closure_cleanup + struct Payload { + Payload() { print_default_created(this); } + ~Payload() { print_destroyed(this); } + Payload(const Payload &) { print_copy_created(this); } + Payload(Payload &&) { print_move_created(this); } + }; + // Export the payload constructor statistics for testing purposes: + m.def("payload_cstats", &ConstructorStats::get); + /* Test cleanup of lambda closure */ + m.def("test_cleanup", []() -> std::function { + Payload p; + + return [p]() { + /* p should be cleaned up when the returned function is garbage collected */ + (void) p; + }; + }); + + // test_cpp_function_roundtrip + /* Test if passing a function pointer from C++ -> Python -> C++ yields the original pointer */ + m.def("dummy_function", &dummy_function); + m.def("dummy_function2", [](int i, int j) { return i + j; }); + m.def("roundtrip", [](std::function f, bool expect_none = false) { + if (expect_none && f) + throw std::runtime_error("Expected None to be converted to empty std::function"); + return f; + }, py::arg("f"), py::arg("expect_none")=false); + m.def("test_dummy_function", [](const std::function &f) -> std::string { + using fn_type = int (*)(int); + auto result = f.target(); + if (!result) { + auto r = f(1); + return "can't convert to function pointer: eval(1) = " + std::to_string(r); + } else if (*result == dummy_function) { + auto r = (*result)(1); + return "matches dummy_function: eval(1) = " + std::to_string(r); + } else { + return "argument does NOT match dummy_function. This should never happen!"; + } + }); + + class AbstractBase { public: virtual unsigned int func() = 0; }; + m.def("func_accepting_func_accepting_base", [](std::function) { }); + + struct MovableObject { + bool valid = true; + + MovableObject() = default; + MovableObject(const MovableObject &) = default; + MovableObject &operator=(const MovableObject &) = default; + MovableObject(MovableObject &&o) : valid(o.valid) { o.valid = false; } + MovableObject &operator=(MovableObject &&o) { + valid = o.valid; + o.valid = false; + return *this; + } + }; + py::class_(m, "MovableObject"); + + // test_movable_object + m.def("callback_with_movable", [](std::function f) { + auto x = MovableObject(); + f(x); // lvalue reference shouldn't move out object + return x.valid; // must still return `true` + }); + + // test_bound_method_callback + struct CppBoundMethodTest {}; + py::class_(m, "CppBoundMethodTest") + .def(py::init<>()) + .def("triple", [](CppBoundMethodTest &, int val) { return 3 * val; }); + + // test async Python callbacks + using callback_f = std::function; + m.def("test_async_callback", [](callback_f f, py::list work) { + // make detached thread that calls `f` with piece of work after a little delay + auto start_f = [f](int j) { + auto invoke_f = [f, j] { + std::this_thread::sleep_for(std::chrono::milliseconds(50)); + f(j); + }; + auto t = std::thread(std::move(invoke_f)); + t.detach(); + }; + + // spawn worker threads + for (auto i : work) + start_f(py::cast(i)); + }); +} diff --git a/wrap/python/pybind11/tests/test_callbacks.py b/wrap/python/pybind11/tests/test_callbacks.py new file mode 100644 index 000000000..6439c8e72 --- /dev/null +++ b/wrap/python/pybind11/tests/test_callbacks.py @@ -0,0 +1,136 @@ +import pytest +from pybind11_tests import callbacks as m +from threading import Thread + + +def test_callbacks(): + from functools import partial + + def func1(): + return "func1" + + def func2(a, b, c, d): + return "func2", a, b, c, d + + def func3(a): + return "func3({})".format(a) + + assert m.test_callback1(func1) == "func1" + assert m.test_callback2(func2) == ("func2", "Hello", "x", True, 5) + assert m.test_callback1(partial(func2, 1, 2, 3, 4)) == ("func2", 1, 2, 3, 4) + assert m.test_callback1(partial(func3, "partial")) == "func3(partial)" + assert m.test_callback3(lambda i: i + 1) == "func(43) = 44" + + f = m.test_callback4() + assert f(43) == 44 + f = m.test_callback5() + assert f(number=43) == 44 + + +def test_bound_method_callback(): + # Bound Python method: + class MyClass: + def double(self, val): + return 2 * val + + z = MyClass() + assert m.test_callback3(z.double) == "func(43) = 86" + + z = m.CppBoundMethodTest() + assert m.test_callback3(z.triple) == "func(43) = 129" + + +def test_keyword_args_and_generalized_unpacking(): + + def f(*args, **kwargs): + return args, kwargs + + assert m.test_tuple_unpacking(f) == (("positional", 1, 2, 3, 4, 5, 6), {}) + assert m.test_dict_unpacking(f) == (("positional", 1), {"key": "value", "a": 1, "b": 2}) + assert m.test_keyword_args(f) == ((), {"x": 10, "y": 20}) + assert m.test_unpacking_and_keywords1(f) == ((1, 2), {"c": 3, "d": 4}) + assert m.test_unpacking_and_keywords2(f) == ( + ("positional", 1, 2, 3, 4, 5), + {"key": "value", "a": 1, "b": 2, "c": 3, "d": 4, "e": 5} + ) + + with pytest.raises(TypeError) as excinfo: + m.test_unpacking_error1(f) + assert "Got multiple values for keyword argument" in str(excinfo.value) + + with pytest.raises(TypeError) as excinfo: + m.test_unpacking_error2(f) + assert "Got multiple values for keyword argument" in str(excinfo.value) + + with pytest.raises(RuntimeError) as excinfo: + m.test_arg_conversion_error1(f) + assert "Unable to convert call argument" in str(excinfo.value) + + with pytest.raises(RuntimeError) as excinfo: + m.test_arg_conversion_error2(f) + assert "Unable to convert call argument" in str(excinfo.value) + + +def test_lambda_closure_cleanup(): + m.test_cleanup() + cstats = m.payload_cstats() + assert cstats.alive() == 0 + assert cstats.copy_constructions == 1 + assert cstats.move_constructions >= 1 + + +def test_cpp_function_roundtrip(): + """Test if passing a function pointer from C++ -> Python -> C++ yields the original pointer""" + + assert m.test_dummy_function(m.dummy_function) == "matches dummy_function: eval(1) = 2" + assert (m.test_dummy_function(m.roundtrip(m.dummy_function)) == + "matches dummy_function: eval(1) = 2") + assert m.roundtrip(None, expect_none=True) is None + assert (m.test_dummy_function(lambda x: x + 2) == + "can't convert to function pointer: eval(1) = 3") + + with pytest.raises(TypeError) as excinfo: + m.test_dummy_function(m.dummy_function2) + assert "incompatible function arguments" in str(excinfo.value) + + with pytest.raises(TypeError) as excinfo: + m.test_dummy_function(lambda x, y: x + y) + assert any(s in str(excinfo.value) for s in ("missing 1 required positional argument", + "takes exactly 2 arguments")) + + +def test_function_signatures(doc): + assert doc(m.test_callback3) == "test_callback3(arg0: Callable[[int], int]) -> str" + assert doc(m.test_callback4) == "test_callback4() -> Callable[[int], int]" + + +def test_movable_object(): + assert m.callback_with_movable(lambda _: None) is True + + +def test_async_callbacks(): + # serves as state for async callback + class Item: + def __init__(self, value): + self.value = value + + res = [] + + # generate stateful lambda that will store result in `res` + def gen_f(): + s = Item(3) + return lambda j: res.append(s.value + j) + + # do some work async + work = [1, 2, 3, 4] + m.test_async_callback(gen_f(), work) + # wait until work is done + from time import sleep + sleep(0.5) + assert sum(res) == sum([x + 3 for x in work]) + + +def test_async_async_callbacks(): + t = Thread(target=test_async_callbacks) + t.start() + t.join() diff --git a/wrap/python/pybind11/tests/test_chrono.cpp b/wrap/python/pybind11/tests/test_chrono.cpp new file mode 100644 index 000000000..899d08d8d --- /dev/null +++ b/wrap/python/pybind11/tests/test_chrono.cpp @@ -0,0 +1,55 @@ +/* + tests/test_chrono.cpp -- test conversions to/from std::chrono types + + Copyright (c) 2016 Trent Houliston and + Wenzel Jakob + + All rights reserved. Use of this source code is governed by a + BSD-style license that can be found in the LICENSE file. +*/ + +#include "pybind11_tests.h" +#include + +TEST_SUBMODULE(chrono, m) { + using system_time = std::chrono::system_clock::time_point; + using steady_time = std::chrono::steady_clock::time_point; + + using timespan = std::chrono::duration; + using timestamp = std::chrono::time_point; + + // test_chrono_system_clock + // Return the current time off the wall clock + m.def("test_chrono1", []() { return std::chrono::system_clock::now(); }); + + // test_chrono_system_clock_roundtrip + // Round trip the passed in system clock time + m.def("test_chrono2", [](system_time t) { return t; }); + + // test_chrono_duration_roundtrip + // Round trip the passed in duration + m.def("test_chrono3", [](std::chrono::system_clock::duration d) { return d; }); + + // test_chrono_duration_subtraction_equivalence + // Difference between two passed in time_points + m.def("test_chrono4", [](system_time a, system_time b) { return a - b; }); + + // test_chrono_steady_clock + // Return the current time off the steady_clock + m.def("test_chrono5", []() { return std::chrono::steady_clock::now(); }); + + // test_chrono_steady_clock_roundtrip + // Round trip a steady clock timepoint + m.def("test_chrono6", [](steady_time t) { return t; }); + + // test_floating_point_duration + // Roundtrip a duration in microseconds from a float argument + m.def("test_chrono7", [](std::chrono::microseconds t) { return t; }); + // Float durations (issue #719) + m.def("test_chrono_float_diff", [](std::chrono::duration a, std::chrono::duration b) { + return a - b; }); + + m.def("test_nano_timepoint", [](timestamp start, timespan delta) -> timestamp { + return start + delta; + }); +} diff --git a/wrap/python/pybind11/tests/test_chrono.py b/wrap/python/pybind11/tests/test_chrono.py new file mode 100644 index 000000000..f308de977 --- /dev/null +++ b/wrap/python/pybind11/tests/test_chrono.py @@ -0,0 +1,107 @@ +from pybind11_tests import chrono as m +import datetime + + +def test_chrono_system_clock(): + + # Get the time from both c++ and datetime + date1 = m.test_chrono1() + date2 = datetime.datetime.today() + + # The returned value should be a datetime + assert isinstance(date1, datetime.datetime) + + # The numbers should vary by a very small amount (time it took to execute) + diff = abs(date1 - date2) + + # There should never be a days/seconds difference + assert diff.days == 0 + assert diff.seconds == 0 + + # We test that no more than about 0.5 seconds passes here + # This makes sure that the dates created are very close to the same + # but if the testing system is incredibly overloaded this should still pass + assert diff.microseconds < 500000 + + +def test_chrono_system_clock_roundtrip(): + date1 = datetime.datetime.today() + + # Roundtrip the time + date2 = m.test_chrono2(date1) + + # The returned value should be a datetime + assert isinstance(date2, datetime.datetime) + + # They should be identical (no information lost on roundtrip) + diff = abs(date1 - date2) + assert diff.days == 0 + assert diff.seconds == 0 + assert diff.microseconds == 0 + + +def test_chrono_duration_roundtrip(): + + # Get the difference between two times (a timedelta) + date1 = datetime.datetime.today() + date2 = datetime.datetime.today() + diff = date2 - date1 + + # Make sure this is a timedelta + assert isinstance(diff, datetime.timedelta) + + cpp_diff = m.test_chrono3(diff) + + assert cpp_diff.days == diff.days + assert cpp_diff.seconds == diff.seconds + assert cpp_diff.microseconds == diff.microseconds + + +def test_chrono_duration_subtraction_equivalence(): + + date1 = datetime.datetime.today() + date2 = datetime.datetime.today() + + diff = date2 - date1 + cpp_diff = m.test_chrono4(date2, date1) + + assert cpp_diff.days == diff.days + assert cpp_diff.seconds == diff.seconds + assert cpp_diff.microseconds == diff.microseconds + + +def test_chrono_steady_clock(): + time1 = m.test_chrono5() + assert isinstance(time1, datetime.timedelta) + + +def test_chrono_steady_clock_roundtrip(): + time1 = datetime.timedelta(days=10, seconds=10, microseconds=100) + time2 = m.test_chrono6(time1) + + assert isinstance(time2, datetime.timedelta) + + # They should be identical (no information lost on roundtrip) + assert time1.days == time2.days + assert time1.seconds == time2.seconds + assert time1.microseconds == time2.microseconds + + +def test_floating_point_duration(): + # Test using a floating point number in seconds + time = m.test_chrono7(35.525123) + + assert isinstance(time, datetime.timedelta) + + assert time.seconds == 35 + assert 525122 <= time.microseconds <= 525123 + + diff = m.test_chrono_float_diff(43.789012, 1.123456) + assert diff.seconds == 42 + assert 665556 <= diff.microseconds <= 665557 + + +def test_nano_timepoint(): + time = datetime.datetime.now() + time1 = m.test_nano_timepoint(time, datetime.timedelta(seconds=60)) + assert(time1 == time + datetime.timedelta(seconds=60)) diff --git a/wrap/python/pybind11/tests/test_class.cpp b/wrap/python/pybind11/tests/test_class.cpp new file mode 100644 index 000000000..499d0cc51 --- /dev/null +++ b/wrap/python/pybind11/tests/test_class.cpp @@ -0,0 +1,422 @@ +/* + tests/test_class.cpp -- test py::class_ definitions and basic functionality + + Copyright (c) 2016 Wenzel Jakob + + All rights reserved. Use of this source code is governed by a + BSD-style license that can be found in the LICENSE file. +*/ + +#include "pybind11_tests.h" +#include "constructor_stats.h" +#include "local_bindings.h" +#include + +#if defined(_MSC_VER) +# pragma warning(disable: 4324) // warning C4324: structure was padded due to alignment specifier +#endif + +// test_brace_initialization +struct NoBraceInitialization { + NoBraceInitialization(std::vector v) : vec{std::move(v)} {} + template + NoBraceInitialization(std::initializer_list l) : vec(l) {} + + std::vector vec; +}; + +TEST_SUBMODULE(class_, m) { + // test_instance + struct NoConstructor { + NoConstructor() = default; + NoConstructor(const NoConstructor &) = default; + NoConstructor(NoConstructor &&) = default; + static NoConstructor *new_instance() { + auto *ptr = new NoConstructor(); + print_created(ptr, "via new_instance"); + return ptr; + } + ~NoConstructor() { print_destroyed(this); } + }; + + py::class_(m, "NoConstructor") + .def_static("new_instance", &NoConstructor::new_instance, "Return an instance"); + + // test_inheritance + class Pet { + public: + Pet(const std::string &name, const std::string &species) + : m_name(name), m_species(species) {} + std::string name() const { return m_name; } + std::string species() const { return m_species; } + private: + std::string m_name; + std::string m_species; + }; + + class Dog : public Pet { + public: + Dog(const std::string &name) : Pet(name, "dog") {} + std::string bark() const { return "Woof!"; } + }; + + class Rabbit : public Pet { + public: + Rabbit(const std::string &name) : Pet(name, "parrot") {} + }; + + class Hamster : public Pet { + public: + Hamster(const std::string &name) : Pet(name, "rodent") {} + }; + + class Chimera : public Pet { + Chimera() : Pet("Kimmy", "chimera") {} + }; + + py::class_ pet_class(m, "Pet"); + pet_class + .def(py::init()) + .def("name", &Pet::name) + .def("species", &Pet::species); + + /* One way of declaring a subclass relationship: reference parent's class_ object */ + py::class_(m, "Dog", pet_class) + .def(py::init()); + + /* Another way of declaring a subclass relationship: reference parent's C++ type */ + py::class_(m, "Rabbit") + .def(py::init()); + + /* And another: list parent in class template arguments */ + py::class_(m, "Hamster") + .def(py::init()); + + /* Constructors are not inherited by default */ + py::class_(m, "Chimera"); + + m.def("pet_name_species", [](const Pet &pet) { return pet.name() + " is a " + pet.species(); }); + m.def("dog_bark", [](const Dog &dog) { return dog.bark(); }); + + // test_automatic_upcasting + struct BaseClass { + BaseClass() = default; + BaseClass(const BaseClass &) = default; + BaseClass(BaseClass &&) = default; + virtual ~BaseClass() {} + }; + struct DerivedClass1 : BaseClass { }; + struct DerivedClass2 : BaseClass { }; + + py::class_(m, "BaseClass").def(py::init<>()); + py::class_(m, "DerivedClass1").def(py::init<>()); + py::class_(m, "DerivedClass2").def(py::init<>()); + + m.def("return_class_1", []() -> BaseClass* { return new DerivedClass1(); }); + m.def("return_class_2", []() -> BaseClass* { return new DerivedClass2(); }); + m.def("return_class_n", [](int n) -> BaseClass* { + if (n == 1) return new DerivedClass1(); + if (n == 2) return new DerivedClass2(); + return new BaseClass(); + }); + m.def("return_none", []() -> BaseClass* { return nullptr; }); + + // test_isinstance + m.def("check_instances", [](py::list l) { + return py::make_tuple( + py::isinstance(l[0]), + py::isinstance(l[1]), + py::isinstance(l[2]), + py::isinstance(l[3]), + py::isinstance(l[4]), + py::isinstance(l[5]), + py::isinstance(l[6]) + ); + }); + + // test_mismatched_holder + struct MismatchBase1 { }; + struct MismatchDerived1 : MismatchBase1 { }; + + struct MismatchBase2 { }; + struct MismatchDerived2 : MismatchBase2 { }; + + m.def("mismatched_holder_1", []() { + auto mod = py::module::import("__main__"); + py::class_>(mod, "MismatchBase1"); + py::class_(mod, "MismatchDerived1"); + }); + m.def("mismatched_holder_2", []() { + auto mod = py::module::import("__main__"); + py::class_(mod, "MismatchBase2"); + py::class_, + MismatchBase2>(mod, "MismatchDerived2"); + }); + + // test_override_static + // #511: problem with inheritance + overwritten def_static + struct MyBase { + static std::unique_ptr make() { + return std::unique_ptr(new MyBase()); + } + }; + + struct MyDerived : MyBase { + static std::unique_ptr make() { + return std::unique_ptr(new MyDerived()); + } + }; + + py::class_(m, "MyBase") + .def_static("make", &MyBase::make); + + py::class_(m, "MyDerived") + .def_static("make", &MyDerived::make) + .def_static("make2", &MyDerived::make); + + // test_implicit_conversion_life_support + struct ConvertibleFromUserType { + int i; + + ConvertibleFromUserType(UserType u) : i(u.value()) { } + }; + + py::class_(m, "AcceptsUserType") + .def(py::init()); + py::implicitly_convertible(); + + m.def("implicitly_convert_argument", [](const ConvertibleFromUserType &r) { return r.i; }); + m.def("implicitly_convert_variable", [](py::object o) { + // `o` is `UserType` and `r` is a reference to a temporary created by implicit + // conversion. This is valid when called inside a bound function because the temp + // object is attached to the same life support system as the arguments. + const auto &r = o.cast(); + return r.i; + }); + m.add_object("implicitly_convert_variable_fail", [&] { + auto f = [](PyObject *, PyObject *args) -> PyObject * { + auto o = py::reinterpret_borrow(args)[0]; + try { // It should fail here because there is no life support. + o.cast(); + } catch (const py::cast_error &e) { + return py::str(e.what()).release().ptr(); + } + return py::str().release().ptr(); + }; + + auto def = new PyMethodDef{"f", f, METH_VARARGS, nullptr}; + return py::reinterpret_steal(PyCFunction_NewEx(def, nullptr, m.ptr())); + }()); + + // test_operator_new_delete + struct HasOpNewDel { + std::uint64_t i; + static void *operator new(size_t s) { py::print("A new", s); return ::operator new(s); } + static void *operator new(size_t s, void *ptr) { py::print("A placement-new", s); return ptr; } + static void operator delete(void *p) { py::print("A delete"); return ::operator delete(p); } + }; + struct HasOpNewDelSize { + std::uint32_t i; + static void *operator new(size_t s) { py::print("B new", s); return ::operator new(s); } + static void *operator new(size_t s, void *ptr) { py::print("B placement-new", s); return ptr; } + static void operator delete(void *p, size_t s) { py::print("B delete", s); return ::operator delete(p); } + }; + struct AliasedHasOpNewDelSize { + std::uint64_t i; + static void *operator new(size_t s) { py::print("C new", s); return ::operator new(s); } + static void *operator new(size_t s, void *ptr) { py::print("C placement-new", s); return ptr; } + static void operator delete(void *p, size_t s) { py::print("C delete", s); return ::operator delete(p); } + virtual ~AliasedHasOpNewDelSize() = default; + }; + struct PyAliasedHasOpNewDelSize : AliasedHasOpNewDelSize { + PyAliasedHasOpNewDelSize() = default; + PyAliasedHasOpNewDelSize(int) { } + std::uint64_t j; + }; + struct HasOpNewDelBoth { + std::uint32_t i[8]; + static void *operator new(size_t s) { py::print("D new", s); return ::operator new(s); } + static void *operator new(size_t s, void *ptr) { py::print("D placement-new", s); return ptr; } + static void operator delete(void *p) { py::print("D delete"); return ::operator delete(p); } + static void operator delete(void *p, size_t s) { py::print("D wrong delete", s); return ::operator delete(p); } + }; + py::class_(m, "HasOpNewDel").def(py::init<>()); + py::class_(m, "HasOpNewDelSize").def(py::init<>()); + py::class_(m, "HasOpNewDelBoth").def(py::init<>()); + py::class_ aliased(m, "AliasedHasOpNewDelSize"); + aliased.def(py::init<>()); + aliased.attr("size_noalias") = py::int_(sizeof(AliasedHasOpNewDelSize)); + aliased.attr("size_alias") = py::int_(sizeof(PyAliasedHasOpNewDelSize)); + + // This test is actually part of test_local_bindings (test_duplicate_local), but we need a + // definition in a different compilation unit within the same module: + bind_local(m, "LocalExternal", py::module_local()); + + // test_bind_protected_functions + class ProtectedA { + protected: + int foo() const { return value; } + + private: + int value = 42; + }; + + class PublicistA : public ProtectedA { + public: + using ProtectedA::foo; + }; + + py::class_(m, "ProtectedA") + .def(py::init<>()) +#if !defined(_MSC_VER) || _MSC_VER >= 1910 + .def("foo", &PublicistA::foo); +#else + .def("foo", static_cast(&PublicistA::foo)); +#endif + + class ProtectedB { + public: + virtual ~ProtectedB() = default; + + protected: + virtual int foo() const { return value; } + + private: + int value = 42; + }; + + class TrampolineB : public ProtectedB { + public: + int foo() const override { PYBIND11_OVERLOAD(int, ProtectedB, foo, ); } + }; + + class PublicistB : public ProtectedB { + public: + using ProtectedB::foo; + }; + + py::class_(m, "ProtectedB") + .def(py::init<>()) +#if !defined(_MSC_VER) || _MSC_VER >= 1910 + .def("foo", &PublicistB::foo); +#else + .def("foo", static_cast(&PublicistB::foo)); +#endif + + // test_brace_initialization + struct BraceInitialization { + int field1; + std::string field2; + }; + + py::class_(m, "BraceInitialization") + .def(py::init()) + .def_readwrite("field1", &BraceInitialization::field1) + .def_readwrite("field2", &BraceInitialization::field2); + // We *don't* want to construct using braces when the given constructor argument maps to a + // constructor, because brace initialization could go to the wrong place (in particular when + // there is also an `initializer_list`-accept constructor): + py::class_(m, "NoBraceInitialization") + .def(py::init>()) + .def_readonly("vec", &NoBraceInitialization::vec); + + // test_reentrant_implicit_conversion_failure + // #1035: issue with runaway reentrant implicit conversion + struct BogusImplicitConversion { + BogusImplicitConversion(const BogusImplicitConversion &) { } + }; + + py::class_(m, "BogusImplicitConversion") + .def(py::init()); + + py::implicitly_convertible(); + + // test_qualname + // #1166: nested class docstring doesn't show nested name + // Also related: tests that __qualname__ is set properly + struct NestBase {}; + struct Nested {}; + py::class_ base(m, "NestBase"); + base.def(py::init<>()); + py::class_(base, "Nested") + .def(py::init<>()) + .def("fn", [](Nested &, int, NestBase &, Nested &) {}) + .def("fa", [](Nested &, int, NestBase &, Nested &) {}, + "a"_a, "b"_a, "c"_a); + base.def("g", [](NestBase &, Nested &) {}); + base.def("h", []() { return NestBase(); }); + + // test_error_after_conversion + // The second-pass path through dispatcher() previously didn't + // remember which overload was used, and would crash trying to + // generate a useful error message + + struct NotRegistered {}; + struct StringWrapper { std::string str; }; + m.def("test_error_after_conversions", [](int) {}); + m.def("test_error_after_conversions", + [](StringWrapper) -> NotRegistered { return {}; }); + py::class_(m, "StringWrapper").def(py::init()); + py::implicitly_convertible(); + + #if defined(PYBIND11_CPP17) + struct alignas(1024) Aligned { + std::uintptr_t ptr() const { return (uintptr_t) this; } + }; + py::class_(m, "Aligned") + .def(py::init<>()) + .def("ptr", &Aligned::ptr); + #endif +} + +template class BreaksBase { public: virtual ~BreaksBase() = default; }; +template class BreaksTramp : public BreaksBase {}; +// These should all compile just fine: +typedef py::class_, std::unique_ptr>, BreaksTramp<1>> DoesntBreak1; +typedef py::class_, BreaksTramp<2>, std::unique_ptr>> DoesntBreak2; +typedef py::class_, std::unique_ptr>> DoesntBreak3; +typedef py::class_, BreaksTramp<4>> DoesntBreak4; +typedef py::class_> DoesntBreak5; +typedef py::class_, std::shared_ptr>, BreaksTramp<6>> DoesntBreak6; +typedef py::class_, BreaksTramp<7>, std::shared_ptr>> DoesntBreak7; +typedef py::class_, std::shared_ptr>> DoesntBreak8; +#define CHECK_BASE(N) static_assert(std::is_same>::value, \ + "DoesntBreak" #N " has wrong type!") +CHECK_BASE(1); CHECK_BASE(2); CHECK_BASE(3); CHECK_BASE(4); CHECK_BASE(5); CHECK_BASE(6); CHECK_BASE(7); CHECK_BASE(8); +#define CHECK_ALIAS(N) static_assert(DoesntBreak##N::has_alias && std::is_same>::value, \ + "DoesntBreak" #N " has wrong type_alias!") +#define CHECK_NOALIAS(N) static_assert(!DoesntBreak##N::has_alias && std::is_void::value, \ + "DoesntBreak" #N " has type alias, but shouldn't!") +CHECK_ALIAS(1); CHECK_ALIAS(2); CHECK_NOALIAS(3); CHECK_ALIAS(4); CHECK_NOALIAS(5); CHECK_ALIAS(6); CHECK_ALIAS(7); CHECK_NOALIAS(8); +#define CHECK_HOLDER(N, TYPE) static_assert(std::is_same>>::value, \ + "DoesntBreak" #N " has wrong holder_type!") +CHECK_HOLDER(1, unique); CHECK_HOLDER(2, unique); CHECK_HOLDER(3, unique); CHECK_HOLDER(4, unique); CHECK_HOLDER(5, unique); +CHECK_HOLDER(6, shared); CHECK_HOLDER(7, shared); CHECK_HOLDER(8, shared); + +// There's no nice way to test that these fail because they fail to compile; leave them here, +// though, so that they can be manually tested by uncommenting them (and seeing that compilation +// failures occurs). + +// We have to actually look into the type: the typedef alone isn't enough to instantiate the type: +#define CHECK_BROKEN(N) static_assert(std::is_same>::value, \ + "Breaks1 has wrong type!"); + +//// Two holder classes: +//typedef py::class_, std::unique_ptr>, std::unique_ptr>> Breaks1; +//CHECK_BROKEN(1); +//// Two aliases: +//typedef py::class_, BreaksTramp<-2>, BreaksTramp<-2>> Breaks2; +//CHECK_BROKEN(2); +//// Holder + 2 aliases +//typedef py::class_, std::unique_ptr>, BreaksTramp<-3>, BreaksTramp<-3>> Breaks3; +//CHECK_BROKEN(3); +//// Alias + 2 holders +//typedef py::class_, std::unique_ptr>, BreaksTramp<-4>, std::shared_ptr>> Breaks4; +//CHECK_BROKEN(4); +//// Invalid option (not a subclass or holder) +//typedef py::class_, BreaksTramp<-4>> Breaks5; +//CHECK_BROKEN(5); +//// Invalid option: multiple inheritance not supported: +//template <> struct BreaksBase<-8> : BreaksBase<-6>, BreaksBase<-7> {}; +//typedef py::class_, BreaksBase<-6>, BreaksBase<-7>> Breaks8; +//CHECK_BROKEN(8); diff --git a/wrap/python/pybind11/tests/test_class.py b/wrap/python/pybind11/tests/test_class.py new file mode 100644 index 000000000..ed63ca853 --- /dev/null +++ b/wrap/python/pybind11/tests/test_class.py @@ -0,0 +1,281 @@ +import pytest + +from pybind11_tests import class_ as m +from pybind11_tests import UserType, ConstructorStats + + +def test_repr(): + # In Python 3.3+, repr() accesses __qualname__ + assert "pybind11_type" in repr(type(UserType)) + assert "UserType" in repr(UserType) + + +def test_instance(msg): + with pytest.raises(TypeError) as excinfo: + m.NoConstructor() + assert msg(excinfo.value) == "m.class_.NoConstructor: No constructor defined!" + + instance = m.NoConstructor.new_instance() + + cstats = ConstructorStats.get(m.NoConstructor) + assert cstats.alive() == 1 + del instance + assert cstats.alive() == 0 + + +def test_docstrings(doc): + assert doc(UserType) == "A `py::class_` type for testing" + assert UserType.__name__ == "UserType" + assert UserType.__module__ == "pybind11_tests" + assert UserType.get_value.__name__ == "get_value" + assert UserType.get_value.__module__ == "pybind11_tests" + + assert doc(UserType.get_value) == """ + get_value(self: m.UserType) -> int + + Get value using a method + """ + assert doc(UserType.value) == "Get/set value using a property" + + assert doc(m.NoConstructor.new_instance) == """ + new_instance() -> m.class_.NoConstructor + + Return an instance + """ + + +def test_qualname(doc): + """Tests that a properly qualified name is set in __qualname__ (even in pre-3.3, where we + backport the attribute) and that generated docstrings properly use it and the module name""" + assert m.NestBase.__qualname__ == "NestBase" + assert m.NestBase.Nested.__qualname__ == "NestBase.Nested" + + assert doc(m.NestBase.__init__) == """ + __init__(self: m.class_.NestBase) -> None + """ + assert doc(m.NestBase.g) == """ + g(self: m.class_.NestBase, arg0: m.class_.NestBase.Nested) -> None + """ + assert doc(m.NestBase.Nested.__init__) == """ + __init__(self: m.class_.NestBase.Nested) -> None + """ + assert doc(m.NestBase.Nested.fn) == """ + fn(self: m.class_.NestBase.Nested, arg0: int, arg1: m.class_.NestBase, arg2: m.class_.NestBase.Nested) -> None + """ # noqa: E501 line too long + assert doc(m.NestBase.Nested.fa) == """ + fa(self: m.class_.NestBase.Nested, a: int, b: m.class_.NestBase, c: m.class_.NestBase.Nested) -> None + """ # noqa: E501 line too long + assert m.NestBase.__module__ == "pybind11_tests.class_" + assert m.NestBase.Nested.__module__ == "pybind11_tests.class_" + + +def test_inheritance(msg): + roger = m.Rabbit('Rabbit') + assert roger.name() + " is a " + roger.species() == "Rabbit is a parrot" + assert m.pet_name_species(roger) == "Rabbit is a parrot" + + polly = m.Pet('Polly', 'parrot') + assert polly.name() + " is a " + polly.species() == "Polly is a parrot" + assert m.pet_name_species(polly) == "Polly is a parrot" + + molly = m.Dog('Molly') + assert molly.name() + " is a " + molly.species() == "Molly is a dog" + assert m.pet_name_species(molly) == "Molly is a dog" + + fred = m.Hamster('Fred') + assert fred.name() + " is a " + fred.species() == "Fred is a rodent" + + assert m.dog_bark(molly) == "Woof!" + + with pytest.raises(TypeError) as excinfo: + m.dog_bark(polly) + assert msg(excinfo.value) == """ + dog_bark(): incompatible function arguments. The following argument types are supported: + 1. (arg0: m.class_.Dog) -> str + + Invoked with: + """ + + with pytest.raises(TypeError) as excinfo: + m.Chimera("lion", "goat") + assert "No constructor defined!" in str(excinfo.value) + + +def test_automatic_upcasting(): + assert type(m.return_class_1()).__name__ == "DerivedClass1" + assert type(m.return_class_2()).__name__ == "DerivedClass2" + assert type(m.return_none()).__name__ == "NoneType" + # Repeat these a few times in a random order to ensure no invalid caching is applied + assert type(m.return_class_n(1)).__name__ == "DerivedClass1" + assert type(m.return_class_n(2)).__name__ == "DerivedClass2" + assert type(m.return_class_n(0)).__name__ == "BaseClass" + assert type(m.return_class_n(2)).__name__ == "DerivedClass2" + assert type(m.return_class_n(2)).__name__ == "DerivedClass2" + assert type(m.return_class_n(0)).__name__ == "BaseClass" + assert type(m.return_class_n(1)).__name__ == "DerivedClass1" + + +def test_isinstance(): + objects = [tuple(), dict(), m.Pet("Polly", "parrot")] + [m.Dog("Molly")] * 4 + expected = (True, True, True, True, True, False, False) + assert m.check_instances(objects) == expected + + +def test_mismatched_holder(): + import re + + with pytest.raises(RuntimeError) as excinfo: + m.mismatched_holder_1() + assert re.match('generic_type: type ".*MismatchDerived1" does not have a non-default ' + 'holder type while its base ".*MismatchBase1" does', str(excinfo.value)) + + with pytest.raises(RuntimeError) as excinfo: + m.mismatched_holder_2() + assert re.match('generic_type: type ".*MismatchDerived2" has a non-default holder type ' + 'while its base ".*MismatchBase2" does not', str(excinfo.value)) + + +def test_override_static(): + """#511: problem with inheritance + overwritten def_static""" + b = m.MyBase.make() + d1 = m.MyDerived.make2() + d2 = m.MyDerived.make() + + assert isinstance(b, m.MyBase) + assert isinstance(d1, m.MyDerived) + assert isinstance(d2, m.MyDerived) + + +def test_implicit_conversion_life_support(): + """Ensure the lifetime of temporary objects created for implicit conversions""" + assert m.implicitly_convert_argument(UserType(5)) == 5 + assert m.implicitly_convert_variable(UserType(5)) == 5 + + assert "outside a bound function" in m.implicitly_convert_variable_fail(UserType(5)) + + +def test_operator_new_delete(capture): + """Tests that class-specific operator new/delete functions are invoked""" + + class SubAliased(m.AliasedHasOpNewDelSize): + pass + + with capture: + a = m.HasOpNewDel() + b = m.HasOpNewDelSize() + d = m.HasOpNewDelBoth() + assert capture == """ + A new 8 + B new 4 + D new 32 + """ + sz_alias = str(m.AliasedHasOpNewDelSize.size_alias) + sz_noalias = str(m.AliasedHasOpNewDelSize.size_noalias) + with capture: + c = m.AliasedHasOpNewDelSize() + c2 = SubAliased() + assert capture == ( + "C new " + sz_noalias + "\n" + + "C new " + sz_alias + "\n" + ) + + with capture: + del a + pytest.gc_collect() + del b + pytest.gc_collect() + del d + pytest.gc_collect() + assert capture == """ + A delete + B delete 4 + D delete + """ + + with capture: + del c + pytest.gc_collect() + del c2 + pytest.gc_collect() + assert capture == ( + "C delete " + sz_noalias + "\n" + + "C delete " + sz_alias + "\n" + ) + + +def test_bind_protected_functions(): + """Expose protected member functions to Python using a helper class""" + a = m.ProtectedA() + assert a.foo() == 42 + + b = m.ProtectedB() + assert b.foo() == 42 + + class C(m.ProtectedB): + def __init__(self): + m.ProtectedB.__init__(self) + + def foo(self): + return 0 + + c = C() + assert c.foo() == 0 + + +def test_brace_initialization(): + """ Tests that simple POD classes can be constructed using C++11 brace initialization """ + a = m.BraceInitialization(123, "test") + assert a.field1 == 123 + assert a.field2 == "test" + + # Tests that a non-simple class doesn't get brace initialization (if the + # class defines an initializer_list constructor, in particular, it would + # win over the expected constructor). + b = m.NoBraceInitialization([123, 456]) + assert b.vec == [123, 456] + + +@pytest.unsupported_on_pypy +def test_class_refcount(): + """Instances must correctly increase/decrease the reference count of their types (#1029)""" + from sys import getrefcount + + class PyDog(m.Dog): + pass + + for cls in m.Dog, PyDog: + refcount_1 = getrefcount(cls) + molly = [cls("Molly") for _ in range(10)] + refcount_2 = getrefcount(cls) + + del molly + pytest.gc_collect() + refcount_3 = getrefcount(cls) + + assert refcount_1 == refcount_3 + assert refcount_2 > refcount_1 + + +def test_reentrant_implicit_conversion_failure(msg): + # ensure that there is no runaway reentrant implicit conversion (#1035) + with pytest.raises(TypeError) as excinfo: + m.BogusImplicitConversion(0) + assert msg(excinfo.value) == ''' + __init__(): incompatible constructor arguments. The following argument types are supported: + 1. m.class_.BogusImplicitConversion(arg0: m.class_.BogusImplicitConversion) + + Invoked with: 0 + ''' + + +def test_error_after_conversions(): + with pytest.raises(TypeError) as exc_info: + m.test_error_after_conversions("hello") + assert str(exc_info.value).startswith( + "Unable to convert function return value to a Python type!") + + +def test_aligned(): + if hasattr(m, "Aligned"): + p = m.Aligned().ptr() + assert p % 1024 == 0 diff --git a/wrap/python/pybind11/tests/test_cmake_build/CMakeLists.txt b/wrap/python/pybind11/tests/test_cmake_build/CMakeLists.txt new file mode 100644 index 000000000..c9b5fcb2e --- /dev/null +++ b/wrap/python/pybind11/tests/test_cmake_build/CMakeLists.txt @@ -0,0 +1,58 @@ +add_custom_target(test_cmake_build) + +if(CMAKE_VERSION VERSION_LESS 3.1) + # 3.0 needed for interface library for subdirectory_target/installed_target + # 3.1 needed for cmake -E env for testing + return() +endif() + +include(CMakeParseArguments) +function(pybind11_add_build_test name) + cmake_parse_arguments(ARG "INSTALL" "" "" ${ARGN}) + + set(build_options "-DCMAKE_PREFIX_PATH=${PROJECT_BINARY_DIR}/mock_install" + "-DCMAKE_CXX_COMPILER=${CMAKE_CXX_COMPILER}" + "-DPYTHON_EXECUTABLE:FILEPATH=${PYTHON_EXECUTABLE}" + "-DPYBIND11_CPP_STANDARD=${PYBIND11_CPP_STANDARD}") + if(NOT ARG_INSTALL) + list(APPEND build_options "-DPYBIND11_PROJECT_DIR=${PROJECT_SOURCE_DIR}") + endif() + + add_custom_target(test_${name} ${CMAKE_CTEST_COMMAND} + --quiet --output-log ${name}.log + --build-and-test "${CMAKE_CURRENT_SOURCE_DIR}/${name}" + "${CMAKE_CURRENT_BINARY_DIR}/${name}" + --build-config Release + --build-noclean + --build-generator ${CMAKE_GENERATOR} + $<$:--build-generator-platform> ${CMAKE_GENERATOR_PLATFORM} + --build-makeprogram ${CMAKE_MAKE_PROGRAM} + --build-target check + --build-options ${build_options} + ) + if(ARG_INSTALL) + add_dependencies(test_${name} mock_install) + endif() + add_dependencies(test_cmake_build test_${name}) +endfunction() + +pybind11_add_build_test(subdirectory_function) +pybind11_add_build_test(subdirectory_target) +if(NOT ${PYTHON_MODULE_EXTENSION} MATCHES "pypy") + pybind11_add_build_test(subdirectory_embed) +endif() + +if(PYBIND11_INSTALL) + add_custom_target(mock_install ${CMAKE_COMMAND} + "-DCMAKE_INSTALL_PREFIX=${PROJECT_BINARY_DIR}/mock_install" + -P "${PROJECT_BINARY_DIR}/cmake_install.cmake" + ) + + pybind11_add_build_test(installed_function INSTALL) + pybind11_add_build_test(installed_target INSTALL) + if(NOT ${PYTHON_MODULE_EXTENSION} MATCHES "pypy") + pybind11_add_build_test(installed_embed INSTALL) + endif() +endif() + +add_dependencies(check test_cmake_build) diff --git a/wrap/python/pybind11/tests/test_cmake_build/embed.cpp b/wrap/python/pybind11/tests/test_cmake_build/embed.cpp new file mode 100644 index 000000000..b9581d2fd --- /dev/null +++ b/wrap/python/pybind11/tests/test_cmake_build/embed.cpp @@ -0,0 +1,21 @@ +#include +namespace py = pybind11; + +PYBIND11_EMBEDDED_MODULE(test_cmake_build, m) { + m.def("add", [](int i, int j) { return i + j; }); +} + +int main(int argc, char *argv[]) { + if (argc != 2) + throw std::runtime_error("Expected test.py file as the first argument"); + auto test_py_file = argv[1]; + + py::scoped_interpreter guard{}; + + auto m = py::module::import("test_cmake_build"); + if (m.attr("add")(1, 2).cast() != 3) + throw std::runtime_error("embed.cpp failed"); + + py::module::import("sys").attr("argv") = py::make_tuple("test.py", "embed.cpp"); + py::eval_file(test_py_file, py::globals()); +} diff --git a/wrap/python/pybind11/tests/test_cmake_build/installed_embed/CMakeLists.txt b/wrap/python/pybind11/tests/test_cmake_build/installed_embed/CMakeLists.txt new file mode 100644 index 000000000..f7fc09c21 --- /dev/null +++ b/wrap/python/pybind11/tests/test_cmake_build/installed_embed/CMakeLists.txt @@ -0,0 +1,15 @@ +cmake_minimum_required(VERSION 3.0) +project(test_installed_embed CXX) + +set(CMAKE_MODULE_PATH "") +find_package(pybind11 CONFIG REQUIRED) +message(STATUS "Found pybind11 v${pybind11_VERSION}: ${pybind11_INCLUDE_DIRS}") + +add_executable(test_cmake_build ../embed.cpp) +target_link_libraries(test_cmake_build PRIVATE pybind11::embed) + +# Do not treat includes from IMPORTED target as SYSTEM (Python headers in pybind11::embed). +# This may be needed to resolve header conflicts, e.g. between Python release and debug headers. +set_target_properties(test_cmake_build PROPERTIES NO_SYSTEM_FROM_IMPORTED ON) + +add_custom_target(check $ ${PROJECT_SOURCE_DIR}/../test.py) diff --git a/wrap/python/pybind11/tests/test_cmake_build/installed_function/CMakeLists.txt b/wrap/python/pybind11/tests/test_cmake_build/installed_function/CMakeLists.txt new file mode 100644 index 000000000..e0c20a8a3 --- /dev/null +++ b/wrap/python/pybind11/tests/test_cmake_build/installed_function/CMakeLists.txt @@ -0,0 +1,12 @@ +cmake_minimum_required(VERSION 2.8.12) +project(test_installed_module CXX) + +set(CMAKE_MODULE_PATH "") + +find_package(pybind11 CONFIG REQUIRED) +message(STATUS "Found pybind11 v${pybind11_VERSION}: ${pybind11_INCLUDE_DIRS}") + +pybind11_add_module(test_cmake_build SHARED NO_EXTRAS ../main.cpp) + +add_custom_target(check ${CMAKE_COMMAND} -E env PYTHONPATH=$ + ${PYTHON_EXECUTABLE} ${PROJECT_SOURCE_DIR}/../test.py ${PROJECT_NAME}) diff --git a/wrap/python/pybind11/tests/test_cmake_build/installed_target/CMakeLists.txt b/wrap/python/pybind11/tests/test_cmake_build/installed_target/CMakeLists.txt new file mode 100644 index 000000000..cd3ae6f7d --- /dev/null +++ b/wrap/python/pybind11/tests/test_cmake_build/installed_target/CMakeLists.txt @@ -0,0 +1,22 @@ +cmake_minimum_required(VERSION 3.0) +project(test_installed_target CXX) + +set(CMAKE_MODULE_PATH "") + +find_package(pybind11 CONFIG REQUIRED) +message(STATUS "Found pybind11 v${pybind11_VERSION}: ${pybind11_INCLUDE_DIRS}") + +add_library(test_cmake_build MODULE ../main.cpp) + +target_link_libraries(test_cmake_build PRIVATE pybind11::module) + +# make sure result is, for example, test_installed_target.so, not libtest_installed_target.dylib +set_target_properties(test_cmake_build PROPERTIES PREFIX "${PYTHON_MODULE_PREFIX}" + SUFFIX "${PYTHON_MODULE_EXTENSION}") + +# Do not treat includes from IMPORTED target as SYSTEM (Python headers in pybind11::module). +# This may be needed to resolve header conflicts, e.g. between Python release and debug headers. +set_target_properties(test_cmake_build PROPERTIES NO_SYSTEM_FROM_IMPORTED ON) + +add_custom_target(check ${CMAKE_COMMAND} -E env PYTHONPATH=$ + ${PYTHON_EXECUTABLE} ${PROJECT_SOURCE_DIR}/../test.py ${PROJECT_NAME}) diff --git a/wrap/python/pybind11/tests/test_cmake_build/main.cpp b/wrap/python/pybind11/tests/test_cmake_build/main.cpp new file mode 100644 index 000000000..e30f2c4b9 --- /dev/null +++ b/wrap/python/pybind11/tests/test_cmake_build/main.cpp @@ -0,0 +1,6 @@ +#include +namespace py = pybind11; + +PYBIND11_MODULE(test_cmake_build, m) { + m.def("add", [](int i, int j) { return i + j; }); +} diff --git a/wrap/python/pybind11/tests/test_cmake_build/subdirectory_embed/CMakeLists.txt b/wrap/python/pybind11/tests/test_cmake_build/subdirectory_embed/CMakeLists.txt new file mode 100644 index 000000000..88ba60dd5 --- /dev/null +++ b/wrap/python/pybind11/tests/test_cmake_build/subdirectory_embed/CMakeLists.txt @@ -0,0 +1,25 @@ +cmake_minimum_required(VERSION 3.0) +project(test_subdirectory_embed CXX) + +set(PYBIND11_INSTALL ON CACHE BOOL "") +set(PYBIND11_EXPORT_NAME test_export) + +add_subdirectory(${PYBIND11_PROJECT_DIR} pybind11) + +# Test basic target functionality +add_executable(test_cmake_build ../embed.cpp) +target_link_libraries(test_cmake_build PRIVATE pybind11::embed) + +add_custom_target(check $ ${PROJECT_SOURCE_DIR}/../test.py) + +# Test custom export group -- PYBIND11_EXPORT_NAME +add_library(test_embed_lib ../embed.cpp) +target_link_libraries(test_embed_lib PRIVATE pybind11::embed) + +install(TARGETS test_embed_lib + EXPORT test_export + ARCHIVE DESTINATION bin + LIBRARY DESTINATION lib + RUNTIME DESTINATION lib) +install(EXPORT test_export + DESTINATION lib/cmake/test_export/test_export-Targets.cmake) diff --git a/wrap/python/pybind11/tests/test_cmake_build/subdirectory_function/CMakeLists.txt b/wrap/python/pybind11/tests/test_cmake_build/subdirectory_function/CMakeLists.txt new file mode 100644 index 000000000..278007aeb --- /dev/null +++ b/wrap/python/pybind11/tests/test_cmake_build/subdirectory_function/CMakeLists.txt @@ -0,0 +1,8 @@ +cmake_minimum_required(VERSION 2.8.12) +project(test_subdirectory_module CXX) + +add_subdirectory(${PYBIND11_PROJECT_DIR} pybind11) +pybind11_add_module(test_cmake_build THIN_LTO ../main.cpp) + +add_custom_target(check ${CMAKE_COMMAND} -E env PYTHONPATH=$ + ${PYTHON_EXECUTABLE} ${PROJECT_SOURCE_DIR}/../test.py ${PROJECT_NAME}) diff --git a/wrap/python/pybind11/tests/test_cmake_build/subdirectory_target/CMakeLists.txt b/wrap/python/pybind11/tests/test_cmake_build/subdirectory_target/CMakeLists.txt new file mode 100644 index 000000000..6b142d62a --- /dev/null +++ b/wrap/python/pybind11/tests/test_cmake_build/subdirectory_target/CMakeLists.txt @@ -0,0 +1,15 @@ +cmake_minimum_required(VERSION 3.0) +project(test_subdirectory_target CXX) + +add_subdirectory(${PYBIND11_PROJECT_DIR} pybind11) + +add_library(test_cmake_build MODULE ../main.cpp) + +target_link_libraries(test_cmake_build PRIVATE pybind11::module) + +# make sure result is, for example, test_installed_target.so, not libtest_installed_target.dylib +set_target_properties(test_cmake_build PROPERTIES PREFIX "${PYTHON_MODULE_PREFIX}" + SUFFIX "${PYTHON_MODULE_EXTENSION}") + +add_custom_target(check ${CMAKE_COMMAND} -E env PYTHONPATH=$ + ${PYTHON_EXECUTABLE} ${PROJECT_SOURCE_DIR}/../test.py ${PROJECT_NAME}) diff --git a/wrap/python/pybind11/tests/test_cmake_build/test.py b/wrap/python/pybind11/tests/test_cmake_build/test.py new file mode 100644 index 000000000..1467a61dc --- /dev/null +++ b/wrap/python/pybind11/tests/test_cmake_build/test.py @@ -0,0 +1,5 @@ +import sys +import test_cmake_build + +assert test_cmake_build.add(1, 2) == 3 +print("{} imports, runs, and adds: 1 + 2 = 3".format(sys.argv[1])) diff --git a/wrap/python/pybind11/tests/test_constants_and_functions.cpp b/wrap/python/pybind11/tests/test_constants_and_functions.cpp new file mode 100644 index 000000000..e8ec74b7b --- /dev/null +++ b/wrap/python/pybind11/tests/test_constants_and_functions.cpp @@ -0,0 +1,127 @@ +/* + tests/test_constants_and_functions.cpp -- global constants and functions, enumerations, raw byte strings + + Copyright (c) 2016 Wenzel Jakob + + All rights reserved. Use of this source code is governed by a + BSD-style license that can be found in the LICENSE file. +*/ + +#include "pybind11_tests.h" + +enum MyEnum { EFirstEntry = 1, ESecondEntry }; + +std::string test_function1() { + return "test_function()"; +} + +std::string test_function2(MyEnum k) { + return "test_function(enum=" + std::to_string(k) + ")"; +} + +std::string test_function3(int i) { + return "test_function(" + std::to_string(i) + ")"; +} + +py::str test_function4() { return "test_function()"; } +py::str test_function4(char *) { return "test_function(char *)"; } +py::str test_function4(int, float) { return "test_function(int, float)"; } +py::str test_function4(float, int) { return "test_function(float, int)"; } + +py::bytes return_bytes() { + const char *data = "\x01\x00\x02\x00"; + return std::string(data, 4); +} + +std::string print_bytes(py::bytes bytes) { + std::string ret = "bytes["; + const auto value = static_cast(bytes); + for (size_t i = 0; i < value.length(); ++i) { + ret += std::to_string(static_cast(value[i])) + " "; + } + ret.back() = ']'; + return ret; +} + +// Test that we properly handle C++17 exception specifiers (which are part of the function signature +// in C++17). These should all still work before C++17, but don't affect the function signature. +namespace test_exc_sp { +int f1(int x) noexcept { return x+1; } +int f2(int x) noexcept(true) { return x+2; } +int f3(int x) noexcept(false) { return x+3; } +#if defined(__GNUG__) +# pragma GCC diagnostic push +# pragma GCC diagnostic ignored "-Wdeprecated" +#endif +int f4(int x) throw() { return x+4; } // Deprecated equivalent to noexcept(true) +#if defined(__GNUG__) +# pragma GCC diagnostic pop +#endif +struct C { + int m1(int x) noexcept { return x-1; } + int m2(int x) const noexcept { return x-2; } + int m3(int x) noexcept(true) { return x-3; } + int m4(int x) const noexcept(true) { return x-4; } + int m5(int x) noexcept(false) { return x-5; } + int m6(int x) const noexcept(false) { return x-6; } +#if defined(__GNUG__) +# pragma GCC diagnostic push +# pragma GCC diagnostic ignored "-Wdeprecated" +#endif + int m7(int x) throw() { return x-7; } + int m8(int x) const throw() { return x-8; } +#if defined(__GNUG__) +# pragma GCC diagnostic pop +#endif +}; +} + + +TEST_SUBMODULE(constants_and_functions, m) { + // test_constants + m.attr("some_constant") = py::int_(14); + + // test_function_overloading + m.def("test_function", &test_function1); + m.def("test_function", &test_function2); + m.def("test_function", &test_function3); + +#if defined(PYBIND11_OVERLOAD_CAST) + m.def("test_function", py::overload_cast<>(&test_function4)); + m.def("test_function", py::overload_cast(&test_function4)); + m.def("test_function", py::overload_cast(&test_function4)); + m.def("test_function", py::overload_cast(&test_function4)); +#else + m.def("test_function", static_cast(&test_function4)); + m.def("test_function", static_cast(&test_function4)); + m.def("test_function", static_cast(&test_function4)); + m.def("test_function", static_cast(&test_function4)); +#endif + + py::enum_(m, "MyEnum") + .value("EFirstEntry", EFirstEntry) + .value("ESecondEntry", ESecondEntry) + .export_values(); + + // test_bytes + m.def("return_bytes", &return_bytes); + m.def("print_bytes", &print_bytes); + + // test_exception_specifiers + using namespace test_exc_sp; + py::class_(m, "C") + .def(py::init<>()) + .def("m1", &C::m1) + .def("m2", &C::m2) + .def("m3", &C::m3) + .def("m4", &C::m4) + .def("m5", &C::m5) + .def("m6", &C::m6) + .def("m7", &C::m7) + .def("m8", &C::m8) + ; + m.def("f1", f1); + m.def("f2", f2); + m.def("f3", f3); + m.def("f4", f4); +} diff --git a/wrap/python/pybind11/tests/test_constants_and_functions.py b/wrap/python/pybind11/tests/test_constants_and_functions.py new file mode 100644 index 000000000..472682d61 --- /dev/null +++ b/wrap/python/pybind11/tests/test_constants_and_functions.py @@ -0,0 +1,39 @@ +from pybind11_tests import constants_and_functions as m + + +def test_constants(): + assert m.some_constant == 14 + + +def test_function_overloading(): + assert m.test_function() == "test_function()" + assert m.test_function(7) == "test_function(7)" + assert m.test_function(m.MyEnum.EFirstEntry) == "test_function(enum=1)" + assert m.test_function(m.MyEnum.ESecondEntry) == "test_function(enum=2)" + + assert m.test_function() == "test_function()" + assert m.test_function("abcd") == "test_function(char *)" + assert m.test_function(1, 1.0) == "test_function(int, float)" + assert m.test_function(1, 1.0) == "test_function(int, float)" + assert m.test_function(2.0, 2) == "test_function(float, int)" + + +def test_bytes(): + assert m.print_bytes(m.return_bytes()) == "bytes[1 0 2 0]" + + +def test_exception_specifiers(): + c = m.C() + assert c.m1(2) == 1 + assert c.m2(3) == 1 + assert c.m3(5) == 2 + assert c.m4(7) == 3 + assert c.m5(10) == 5 + assert c.m6(14) == 8 + assert c.m7(20) == 13 + assert c.m8(29) == 21 + + assert m.f1(33) == 34 + assert m.f2(53) == 55 + assert m.f3(86) == 89 + assert m.f4(140) == 144 diff --git a/wrap/python/pybind11/tests/test_copy_move.cpp b/wrap/python/pybind11/tests/test_copy_move.cpp new file mode 100644 index 000000000..98d5e0a0b --- /dev/null +++ b/wrap/python/pybind11/tests/test_copy_move.cpp @@ -0,0 +1,213 @@ +/* + tests/test_copy_move_policies.cpp -- 'copy' and 'move' return value policies + and related tests + + Copyright (c) 2016 Ben North + + All rights reserved. Use of this source code is governed by a + BSD-style license that can be found in the LICENSE file. +*/ + +#include "pybind11_tests.h" +#include "constructor_stats.h" +#include + +template +struct empty { + static const derived& get_one() { return instance_; } + static derived instance_; +}; + +struct lacking_copy_ctor : public empty { + lacking_copy_ctor() {} + lacking_copy_ctor(const lacking_copy_ctor& other) = delete; +}; + +template <> lacking_copy_ctor empty::instance_ = {}; + +struct lacking_move_ctor : public empty { + lacking_move_ctor() {} + lacking_move_ctor(const lacking_move_ctor& other) = delete; + lacking_move_ctor(lacking_move_ctor&& other) = delete; +}; + +template <> lacking_move_ctor empty::instance_ = {}; + +/* Custom type caster move/copy test classes */ +class MoveOnlyInt { +public: + MoveOnlyInt() { print_default_created(this); } + MoveOnlyInt(int v) : value{std::move(v)} { print_created(this, value); } + MoveOnlyInt(MoveOnlyInt &&m) { print_move_created(this, m.value); std::swap(value, m.value); } + MoveOnlyInt &operator=(MoveOnlyInt &&m) { print_move_assigned(this, m.value); std::swap(value, m.value); return *this; } + MoveOnlyInt(const MoveOnlyInt &) = delete; + MoveOnlyInt &operator=(const MoveOnlyInt &) = delete; + ~MoveOnlyInt() { print_destroyed(this); } + + int value; +}; +class MoveOrCopyInt { +public: + MoveOrCopyInt() { print_default_created(this); } + MoveOrCopyInt(int v) : value{std::move(v)} { print_created(this, value); } + MoveOrCopyInt(MoveOrCopyInt &&m) { print_move_created(this, m.value); std::swap(value, m.value); } + MoveOrCopyInt &operator=(MoveOrCopyInt &&m) { print_move_assigned(this, m.value); std::swap(value, m.value); return *this; } + MoveOrCopyInt(const MoveOrCopyInt &c) { print_copy_created(this, c.value); value = c.value; } + MoveOrCopyInt &operator=(const MoveOrCopyInt &c) { print_copy_assigned(this, c.value); value = c.value; return *this; } + ~MoveOrCopyInt() { print_destroyed(this); } + + int value; +}; +class CopyOnlyInt { +public: + CopyOnlyInt() { print_default_created(this); } + CopyOnlyInt(int v) : value{std::move(v)} { print_created(this, value); } + CopyOnlyInt(const CopyOnlyInt &c) { print_copy_created(this, c.value); value = c.value; } + CopyOnlyInt &operator=(const CopyOnlyInt &c) { print_copy_assigned(this, c.value); value = c.value; return *this; } + ~CopyOnlyInt() { print_destroyed(this); } + + int value; +}; +NAMESPACE_BEGIN(pybind11) +NAMESPACE_BEGIN(detail) +template <> struct type_caster { + PYBIND11_TYPE_CASTER(MoveOnlyInt, _("MoveOnlyInt")); + bool load(handle src, bool) { value = MoveOnlyInt(src.cast()); return true; } + static handle cast(const MoveOnlyInt &m, return_value_policy r, handle p) { return pybind11::cast(m.value, r, p); } +}; + +template <> struct type_caster { + PYBIND11_TYPE_CASTER(MoveOrCopyInt, _("MoveOrCopyInt")); + bool load(handle src, bool) { value = MoveOrCopyInt(src.cast()); return true; } + static handle cast(const MoveOrCopyInt &m, return_value_policy r, handle p) { return pybind11::cast(m.value, r, p); } +}; + +template <> struct type_caster { +protected: + CopyOnlyInt value; +public: + static constexpr auto name = _("CopyOnlyInt"); + bool load(handle src, bool) { value = CopyOnlyInt(src.cast()); return true; } + static handle cast(const CopyOnlyInt &m, return_value_policy r, handle p) { return pybind11::cast(m.value, r, p); } + static handle cast(const CopyOnlyInt *src, return_value_policy policy, handle parent) { + if (!src) return none().release(); + return cast(*src, policy, parent); + } + operator CopyOnlyInt*() { return &value; } + operator CopyOnlyInt&() { return value; } + template using cast_op_type = pybind11::detail::cast_op_type; +}; +NAMESPACE_END(detail) +NAMESPACE_END(pybind11) + +TEST_SUBMODULE(copy_move_policies, m) { + // test_lacking_copy_ctor + py::class_(m, "lacking_copy_ctor") + .def_static("get_one", &lacking_copy_ctor::get_one, + py::return_value_policy::copy); + // test_lacking_move_ctor + py::class_(m, "lacking_move_ctor") + .def_static("get_one", &lacking_move_ctor::get_one, + py::return_value_policy::move); + + // test_move_and_copy_casts + m.def("move_and_copy_casts", [](py::object o) { + int r = 0; + r += py::cast(o).value; /* moves */ + r += py::cast(o).value; /* moves */ + r += py::cast(o).value; /* copies */ + MoveOrCopyInt m1(py::cast(o)); /* moves */ + MoveOnlyInt m2(py::cast(o)); /* moves */ + CopyOnlyInt m3(py::cast(o)); /* copies */ + r += m1.value + m2.value + m3.value; + + return r; + }); + + // test_move_and_copy_loads + m.def("move_only", [](MoveOnlyInt m) { return m.value; }); + m.def("move_or_copy", [](MoveOrCopyInt m) { return m.value; }); + m.def("copy_only", [](CopyOnlyInt m) { return m.value; }); + m.def("move_pair", [](std::pair p) { + return p.first.value + p.second.value; + }); + m.def("move_tuple", [](std::tuple t) { + return std::get<0>(t).value + std::get<1>(t).value + std::get<2>(t).value; + }); + m.def("copy_tuple", [](std::tuple t) { + return std::get<0>(t).value + std::get<1>(t).value; + }); + m.def("move_copy_nested", [](std::pair>, MoveOrCopyInt>> x) { + return x.first.value + std::get<0>(x.second.first).value + std::get<1>(x.second.first).value + + std::get<0>(std::get<2>(x.second.first)).value + x.second.second.value; + }); + m.def("move_and_copy_cstats", []() { + ConstructorStats::gc(); + // Reset counts to 0 so that previous tests don't affect later ones: + auto &mc = ConstructorStats::get(); + mc.move_assignments = mc.move_constructions = mc.copy_assignments = mc.copy_constructions = 0; + auto &mo = ConstructorStats::get(); + mo.move_assignments = mo.move_constructions = mo.copy_assignments = mo.copy_constructions = 0; + auto &co = ConstructorStats::get(); + co.move_assignments = co.move_constructions = co.copy_assignments = co.copy_constructions = 0; + py::dict d; + d["MoveOrCopyInt"] = py::cast(mc, py::return_value_policy::reference); + d["MoveOnlyInt"] = py::cast(mo, py::return_value_policy::reference); + d["CopyOnlyInt"] = py::cast(co, py::return_value_policy::reference); + return d; + }); +#ifdef PYBIND11_HAS_OPTIONAL + // test_move_and_copy_load_optional + m.attr("has_optional") = true; + m.def("move_optional", [](std::optional o) { + return o->value; + }); + m.def("move_or_copy_optional", [](std::optional o) { + return o->value; + }); + m.def("copy_optional", [](std::optional o) { + return o->value; + }); + m.def("move_optional_tuple", [](std::optional> x) { + return std::get<0>(*x).value + std::get<1>(*x).value + std::get<2>(*x).value; + }); +#else + m.attr("has_optional") = false; +#endif + + // #70 compilation issue if operator new is not public + struct PrivateOpNew { + int value = 1; + private: +#if defined(_MSC_VER) +# pragma warning(disable: 4822) // warning C4822: local class member function does not have a body +#endif + void *operator new(size_t bytes); + }; + py::class_(m, "PrivateOpNew").def_readonly("value", &PrivateOpNew::value); + m.def("private_op_new_value", []() { return PrivateOpNew(); }); + m.def("private_op_new_reference", []() -> const PrivateOpNew & { + static PrivateOpNew x{}; + return x; + }, py::return_value_policy::reference); + + // test_move_fallback + // #389: rvp::move should fall-through to copy on non-movable objects + struct MoveIssue1 { + int v; + MoveIssue1(int v) : v{v} {} + MoveIssue1(const MoveIssue1 &c) = default; + MoveIssue1(MoveIssue1 &&) = delete; + }; + py::class_(m, "MoveIssue1").def(py::init()).def_readwrite("value", &MoveIssue1::v); + + struct MoveIssue2 { + int v; + MoveIssue2(int v) : v{v} {} + MoveIssue2(MoveIssue2 &&) = default; + }; + py::class_(m, "MoveIssue2").def(py::init()).def_readwrite("value", &MoveIssue2::v); + + m.def("get_moveissue1", [](int i) { return new MoveIssue1(i); }, py::return_value_policy::move); + m.def("get_moveissue2", [](int i) { return MoveIssue2(i); }, py::return_value_policy::move); +} diff --git a/wrap/python/pybind11/tests/test_copy_move.py b/wrap/python/pybind11/tests/test_copy_move.py new file mode 100644 index 000000000..aff2d99f2 --- /dev/null +++ b/wrap/python/pybind11/tests/test_copy_move.py @@ -0,0 +1,112 @@ +import pytest +from pybind11_tests import copy_move_policies as m + + +def test_lacking_copy_ctor(): + with pytest.raises(RuntimeError) as excinfo: + m.lacking_copy_ctor.get_one() + assert "the object is non-copyable!" in str(excinfo.value) + + +def test_lacking_move_ctor(): + with pytest.raises(RuntimeError) as excinfo: + m.lacking_move_ctor.get_one() + assert "the object is neither movable nor copyable!" in str(excinfo.value) + + +def test_move_and_copy_casts(): + """Cast some values in C++ via custom type casters and count the number of moves/copies.""" + + cstats = m.move_and_copy_cstats() + c_m, c_mc, c_c = cstats["MoveOnlyInt"], cstats["MoveOrCopyInt"], cstats["CopyOnlyInt"] + + # The type move constructions/assignments below each get incremented: the move assignment comes + # from the type_caster load; the move construction happens when extracting that via a cast or + # loading into an argument. + assert m.move_and_copy_casts(3) == 18 + assert c_m.copy_assignments + c_m.copy_constructions == 0 + assert c_m.move_assignments == 2 + assert c_m.move_constructions >= 2 + assert c_mc.alive() == 0 + assert c_mc.copy_assignments + c_mc.copy_constructions == 0 + assert c_mc.move_assignments == 2 + assert c_mc.move_constructions >= 2 + assert c_c.alive() == 0 + assert c_c.copy_assignments == 2 + assert c_c.copy_constructions >= 2 + assert c_m.alive() + c_mc.alive() + c_c.alive() == 0 + + +def test_move_and_copy_loads(): + """Call some functions that load arguments via custom type casters and count the number of + moves/copies.""" + + cstats = m.move_and_copy_cstats() + c_m, c_mc, c_c = cstats["MoveOnlyInt"], cstats["MoveOrCopyInt"], cstats["CopyOnlyInt"] + + assert m.move_only(10) == 10 # 1 move, c_m + assert m.move_or_copy(11) == 11 # 1 move, c_mc + assert m.copy_only(12) == 12 # 1 copy, c_c + assert m.move_pair((13, 14)) == 27 # 1 c_m move, 1 c_mc move + assert m.move_tuple((15, 16, 17)) == 48 # 2 c_m moves, 1 c_mc move + assert m.copy_tuple((18, 19)) == 37 # 2 c_c copies + # Direct constructions: 2 c_m moves, 2 c_mc moves, 1 c_c copy + # Extra moves/copies when moving pairs/tuples: 3 c_m, 3 c_mc, 2 c_c + assert m.move_copy_nested((1, ((2, 3, (4,)), 5))) == 15 + + assert c_m.copy_assignments + c_m.copy_constructions == 0 + assert c_m.move_assignments == 6 + assert c_m.move_constructions == 9 + assert c_mc.copy_assignments + c_mc.copy_constructions == 0 + assert c_mc.move_assignments == 5 + assert c_mc.move_constructions == 8 + assert c_c.copy_assignments == 4 + assert c_c.copy_constructions == 6 + assert c_m.alive() + c_mc.alive() + c_c.alive() == 0 + + +@pytest.mark.skipif(not m.has_optional, reason='no ') +def test_move_and_copy_load_optional(): + """Tests move/copy loads of std::optional arguments""" + + cstats = m.move_and_copy_cstats() + c_m, c_mc, c_c = cstats["MoveOnlyInt"], cstats["MoveOrCopyInt"], cstats["CopyOnlyInt"] + + # The extra move/copy constructions below come from the std::optional move (which has to move + # its arguments): + assert m.move_optional(10) == 10 # c_m: 1 move assign, 2 move construct + assert m.move_or_copy_optional(11) == 11 # c_mc: 1 move assign, 2 move construct + assert m.copy_optional(12) == 12 # c_c: 1 copy assign, 2 copy construct + # 1 move assign + move construct moves each of c_m, c_mc, 1 c_c copy + # +1 move/copy construct each from moving the tuple + # +1 move/copy construct each from moving the optional (which moves the tuple again) + assert m.move_optional_tuple((3, 4, 5)) == 12 + + assert c_m.copy_assignments + c_m.copy_constructions == 0 + assert c_m.move_assignments == 2 + assert c_m.move_constructions == 5 + assert c_mc.copy_assignments + c_mc.copy_constructions == 0 + assert c_mc.move_assignments == 2 + assert c_mc.move_constructions == 5 + assert c_c.copy_assignments == 2 + assert c_c.copy_constructions == 5 + assert c_m.alive() + c_mc.alive() + c_c.alive() == 0 + + +def test_private_op_new(): + """An object with a private `operator new` cannot be returned by value""" + + with pytest.raises(RuntimeError) as excinfo: + m.private_op_new_value() + assert "the object is neither movable nor copyable" in str(excinfo.value) + + assert m.private_op_new_reference().value == 1 + + +def test_move_fallback(): + """#389: rvp::move should fall-through to copy on non-movable objects""" + + m2 = m.get_moveissue2(2) + assert m2.value == 2 + m1 = m.get_moveissue1(1) + assert m1.value == 1 diff --git a/wrap/python/pybind11/tests/test_docstring_options.cpp b/wrap/python/pybind11/tests/test_docstring_options.cpp new file mode 100644 index 000000000..8c8f79fd5 --- /dev/null +++ b/wrap/python/pybind11/tests/test_docstring_options.cpp @@ -0,0 +1,61 @@ +/* + tests/test_docstring_options.cpp -- generation of docstrings and signatures + + Copyright (c) 2016 Wenzel Jakob + + All rights reserved. Use of this source code is governed by a + BSD-style license that can be found in the LICENSE file. +*/ + +#include "pybind11_tests.h" + +TEST_SUBMODULE(docstring_options, m) { + // test_docstring_options + { + py::options options; + options.disable_function_signatures(); + + m.def("test_function1", [](int, int) {}, py::arg("a"), py::arg("b")); + m.def("test_function2", [](int, int) {}, py::arg("a"), py::arg("b"), "A custom docstring"); + + m.def("test_overloaded1", [](int) {}, py::arg("i"), "Overload docstring"); + m.def("test_overloaded1", [](double) {}, py::arg("d")); + + m.def("test_overloaded2", [](int) {}, py::arg("i"), "overload docstring 1"); + m.def("test_overloaded2", [](double) {}, py::arg("d"), "overload docstring 2"); + + m.def("test_overloaded3", [](int) {}, py::arg("i")); + m.def("test_overloaded3", [](double) {}, py::arg("d"), "Overload docstr"); + + options.enable_function_signatures(); + + m.def("test_function3", [](int, int) {}, py::arg("a"), py::arg("b")); + m.def("test_function4", [](int, int) {}, py::arg("a"), py::arg("b"), "A custom docstring"); + + options.disable_function_signatures().disable_user_defined_docstrings(); + + m.def("test_function5", [](int, int) {}, py::arg("a"), py::arg("b"), "A custom docstring"); + + { + py::options nested_options; + nested_options.enable_user_defined_docstrings(); + m.def("test_function6", [](int, int) {}, py::arg("a"), py::arg("b"), "A custom docstring"); + } + } + + m.def("test_function7", [](int, int) {}, py::arg("a"), py::arg("b"), "A custom docstring"); + + { + py::options options; + options.disable_user_defined_docstrings(); + + struct DocstringTestFoo { + int value; + void setValue(int v) { value = v; } + int getValue() const { return value; } + }; + py::class_(m, "DocstringTestFoo", "This is a class docstring") + .def_property("value_prop", &DocstringTestFoo::getValue, &DocstringTestFoo::setValue, "This is a property docstring") + ; + } +} diff --git a/wrap/python/pybind11/tests/test_docstring_options.py b/wrap/python/pybind11/tests/test_docstring_options.py new file mode 100644 index 000000000..0dbca609e --- /dev/null +++ b/wrap/python/pybind11/tests/test_docstring_options.py @@ -0,0 +1,38 @@ +from pybind11_tests import docstring_options as m + + +def test_docstring_options(): + # options.disable_function_signatures() + assert not m.test_function1.__doc__ + + assert m.test_function2.__doc__ == "A custom docstring" + + # docstring specified on just the first overload definition: + assert m.test_overloaded1.__doc__ == "Overload docstring" + + # docstring on both overloads: + assert m.test_overloaded2.__doc__ == "overload docstring 1\noverload docstring 2" + + # docstring on only second overload: + assert m.test_overloaded3.__doc__ == "Overload docstr" + + # options.enable_function_signatures() + assert m.test_function3.__doc__ .startswith("test_function3(a: int, b: int) -> None") + + assert m.test_function4.__doc__ .startswith("test_function4(a: int, b: int) -> None") + assert m.test_function4.__doc__ .endswith("A custom docstring\n") + + # options.disable_function_signatures() + # options.disable_user_defined_docstrings() + assert not m.test_function5.__doc__ + + # nested options.enable_user_defined_docstrings() + assert m.test_function6.__doc__ == "A custom docstring" + + # RAII destructor + assert m.test_function7.__doc__ .startswith("test_function7(a: int, b: int) -> None") + assert m.test_function7.__doc__ .endswith("A custom docstring\n") + + # Suppression of user-defined docstrings for non-function objects + assert not m.DocstringTestFoo.__doc__ + assert not m.DocstringTestFoo.value_prop.__doc__ diff --git a/wrap/python/pybind11/tests/test_eigen.cpp b/wrap/python/pybind11/tests/test_eigen.cpp new file mode 100644 index 000000000..aba088d72 --- /dev/null +++ b/wrap/python/pybind11/tests/test_eigen.cpp @@ -0,0 +1,329 @@ +/* + tests/eigen.cpp -- automatic conversion of Eigen types + + Copyright (c) 2016 Wenzel Jakob + + All rights reserved. Use of this source code is governed by a + BSD-style license that can be found in the LICENSE file. +*/ + +#include "pybind11_tests.h" +#include "constructor_stats.h" +#include +#include + +#if defined(_MSC_VER) +# pragma warning(disable: 4996) // C4996: std::unary_negation is deprecated +#endif + +#include + +using MatrixXdR = Eigen::Matrix; + + + +// Sets/resets a testing reference matrix to have values of 10*r + c, where r and c are the +// (1-based) row/column number. +template void reset_ref(M &x) { + for (int i = 0; i < x.rows(); i++) for (int j = 0; j < x.cols(); j++) + x(i, j) = 11 + 10*i + j; +} + +// Returns a static, column-major matrix +Eigen::MatrixXd &get_cm() { + static Eigen::MatrixXd *x; + if (!x) { + x = new Eigen::MatrixXd(3, 3); + reset_ref(*x); + } + return *x; +} +// Likewise, but row-major +MatrixXdR &get_rm() { + static MatrixXdR *x; + if (!x) { + x = new MatrixXdR(3, 3); + reset_ref(*x); + } + return *x; +} +// Resets the values of the static matrices returned by get_cm()/get_rm() +void reset_refs() { + reset_ref(get_cm()); + reset_ref(get_rm()); +} + +// Returns element 2,1 from a matrix (used to test copy/nocopy) +double get_elem(Eigen::Ref m) { return m(2, 1); }; + + +// Returns a matrix with 10*r + 100*c added to each matrix element (to help test that the matrix +// reference is referencing rows/columns correctly). +template Eigen::MatrixXd adjust_matrix(MatrixArgType m) { + Eigen::MatrixXd ret(m); + for (int c = 0; c < m.cols(); c++) for (int r = 0; r < m.rows(); r++) + ret(r, c) += 10*r + 100*c; + return ret; +} + +struct CustomOperatorNew { + CustomOperatorNew() = default; + + Eigen::Matrix4d a = Eigen::Matrix4d::Zero(); + Eigen::Matrix4d b = Eigen::Matrix4d::Identity(); + + EIGEN_MAKE_ALIGNED_OPERATOR_NEW; +}; + +TEST_SUBMODULE(eigen, m) { + using FixedMatrixR = Eigen::Matrix; + using FixedMatrixC = Eigen::Matrix; + using DenseMatrixR = Eigen::Matrix; + using DenseMatrixC = Eigen::Matrix; + using FourRowMatrixC = Eigen::Matrix; + using FourColMatrixC = Eigen::Matrix; + using FourRowMatrixR = Eigen::Matrix; + using FourColMatrixR = Eigen::Matrix; + using SparseMatrixR = Eigen::SparseMatrix; + using SparseMatrixC = Eigen::SparseMatrix; + + m.attr("have_eigen") = true; + + // various tests + m.def("double_col", [](const Eigen::VectorXf &x) -> Eigen::VectorXf { return 2.0f * x; }); + m.def("double_row", [](const Eigen::RowVectorXf &x) -> Eigen::RowVectorXf { return 2.0f * x; }); + m.def("double_complex", [](const Eigen::VectorXcf &x) -> Eigen::VectorXcf { return 2.0f * x; }); + m.def("double_threec", [](py::EigenDRef x) { x *= 2; }); + m.def("double_threer", [](py::EigenDRef x) { x *= 2; }); + m.def("double_mat_cm", [](Eigen::MatrixXf x) -> Eigen::MatrixXf { return 2.0f * x; }); + m.def("double_mat_rm", [](DenseMatrixR x) -> DenseMatrixR { return 2.0f * x; }); + + // test_eigen_ref_to_python + // Different ways of passing via Eigen::Ref; the first and second are the Eigen-recommended + m.def("cholesky1", [](Eigen::Ref x) -> Eigen::MatrixXd { return x.llt().matrixL(); }); + m.def("cholesky2", [](const Eigen::Ref &x) -> Eigen::MatrixXd { return x.llt().matrixL(); }); + m.def("cholesky3", [](const Eigen::Ref &x) -> Eigen::MatrixXd { return x.llt().matrixL(); }); + m.def("cholesky4", [](Eigen::Ref x) -> Eigen::MatrixXd { return x.llt().matrixL(); }); + + // test_eigen_ref_mutators + // Mutators: these add some value to the given element using Eigen, but Eigen should be mapping into + // the numpy array data and so the result should show up there. There are three versions: one that + // works on a contiguous-row matrix (numpy's default), one for a contiguous-column matrix, and one + // for any matrix. + auto add_rm = [](Eigen::Ref x, int r, int c, double v) { x(r,c) += v; }; + auto add_cm = [](Eigen::Ref x, int r, int c, double v) { x(r,c) += v; }; + + // Mutators (Eigen maps into numpy variables): + m.def("add_rm", add_rm); // Only takes row-contiguous + m.def("add_cm", add_cm); // Only takes column-contiguous + // Overloaded versions that will accept either row or column contiguous: + m.def("add1", add_rm); + m.def("add1", add_cm); + m.def("add2", add_cm); + m.def("add2", add_rm); + // This one accepts a matrix of any stride: + m.def("add_any", [](py::EigenDRef x, int r, int c, double v) { x(r,c) += v; }); + + // Return mutable references (numpy maps into eigen variables) + m.def("get_cm_ref", []() { return Eigen::Ref(get_cm()); }); + m.def("get_rm_ref", []() { return Eigen::Ref(get_rm()); }); + // The same references, but non-mutable (numpy maps into eigen variables, but is !writeable) + m.def("get_cm_const_ref", []() { return Eigen::Ref(get_cm()); }); + m.def("get_rm_const_ref", []() { return Eigen::Ref(get_rm()); }); + + m.def("reset_refs", reset_refs); // Restores get_{cm,rm}_ref to original values + + // Increments and returns ref to (same) matrix + m.def("incr_matrix", [](Eigen::Ref m, double v) { + m += Eigen::MatrixXd::Constant(m.rows(), m.cols(), v); + return m; + }, py::return_value_policy::reference); + + // Same, but accepts a matrix of any strides + m.def("incr_matrix_any", [](py::EigenDRef m, double v) { + m += Eigen::MatrixXd::Constant(m.rows(), m.cols(), v); + return m; + }, py::return_value_policy::reference); + + // Returns an eigen slice of even rows + m.def("even_rows", [](py::EigenDRef m) { + return py::EigenDMap( + m.data(), (m.rows() + 1) / 2, m.cols(), + py::EigenDStride(m.outerStride(), 2 * m.innerStride())); + }, py::return_value_policy::reference); + + // Returns an eigen slice of even columns + m.def("even_cols", [](py::EigenDRef m) { + return py::EigenDMap( + m.data(), m.rows(), (m.cols() + 1) / 2, + py::EigenDStride(2 * m.outerStride(), m.innerStride())); + }, py::return_value_policy::reference); + + // Returns diagonals: a vector-like object with an inner stride != 1 + m.def("diagonal", [](const Eigen::Ref &x) { return x.diagonal(); }); + m.def("diagonal_1", [](const Eigen::Ref &x) { return x.diagonal<1>(); }); + m.def("diagonal_n", [](const Eigen::Ref &x, int index) { return x.diagonal(index); }); + + // Return a block of a matrix (gives non-standard strides) + m.def("block", [](const Eigen::Ref &x, int start_row, int start_col, int block_rows, int block_cols) { + return x.block(start_row, start_col, block_rows, block_cols); + }); + + // test_eigen_return_references, test_eigen_keepalive + // return value referencing/copying tests: + class ReturnTester { + Eigen::MatrixXd mat = create(); + public: + ReturnTester() { print_created(this); } + ~ReturnTester() { print_destroyed(this); } + static Eigen::MatrixXd create() { return Eigen::MatrixXd::Ones(10, 10); } + static const Eigen::MatrixXd createConst() { return Eigen::MatrixXd::Ones(10, 10); } + Eigen::MatrixXd &get() { return mat; } + Eigen::MatrixXd *getPtr() { return &mat; } + const Eigen::MatrixXd &view() { return mat; } + const Eigen::MatrixXd *viewPtr() { return &mat; } + Eigen::Ref ref() { return mat; } + Eigen::Ref refConst() { return mat; } + Eigen::Block block(int r, int c, int nrow, int ncol) { return mat.block(r, c, nrow, ncol); } + Eigen::Block blockConst(int r, int c, int nrow, int ncol) const { return mat.block(r, c, nrow, ncol); } + py::EigenDMap corners() { return py::EigenDMap(mat.data(), + py::EigenDStride(mat.outerStride() * (mat.outerSize()-1), mat.innerStride() * (mat.innerSize()-1))); } + py::EigenDMap cornersConst() const { return py::EigenDMap(mat.data(), + py::EigenDStride(mat.outerStride() * (mat.outerSize()-1), mat.innerStride() * (mat.innerSize()-1))); } + }; + using rvp = py::return_value_policy; + py::class_(m, "ReturnTester") + .def(py::init<>()) + .def_static("create", &ReturnTester::create) + .def_static("create_const", &ReturnTester::createConst) + .def("get", &ReturnTester::get, rvp::reference_internal) + .def("get_ptr", &ReturnTester::getPtr, rvp::reference_internal) + .def("view", &ReturnTester::view, rvp::reference_internal) + .def("view_ptr", &ReturnTester::view, rvp::reference_internal) + .def("copy_get", &ReturnTester::get) // Default rvp: copy + .def("copy_view", &ReturnTester::view) // " + .def("ref", &ReturnTester::ref) // Default for Ref is to reference + .def("ref_const", &ReturnTester::refConst) // Likewise, but const + .def("ref_safe", &ReturnTester::ref, rvp::reference_internal) + .def("ref_const_safe", &ReturnTester::refConst, rvp::reference_internal) + .def("copy_ref", &ReturnTester::ref, rvp::copy) + .def("copy_ref_const", &ReturnTester::refConst, rvp::copy) + .def("block", &ReturnTester::block) + .def("block_safe", &ReturnTester::block, rvp::reference_internal) + .def("block_const", &ReturnTester::blockConst, rvp::reference_internal) + .def("copy_block", &ReturnTester::block, rvp::copy) + .def("corners", &ReturnTester::corners, rvp::reference_internal) + .def("corners_const", &ReturnTester::cornersConst, rvp::reference_internal) + ; + + // test_special_matrix_objects + // Returns a DiagonalMatrix with diagonal (1,2,3,...) + m.def("incr_diag", [](int k) { + Eigen::DiagonalMatrix m(k); + for (int i = 0; i < k; i++) m.diagonal()[i] = i+1; + return m; + }); + + // Returns a SelfAdjointView referencing the lower triangle of m + m.def("symmetric_lower", [](const Eigen::MatrixXi &m) { + return m.selfadjointView(); + }); + // Returns a SelfAdjointView referencing the lower triangle of m + m.def("symmetric_upper", [](const Eigen::MatrixXi &m) { + return m.selfadjointView(); + }); + + // Test matrix for various functions below. + Eigen::MatrixXf mat(5, 6); + mat << 0, 3, 0, 0, 0, 11, + 22, 0, 0, 0, 17, 11, + 7, 5, 0, 1, 0, 11, + 0, 0, 0, 0, 0, 11, + 0, 0, 14, 0, 8, 11; + + // test_fixed, and various other tests + m.def("fixed_r", [mat]() -> FixedMatrixR { return FixedMatrixR(mat); }); + m.def("fixed_r_const", [mat]() -> const FixedMatrixR { return FixedMatrixR(mat); }); + m.def("fixed_c", [mat]() -> FixedMatrixC { return FixedMatrixC(mat); }); + m.def("fixed_copy_r", [](const FixedMatrixR &m) -> FixedMatrixR { return m; }); + m.def("fixed_copy_c", [](const FixedMatrixC &m) -> FixedMatrixC { return m; }); + // test_mutator_descriptors + m.def("fixed_mutator_r", [](Eigen::Ref) {}); + m.def("fixed_mutator_c", [](Eigen::Ref) {}); + m.def("fixed_mutator_a", [](py::EigenDRef) {}); + // test_dense + m.def("dense_r", [mat]() -> DenseMatrixR { return DenseMatrixR(mat); }); + m.def("dense_c", [mat]() -> DenseMatrixC { return DenseMatrixC(mat); }); + m.def("dense_copy_r", [](const DenseMatrixR &m) -> DenseMatrixR { return m; }); + m.def("dense_copy_c", [](const DenseMatrixC &m) -> DenseMatrixC { return m; }); + // test_sparse, test_sparse_signature + m.def("sparse_r", [mat]() -> SparseMatrixR { return Eigen::SparseView(mat); }); + m.def("sparse_c", [mat]() -> SparseMatrixC { return Eigen::SparseView(mat); }); + m.def("sparse_copy_r", [](const SparseMatrixR &m) -> SparseMatrixR { return m; }); + m.def("sparse_copy_c", [](const SparseMatrixC &m) -> SparseMatrixC { return m; }); + // test_partially_fixed + m.def("partial_copy_four_rm_r", [](const FourRowMatrixR &m) -> FourRowMatrixR { return m; }); + m.def("partial_copy_four_rm_c", [](const FourColMatrixR &m) -> FourColMatrixR { return m; }); + m.def("partial_copy_four_cm_r", [](const FourRowMatrixC &m) -> FourRowMatrixC { return m; }); + m.def("partial_copy_four_cm_c", [](const FourColMatrixC &m) -> FourColMatrixC { return m; }); + + // test_cpp_casting + // Test that we can cast a numpy object to a Eigen::MatrixXd explicitly + m.def("cpp_copy", [](py::handle m) { return m.cast()(1, 0); }); + m.def("cpp_ref_c", [](py::handle m) { return m.cast>()(1, 0); }); + m.def("cpp_ref_r", [](py::handle m) { return m.cast>()(1, 0); }); + m.def("cpp_ref_any", [](py::handle m) { return m.cast>()(1, 0); }); + + + // test_nocopy_wrapper + // Test that we can prevent copying into an argument that would normally copy: First a version + // that would allow copying (if types or strides don't match) for comparison: + m.def("get_elem", &get_elem); + // Now this alternative that calls the tells pybind to fail rather than copy: + m.def("get_elem_nocopy", [](Eigen::Ref m) -> double { return get_elem(m); }, + py::arg().noconvert()); + // Also test a row-major-only no-copy const ref: + m.def("get_elem_rm_nocopy", [](Eigen::Ref> &m) -> long { return m(2, 1); }, + py::arg().noconvert()); + + // test_issue738 + // Issue #738: 1xN or Nx1 2D matrices were neither accepted nor properly copied with an + // incompatible stride value on the length-1 dimension--but that should be allowed (without + // requiring a copy!) because the stride value can be safely ignored on a size-1 dimension. + m.def("iss738_f1", &adjust_matrix &>, py::arg().noconvert()); + m.def("iss738_f2", &adjust_matrix> &>, py::arg().noconvert()); + + // test_issue1105 + // Issue #1105: when converting from a numpy two-dimensional (Nx1) or (1xN) value into a dense + // eigen Vector or RowVector, the argument would fail to load because the numpy copy would fail: + // numpy won't broadcast a Nx1 into a 1-dimensional vector. + m.def("iss1105_col", [](Eigen::VectorXd) { return true; }); + m.def("iss1105_row", [](Eigen::RowVectorXd) { return true; }); + + // test_named_arguments + // Make sure named arguments are working properly: + m.def("matrix_multiply", [](const py::EigenDRef A, const py::EigenDRef B) + -> Eigen::MatrixXd { + if (A.cols() != B.rows()) throw std::domain_error("Nonconformable matrices!"); + return A * B; + }, py::arg("A"), py::arg("B")); + + // test_custom_operator_new + py::class_(m, "CustomOperatorNew") + .def(py::init<>()) + .def_readonly("a", &CustomOperatorNew::a) + .def_readonly("b", &CustomOperatorNew::b); + + // test_eigen_ref_life_support + // In case of a failure (the caster's temp array does not live long enough), creating + // a new array (np.ones(10)) increases the chances that the temp array will be garbage + // collected and/or that its memory will be overridden with different values. + m.def("get_elem_direct", [](Eigen::Ref v) { + py::module::import("numpy").attr("ones")(10); + return v(5); + }); + m.def("get_elem_indirect", [](std::vector> v) { + py::module::import("numpy").attr("ones")(10); + return v[0](5); + }); +} diff --git a/wrap/python/pybind11/tests/test_eigen.py b/wrap/python/pybind11/tests/test_eigen.py new file mode 100644 index 000000000..45f64ca94 --- /dev/null +++ b/wrap/python/pybind11/tests/test_eigen.py @@ -0,0 +1,694 @@ +import pytest +from pybind11_tests import ConstructorStats + +pytestmark = pytest.requires_eigen_and_numpy + +with pytest.suppress(ImportError): + from pybind11_tests import eigen as m + import numpy as np + + ref = np.array([[ 0., 3, 0, 0, 0, 11], + [22, 0, 0, 0, 17, 11], + [ 7, 5, 0, 1, 0, 11], + [ 0, 0, 0, 0, 0, 11], + [ 0, 0, 14, 0, 8, 11]]) + + +def assert_equal_ref(mat): + np.testing.assert_array_equal(mat, ref) + + +def assert_sparse_equal_ref(sparse_mat): + assert_equal_ref(sparse_mat.toarray()) + + +def test_fixed(): + assert_equal_ref(m.fixed_c()) + assert_equal_ref(m.fixed_r()) + assert_equal_ref(m.fixed_copy_r(m.fixed_r())) + assert_equal_ref(m.fixed_copy_c(m.fixed_c())) + assert_equal_ref(m.fixed_copy_r(m.fixed_c())) + assert_equal_ref(m.fixed_copy_c(m.fixed_r())) + + +def test_dense(): + assert_equal_ref(m.dense_r()) + assert_equal_ref(m.dense_c()) + assert_equal_ref(m.dense_copy_r(m.dense_r())) + assert_equal_ref(m.dense_copy_c(m.dense_c())) + assert_equal_ref(m.dense_copy_r(m.dense_c())) + assert_equal_ref(m.dense_copy_c(m.dense_r())) + + +def test_partially_fixed(): + ref2 = np.array([[0., 1, 2, 3], [4, 5, 6, 7], [8, 9, 10, 11], [12, 13, 14, 15]]) + np.testing.assert_array_equal(m.partial_copy_four_rm_r(ref2), ref2) + np.testing.assert_array_equal(m.partial_copy_four_rm_c(ref2), ref2) + np.testing.assert_array_equal(m.partial_copy_four_rm_r(ref2[:, 1]), ref2[:, [1]]) + np.testing.assert_array_equal(m.partial_copy_four_rm_c(ref2[0, :]), ref2[[0], :]) + np.testing.assert_array_equal(m.partial_copy_four_rm_r(ref2[:, (0, 2)]), ref2[:, (0, 2)]) + np.testing.assert_array_equal( + m.partial_copy_four_rm_c(ref2[(3, 1, 2), :]), ref2[(3, 1, 2), :]) + + np.testing.assert_array_equal(m.partial_copy_four_cm_r(ref2), ref2) + np.testing.assert_array_equal(m.partial_copy_four_cm_c(ref2), ref2) + np.testing.assert_array_equal(m.partial_copy_four_cm_r(ref2[:, 1]), ref2[:, [1]]) + np.testing.assert_array_equal(m.partial_copy_four_cm_c(ref2[0, :]), ref2[[0], :]) + np.testing.assert_array_equal(m.partial_copy_four_cm_r(ref2[:, (0, 2)]), ref2[:, (0, 2)]) + np.testing.assert_array_equal( + m.partial_copy_four_cm_c(ref2[(3, 1, 2), :]), ref2[(3, 1, 2), :]) + + # TypeError should be raise for a shape mismatch + functions = [m.partial_copy_four_rm_r, m.partial_copy_four_rm_c, + m.partial_copy_four_cm_r, m.partial_copy_four_cm_c] + matrix_with_wrong_shape = [[1, 2], + [3, 4]] + for f in functions: + with pytest.raises(TypeError) as excinfo: + f(matrix_with_wrong_shape) + assert "incompatible function arguments" in str(excinfo.value) + + +def test_mutator_descriptors(): + zr = np.arange(30, dtype='float32').reshape(5, 6) # row-major + zc = zr.reshape(6, 5).transpose() # column-major + + m.fixed_mutator_r(zr) + m.fixed_mutator_c(zc) + m.fixed_mutator_a(zr) + m.fixed_mutator_a(zc) + with pytest.raises(TypeError) as excinfo: + m.fixed_mutator_r(zc) + assert ('(arg0: numpy.ndarray[float32[5, 6], flags.writeable, flags.c_contiguous]) -> None' + in str(excinfo.value)) + with pytest.raises(TypeError) as excinfo: + m.fixed_mutator_c(zr) + assert ('(arg0: numpy.ndarray[float32[5, 6], flags.writeable, flags.f_contiguous]) -> None' + in str(excinfo.value)) + with pytest.raises(TypeError) as excinfo: + m.fixed_mutator_a(np.array([[1, 2], [3, 4]], dtype='float32')) + assert ('(arg0: numpy.ndarray[float32[5, 6], flags.writeable]) -> None' + in str(excinfo.value)) + zr.flags.writeable = False + with pytest.raises(TypeError): + m.fixed_mutator_r(zr) + with pytest.raises(TypeError): + m.fixed_mutator_a(zr) + + +def test_cpp_casting(): + assert m.cpp_copy(m.fixed_r()) == 22. + assert m.cpp_copy(m.fixed_c()) == 22. + z = np.array([[5., 6], [7, 8]]) + assert m.cpp_copy(z) == 7. + assert m.cpp_copy(m.get_cm_ref()) == 21. + assert m.cpp_copy(m.get_rm_ref()) == 21. + assert m.cpp_ref_c(m.get_cm_ref()) == 21. + assert m.cpp_ref_r(m.get_rm_ref()) == 21. + with pytest.raises(RuntimeError) as excinfo: + # Can't reference m.fixed_c: it contains floats, m.cpp_ref_any wants doubles + m.cpp_ref_any(m.fixed_c()) + assert 'Unable to cast Python instance' in str(excinfo.value) + with pytest.raises(RuntimeError) as excinfo: + # Can't reference m.fixed_r: it contains floats, m.cpp_ref_any wants doubles + m.cpp_ref_any(m.fixed_r()) + assert 'Unable to cast Python instance' in str(excinfo.value) + assert m.cpp_ref_any(m.ReturnTester.create()) == 1. + + assert m.cpp_ref_any(m.get_cm_ref()) == 21. + assert m.cpp_ref_any(m.get_cm_ref()) == 21. + + +def test_pass_readonly_array(): + z = np.full((5, 6), 42.0) + z.flags.writeable = False + np.testing.assert_array_equal(z, m.fixed_copy_r(z)) + np.testing.assert_array_equal(m.fixed_r_const(), m.fixed_r()) + assert not m.fixed_r_const().flags.writeable + np.testing.assert_array_equal(m.fixed_copy_r(m.fixed_r_const()), m.fixed_r_const()) + + +def test_nonunit_stride_from_python(): + counting_mat = np.arange(9.0, dtype=np.float32).reshape((3, 3)) + second_row = counting_mat[1, :] + second_col = counting_mat[:, 1] + np.testing.assert_array_equal(m.double_row(second_row), 2.0 * second_row) + np.testing.assert_array_equal(m.double_col(second_row), 2.0 * second_row) + np.testing.assert_array_equal(m.double_complex(second_row), 2.0 * second_row) + np.testing.assert_array_equal(m.double_row(second_col), 2.0 * second_col) + np.testing.assert_array_equal(m.double_col(second_col), 2.0 * second_col) + np.testing.assert_array_equal(m.double_complex(second_col), 2.0 * second_col) + + counting_3d = np.arange(27.0, dtype=np.float32).reshape((3, 3, 3)) + slices = [counting_3d[0, :, :], counting_3d[:, 0, :], counting_3d[:, :, 0]] + for slice_idx, ref_mat in enumerate(slices): + np.testing.assert_array_equal(m.double_mat_cm(ref_mat), 2.0 * ref_mat) + np.testing.assert_array_equal(m.double_mat_rm(ref_mat), 2.0 * ref_mat) + + # Mutator: + m.double_threer(second_row) + m.double_threec(second_col) + np.testing.assert_array_equal(counting_mat, [[0., 2, 2], [6, 16, 10], [6, 14, 8]]) + + +def test_negative_stride_from_python(msg): + """Eigen doesn't support (as of yet) negative strides. When a function takes an Eigen matrix by + copy or const reference, we can pass a numpy array that has negative strides. Otherwise, an + exception will be thrown as Eigen will not be able to map the numpy array.""" + + counting_mat = np.arange(9.0, dtype=np.float32).reshape((3, 3)) + counting_mat = counting_mat[::-1, ::-1] + second_row = counting_mat[1, :] + second_col = counting_mat[:, 1] + np.testing.assert_array_equal(m.double_row(second_row), 2.0 * second_row) + np.testing.assert_array_equal(m.double_col(second_row), 2.0 * second_row) + np.testing.assert_array_equal(m.double_complex(second_row), 2.0 * second_row) + np.testing.assert_array_equal(m.double_row(second_col), 2.0 * second_col) + np.testing.assert_array_equal(m.double_col(second_col), 2.0 * second_col) + np.testing.assert_array_equal(m.double_complex(second_col), 2.0 * second_col) + + counting_3d = np.arange(27.0, dtype=np.float32).reshape((3, 3, 3)) + counting_3d = counting_3d[::-1, ::-1, ::-1] + slices = [counting_3d[0, :, :], counting_3d[:, 0, :], counting_3d[:, :, 0]] + for slice_idx, ref_mat in enumerate(slices): + np.testing.assert_array_equal(m.double_mat_cm(ref_mat), 2.0 * ref_mat) + np.testing.assert_array_equal(m.double_mat_rm(ref_mat), 2.0 * ref_mat) + + # Mutator: + with pytest.raises(TypeError) as excinfo: + m.double_threer(second_row) + assert msg(excinfo.value) == """ + double_threer(): incompatible function arguments. The following argument types are supported: + 1. (arg0: numpy.ndarray[float32[1, 3], flags.writeable]) -> None + + Invoked with: """ + repr(np.array([ 5., 4., 3.], dtype='float32')) # noqa: E501 line too long + + with pytest.raises(TypeError) as excinfo: + m.double_threec(second_col) + assert msg(excinfo.value) == """ + double_threec(): incompatible function arguments. The following argument types are supported: + 1. (arg0: numpy.ndarray[float32[3, 1], flags.writeable]) -> None + + Invoked with: """ + repr(np.array([ 7., 4., 1.], dtype='float32')) # noqa: E501 line too long + + +def test_nonunit_stride_to_python(): + assert np.all(m.diagonal(ref) == ref.diagonal()) + assert np.all(m.diagonal_1(ref) == ref.diagonal(1)) + for i in range(-5, 7): + assert np.all(m.diagonal_n(ref, i) == ref.diagonal(i)), "m.diagonal_n({})".format(i) + + assert np.all(m.block(ref, 2, 1, 3, 3) == ref[2:5, 1:4]) + assert np.all(m.block(ref, 1, 4, 4, 2) == ref[1:, 4:]) + assert np.all(m.block(ref, 1, 4, 3, 2) == ref[1:4, 4:]) + + +def test_eigen_ref_to_python(): + chols = [m.cholesky1, m.cholesky2, m.cholesky3, m.cholesky4] + for i, chol in enumerate(chols, start=1): + mymat = chol(np.array([[1., 2, 4], [2, 13, 23], [4, 23, 77]])) + assert np.all(mymat == np.array([[1, 0, 0], [2, 3, 0], [4, 5, 6]])), "cholesky{}".format(i) + + +def assign_both(a1, a2, r, c, v): + a1[r, c] = v + a2[r, c] = v + + +def array_copy_but_one(a, r, c, v): + z = np.array(a, copy=True) + z[r, c] = v + return z + + +def test_eigen_return_references(): + """Tests various ways of returning references and non-referencing copies""" + + master = np.ones((10, 10)) + a = m.ReturnTester() + a_get1 = a.get() + assert not a_get1.flags.owndata and a_get1.flags.writeable + assign_both(a_get1, master, 3, 3, 5) + a_get2 = a.get_ptr() + assert not a_get2.flags.owndata and a_get2.flags.writeable + assign_both(a_get1, master, 2, 3, 6) + + a_view1 = a.view() + assert not a_view1.flags.owndata and not a_view1.flags.writeable + with pytest.raises(ValueError): + a_view1[2, 3] = 4 + a_view2 = a.view_ptr() + assert not a_view2.flags.owndata and not a_view2.flags.writeable + with pytest.raises(ValueError): + a_view2[2, 3] = 4 + + a_copy1 = a.copy_get() + assert a_copy1.flags.owndata and a_copy1.flags.writeable + np.testing.assert_array_equal(a_copy1, master) + a_copy1[7, 7] = -44 # Shouldn't affect anything else + c1want = array_copy_but_one(master, 7, 7, -44) + a_copy2 = a.copy_view() + assert a_copy2.flags.owndata and a_copy2.flags.writeable + np.testing.assert_array_equal(a_copy2, master) + a_copy2[4, 4] = -22 # Shouldn't affect anything else + c2want = array_copy_but_one(master, 4, 4, -22) + + a_ref1 = a.ref() + assert not a_ref1.flags.owndata and a_ref1.flags.writeable + assign_both(a_ref1, master, 1, 1, 15) + a_ref2 = a.ref_const() + assert not a_ref2.flags.owndata and not a_ref2.flags.writeable + with pytest.raises(ValueError): + a_ref2[5, 5] = 33 + a_ref3 = a.ref_safe() + assert not a_ref3.flags.owndata and a_ref3.flags.writeable + assign_both(a_ref3, master, 0, 7, 99) + a_ref4 = a.ref_const_safe() + assert not a_ref4.flags.owndata and not a_ref4.flags.writeable + with pytest.raises(ValueError): + a_ref4[7, 0] = 987654321 + + a_copy3 = a.copy_ref() + assert a_copy3.flags.owndata and a_copy3.flags.writeable + np.testing.assert_array_equal(a_copy3, master) + a_copy3[8, 1] = 11 + c3want = array_copy_but_one(master, 8, 1, 11) + a_copy4 = a.copy_ref_const() + assert a_copy4.flags.owndata and a_copy4.flags.writeable + np.testing.assert_array_equal(a_copy4, master) + a_copy4[8, 4] = 88 + c4want = array_copy_but_one(master, 8, 4, 88) + + a_block1 = a.block(3, 3, 2, 2) + assert not a_block1.flags.owndata and a_block1.flags.writeable + a_block1[0, 0] = 55 + master[3, 3] = 55 + a_block2 = a.block_safe(2, 2, 3, 2) + assert not a_block2.flags.owndata and a_block2.flags.writeable + a_block2[2, 1] = -123 + master[4, 3] = -123 + a_block3 = a.block_const(6, 7, 4, 3) + assert not a_block3.flags.owndata and not a_block3.flags.writeable + with pytest.raises(ValueError): + a_block3[2, 2] = -44444 + + a_copy5 = a.copy_block(2, 2, 2, 3) + assert a_copy5.flags.owndata and a_copy5.flags.writeable + np.testing.assert_array_equal(a_copy5, master[2:4, 2:5]) + a_copy5[1, 1] = 777 + c5want = array_copy_but_one(master[2:4, 2:5], 1, 1, 777) + + a_corn1 = a.corners() + assert not a_corn1.flags.owndata and a_corn1.flags.writeable + a_corn1 *= 50 + a_corn1[1, 1] = 999 + master[0, 0] = 50 + master[0, 9] = 50 + master[9, 0] = 50 + master[9, 9] = 999 + a_corn2 = a.corners_const() + assert not a_corn2.flags.owndata and not a_corn2.flags.writeable + with pytest.raises(ValueError): + a_corn2[1, 0] = 51 + + # All of the changes made all the way along should be visible everywhere + # now (except for the copies, of course) + np.testing.assert_array_equal(a_get1, master) + np.testing.assert_array_equal(a_get2, master) + np.testing.assert_array_equal(a_view1, master) + np.testing.assert_array_equal(a_view2, master) + np.testing.assert_array_equal(a_ref1, master) + np.testing.assert_array_equal(a_ref2, master) + np.testing.assert_array_equal(a_ref3, master) + np.testing.assert_array_equal(a_ref4, master) + np.testing.assert_array_equal(a_block1, master[3:5, 3:5]) + np.testing.assert_array_equal(a_block2, master[2:5, 2:4]) + np.testing.assert_array_equal(a_block3, master[6:10, 7:10]) + np.testing.assert_array_equal(a_corn1, master[0::master.shape[0] - 1, 0::master.shape[1] - 1]) + np.testing.assert_array_equal(a_corn2, master[0::master.shape[0] - 1, 0::master.shape[1] - 1]) + + np.testing.assert_array_equal(a_copy1, c1want) + np.testing.assert_array_equal(a_copy2, c2want) + np.testing.assert_array_equal(a_copy3, c3want) + np.testing.assert_array_equal(a_copy4, c4want) + np.testing.assert_array_equal(a_copy5, c5want) + + +def assert_keeps_alive(cl, method, *args): + cstats = ConstructorStats.get(cl) + start_with = cstats.alive() + a = cl() + assert cstats.alive() == start_with + 1 + z = method(a, *args) + assert cstats.alive() == start_with + 1 + del a + # Here's the keep alive in action: + assert cstats.alive() == start_with + 1 + del z + # Keep alive should have expired: + assert cstats.alive() == start_with + + +def test_eigen_keepalive(): + a = m.ReturnTester() + cstats = ConstructorStats.get(m.ReturnTester) + assert cstats.alive() == 1 + unsafe = [a.ref(), a.ref_const(), a.block(1, 2, 3, 4)] + copies = [a.copy_get(), a.copy_view(), a.copy_ref(), a.copy_ref_const(), + a.copy_block(4, 3, 2, 1)] + del a + assert cstats.alive() == 0 + del unsafe + del copies + + for meth in [m.ReturnTester.get, m.ReturnTester.get_ptr, m.ReturnTester.view, + m.ReturnTester.view_ptr, m.ReturnTester.ref_safe, m.ReturnTester.ref_const_safe, + m.ReturnTester.corners, m.ReturnTester.corners_const]: + assert_keeps_alive(m.ReturnTester, meth) + + for meth in [m.ReturnTester.block_safe, m.ReturnTester.block_const]: + assert_keeps_alive(m.ReturnTester, meth, 4, 3, 2, 1) + + +def test_eigen_ref_mutators(): + """Tests Eigen's ability to mutate numpy values""" + + orig = np.array([[1., 2, 3], [4, 5, 6], [7, 8, 9]]) + zr = np.array(orig) + zc = np.array(orig, order='F') + m.add_rm(zr, 1, 0, 100) + assert np.all(zr == np.array([[1., 2, 3], [104, 5, 6], [7, 8, 9]])) + m.add_cm(zc, 1, 0, 200) + assert np.all(zc == np.array([[1., 2, 3], [204, 5, 6], [7, 8, 9]])) + + m.add_any(zr, 1, 0, 20) + assert np.all(zr == np.array([[1., 2, 3], [124, 5, 6], [7, 8, 9]])) + m.add_any(zc, 1, 0, 10) + assert np.all(zc == np.array([[1., 2, 3], [214, 5, 6], [7, 8, 9]])) + + # Can't reference a col-major array with a row-major Ref, and vice versa: + with pytest.raises(TypeError): + m.add_rm(zc, 1, 0, 1) + with pytest.raises(TypeError): + m.add_cm(zr, 1, 0, 1) + + # Overloads: + m.add1(zr, 1, 0, -100) + m.add2(zr, 1, 0, -20) + assert np.all(zr == orig) + m.add1(zc, 1, 0, -200) + m.add2(zc, 1, 0, -10) + assert np.all(zc == orig) + + # a non-contiguous slice (this won't work on either the row- or + # column-contiguous refs, but should work for the any) + cornersr = zr[0::2, 0::2] + cornersc = zc[0::2, 0::2] + + assert np.all(cornersr == np.array([[1., 3], [7, 9]])) + assert np.all(cornersc == np.array([[1., 3], [7, 9]])) + + with pytest.raises(TypeError): + m.add_rm(cornersr, 0, 1, 25) + with pytest.raises(TypeError): + m.add_cm(cornersr, 0, 1, 25) + with pytest.raises(TypeError): + m.add_rm(cornersc, 0, 1, 25) + with pytest.raises(TypeError): + m.add_cm(cornersc, 0, 1, 25) + m.add_any(cornersr, 0, 1, 25) + m.add_any(cornersc, 0, 1, 44) + assert np.all(zr == np.array([[1., 2, 28], [4, 5, 6], [7, 8, 9]])) + assert np.all(zc == np.array([[1., 2, 47], [4, 5, 6], [7, 8, 9]])) + + # You shouldn't be allowed to pass a non-writeable array to a mutating Eigen method: + zro = zr[0:4, 0:4] + zro.flags.writeable = False + with pytest.raises(TypeError): + m.add_rm(zro, 0, 0, 0) + with pytest.raises(TypeError): + m.add_any(zro, 0, 0, 0) + with pytest.raises(TypeError): + m.add1(zro, 0, 0, 0) + with pytest.raises(TypeError): + m.add2(zro, 0, 0, 0) + + # integer array shouldn't be passable to a double-matrix-accepting mutating func: + zi = np.array([[1, 2], [3, 4]]) + with pytest.raises(TypeError): + m.add_rm(zi) + + +def test_numpy_ref_mutators(): + """Tests numpy mutating Eigen matrices (for returned Eigen::Ref<...>s)""" + + m.reset_refs() # In case another test already changed it + + zc = m.get_cm_ref() + zcro = m.get_cm_const_ref() + zr = m.get_rm_ref() + zrro = m.get_rm_const_ref() + + assert [zc[1, 2], zcro[1, 2], zr[1, 2], zrro[1, 2]] == [23] * 4 + + assert not zc.flags.owndata and zc.flags.writeable + assert not zr.flags.owndata and zr.flags.writeable + assert not zcro.flags.owndata and not zcro.flags.writeable + assert not zrro.flags.owndata and not zrro.flags.writeable + + zc[1, 2] = 99 + expect = np.array([[11., 12, 13], [21, 22, 99], [31, 32, 33]]) + # We should have just changed zc, of course, but also zcro and the original eigen matrix + assert np.all(zc == expect) + assert np.all(zcro == expect) + assert np.all(m.get_cm_ref() == expect) + + zr[1, 2] = 99 + assert np.all(zr == expect) + assert np.all(zrro == expect) + assert np.all(m.get_rm_ref() == expect) + + # Make sure the readonly ones are numpy-readonly: + with pytest.raises(ValueError): + zcro[1, 2] = 6 + with pytest.raises(ValueError): + zrro[1, 2] = 6 + + # We should be able to explicitly copy like this (and since we're copying, + # the const should drop away) + y1 = np.array(m.get_cm_const_ref()) + + assert y1.flags.owndata and y1.flags.writeable + # We should get copies of the eigen data, which was modified above: + assert y1[1, 2] == 99 + y1[1, 2] += 12 + assert y1[1, 2] == 111 + assert zc[1, 2] == 99 # Make sure we aren't referencing the original + + +def test_both_ref_mutators(): + """Tests a complex chain of nested eigen/numpy references""" + + m.reset_refs() # In case another test already changed it + + z = m.get_cm_ref() # numpy -> eigen + z[0, 2] -= 3 + z2 = m.incr_matrix(z, 1) # numpy -> eigen -> numpy -> eigen + z2[1, 1] += 6 + z3 = m.incr_matrix(z, 2) # (numpy -> eigen)^3 + z3[2, 2] += -5 + z4 = m.incr_matrix(z, 3) # (numpy -> eigen)^4 + z4[1, 1] -= 1 + z5 = m.incr_matrix(z, 4) # (numpy -> eigen)^5 + z5[0, 0] = 0 + assert np.all(z == z2) + assert np.all(z == z3) + assert np.all(z == z4) + assert np.all(z == z5) + expect = np.array([[0., 22, 20], [31, 37, 33], [41, 42, 38]]) + assert np.all(z == expect) + + y = np.array(range(100), dtype='float64').reshape(10, 10) + y2 = m.incr_matrix_any(y, 10) # np -> eigen -> np + y3 = m.incr_matrix_any(y2[0::2, 0::2], -33) # np -> eigen -> np slice -> np -> eigen -> np + y4 = m.even_rows(y3) # numpy -> eigen slice -> (... y3) + y5 = m.even_cols(y4) # numpy -> eigen slice -> (... y4) + y6 = m.incr_matrix_any(y5, 1000) # numpy -> eigen -> (... y5) + + # Apply same mutations using just numpy: + yexpect = np.array(range(100), dtype='float64').reshape(10, 10) + yexpect += 10 + yexpect[0::2, 0::2] -= 33 + yexpect[0::4, 0::4] += 1000 + assert np.all(y6 == yexpect[0::4, 0::4]) + assert np.all(y5 == yexpect[0::4, 0::4]) + assert np.all(y4 == yexpect[0::4, 0::2]) + assert np.all(y3 == yexpect[0::2, 0::2]) + assert np.all(y2 == yexpect) + assert np.all(y == yexpect) + + +def test_nocopy_wrapper(): + # get_elem requires a column-contiguous matrix reference, but should be + # callable with other types of matrix (via copying): + int_matrix_colmajor = np.array([[1, 2, 3], [4, 5, 6], [7, 8, 9]], order='F') + dbl_matrix_colmajor = np.array(int_matrix_colmajor, dtype='double', order='F', copy=True) + int_matrix_rowmajor = np.array(int_matrix_colmajor, order='C', copy=True) + dbl_matrix_rowmajor = np.array(int_matrix_rowmajor, dtype='double', order='C', copy=True) + + # All should be callable via get_elem: + assert m.get_elem(int_matrix_colmajor) == 8 + assert m.get_elem(dbl_matrix_colmajor) == 8 + assert m.get_elem(int_matrix_rowmajor) == 8 + assert m.get_elem(dbl_matrix_rowmajor) == 8 + + # All but the second should fail with m.get_elem_nocopy: + with pytest.raises(TypeError) as excinfo: + m.get_elem_nocopy(int_matrix_colmajor) + assert ('get_elem_nocopy(): incompatible function arguments.' in str(excinfo.value) and + ', flags.f_contiguous' in str(excinfo.value)) + assert m.get_elem_nocopy(dbl_matrix_colmajor) == 8 + with pytest.raises(TypeError) as excinfo: + m.get_elem_nocopy(int_matrix_rowmajor) + assert ('get_elem_nocopy(): incompatible function arguments.' in str(excinfo.value) and + ', flags.f_contiguous' in str(excinfo.value)) + with pytest.raises(TypeError) as excinfo: + m.get_elem_nocopy(dbl_matrix_rowmajor) + assert ('get_elem_nocopy(): incompatible function arguments.' in str(excinfo.value) and + ', flags.f_contiguous' in str(excinfo.value)) + + # For the row-major test, we take a long matrix in row-major, so only the third is allowed: + with pytest.raises(TypeError) as excinfo: + m.get_elem_rm_nocopy(int_matrix_colmajor) + assert ('get_elem_rm_nocopy(): incompatible function arguments.' in str(excinfo.value) and + ', flags.c_contiguous' in str(excinfo.value)) + with pytest.raises(TypeError) as excinfo: + m.get_elem_rm_nocopy(dbl_matrix_colmajor) + assert ('get_elem_rm_nocopy(): incompatible function arguments.' in str(excinfo.value) and + ', flags.c_contiguous' in str(excinfo.value)) + assert m.get_elem_rm_nocopy(int_matrix_rowmajor) == 8 + with pytest.raises(TypeError) as excinfo: + m.get_elem_rm_nocopy(dbl_matrix_rowmajor) + assert ('get_elem_rm_nocopy(): incompatible function arguments.' in str(excinfo.value) and + ', flags.c_contiguous' in str(excinfo.value)) + + +def test_eigen_ref_life_support(): + """Ensure the lifetime of temporary arrays created by the `Ref` caster + + The `Ref` caster sometimes creates a copy which needs to stay alive. This needs to + happen both for directs casts (just the array) or indirectly (e.g. list of arrays). + """ + + a = np.full(shape=10, fill_value=8, dtype=np.int8) + assert m.get_elem_direct(a) == 8 + + list_of_a = [a] + assert m.get_elem_indirect(list_of_a) == 8 + + +def test_special_matrix_objects(): + assert np.all(m.incr_diag(7) == np.diag([1., 2, 3, 4, 5, 6, 7])) + + asymm = np.array([[ 1., 2, 3, 4], + [ 5, 6, 7, 8], + [ 9, 10, 11, 12], + [13, 14, 15, 16]]) + symm_lower = np.array(asymm) + symm_upper = np.array(asymm) + for i in range(4): + for j in range(i + 1, 4): + symm_lower[i, j] = symm_lower[j, i] + symm_upper[j, i] = symm_upper[i, j] + + assert np.all(m.symmetric_lower(asymm) == symm_lower) + assert np.all(m.symmetric_upper(asymm) == symm_upper) + + +def test_dense_signature(doc): + assert doc(m.double_col) == """ + double_col(arg0: numpy.ndarray[float32[m, 1]]) -> numpy.ndarray[float32[m, 1]] + """ + assert doc(m.double_row) == """ + double_row(arg0: numpy.ndarray[float32[1, n]]) -> numpy.ndarray[float32[1, n]] + """ + assert doc(m.double_complex) == """ + double_complex(arg0: numpy.ndarray[complex64[m, 1]]) -> numpy.ndarray[complex64[m, 1]] + """ + assert doc(m.double_mat_rm) == """ + double_mat_rm(arg0: numpy.ndarray[float32[m, n]]) -> numpy.ndarray[float32[m, n]] + """ + + +def test_named_arguments(): + a = np.array([[1.0, 2], [3, 4], [5, 6]]) + b = np.ones((2, 1)) + + assert np.all(m.matrix_multiply(a, b) == np.array([[3.], [7], [11]])) + assert np.all(m.matrix_multiply(A=a, B=b) == np.array([[3.], [7], [11]])) + assert np.all(m.matrix_multiply(B=b, A=a) == np.array([[3.], [7], [11]])) + + with pytest.raises(ValueError) as excinfo: + m.matrix_multiply(b, a) + assert str(excinfo.value) == 'Nonconformable matrices!' + + with pytest.raises(ValueError) as excinfo: + m.matrix_multiply(A=b, B=a) + assert str(excinfo.value) == 'Nonconformable matrices!' + + with pytest.raises(ValueError) as excinfo: + m.matrix_multiply(B=a, A=b) + assert str(excinfo.value) == 'Nonconformable matrices!' + + +@pytest.requires_eigen_and_scipy +def test_sparse(): + assert_sparse_equal_ref(m.sparse_r()) + assert_sparse_equal_ref(m.sparse_c()) + assert_sparse_equal_ref(m.sparse_copy_r(m.sparse_r())) + assert_sparse_equal_ref(m.sparse_copy_c(m.sparse_c())) + assert_sparse_equal_ref(m.sparse_copy_r(m.sparse_c())) + assert_sparse_equal_ref(m.sparse_copy_c(m.sparse_r())) + + +@pytest.requires_eigen_and_scipy +def test_sparse_signature(doc): + assert doc(m.sparse_copy_r) == """ + sparse_copy_r(arg0: scipy.sparse.csr_matrix[float32]) -> scipy.sparse.csr_matrix[float32] + """ # noqa: E501 line too long + assert doc(m.sparse_copy_c) == """ + sparse_copy_c(arg0: scipy.sparse.csc_matrix[float32]) -> scipy.sparse.csc_matrix[float32] + """ # noqa: E501 line too long + + +def test_issue738(): + """Ignore strides on a length-1 dimension (even if they would be incompatible length > 1)""" + assert np.all(m.iss738_f1(np.array([[1., 2, 3]])) == np.array([[1., 102, 203]])) + assert np.all(m.iss738_f1(np.array([[1.], [2], [3]])) == np.array([[1.], [12], [23]])) + + assert np.all(m.iss738_f2(np.array([[1., 2, 3]])) == np.array([[1., 102, 203]])) + assert np.all(m.iss738_f2(np.array([[1.], [2], [3]])) == np.array([[1.], [12], [23]])) + + +def test_issue1105(): + """Issue 1105: 1xN or Nx1 input arrays weren't accepted for eigen + compile-time row vectors or column vector""" + assert m.iss1105_row(np.ones((1, 7))) + assert m.iss1105_col(np.ones((7, 1))) + + # These should still fail (incompatible dimensions): + with pytest.raises(TypeError) as excinfo: + m.iss1105_row(np.ones((7, 1))) + assert "incompatible function arguments" in str(excinfo) + with pytest.raises(TypeError) as excinfo: + m.iss1105_col(np.ones((1, 7))) + assert "incompatible function arguments" in str(excinfo) + + +def test_custom_operator_new(): + """Using Eigen types as member variables requires a class-specific + operator new with proper alignment""" + + o = m.CustomOperatorNew() + np.testing.assert_allclose(o.a, 0.0) + np.testing.assert_allclose(o.b.diagonal(), 1.0) diff --git a/wrap/python/pybind11/tests/test_embed/CMakeLists.txt b/wrap/python/pybind11/tests/test_embed/CMakeLists.txt new file mode 100644 index 000000000..8b4f1f843 --- /dev/null +++ b/wrap/python/pybind11/tests/test_embed/CMakeLists.txt @@ -0,0 +1,41 @@ +if(${PYTHON_MODULE_EXTENSION} MATCHES "pypy") + add_custom_target(cpptest) # Dummy target on PyPy. Embedding is not supported. + set(_suppress_unused_variable_warning "${DOWNLOAD_CATCH}") + return() +endif() + +find_package(Catch 1.9.3) +if(CATCH_FOUND) + message(STATUS "Building interpreter tests using Catch v${CATCH_VERSION}") +else() + message(STATUS "Catch not detected. Interpreter tests will be skipped. Install Catch headers" + " manually or use `cmake -DDOWNLOAD_CATCH=1` to fetch them automatically.") + return() +endif() + +add_executable(test_embed + catch.cpp + test_interpreter.cpp +) +target_include_directories(test_embed PRIVATE ${CATCH_INCLUDE_DIR}) +pybind11_enable_warnings(test_embed) + +if(NOT CMAKE_VERSION VERSION_LESS 3.0) + target_link_libraries(test_embed PRIVATE pybind11::embed) +else() + target_include_directories(test_embed PRIVATE ${PYBIND11_INCLUDE_DIR} ${PYTHON_INCLUDE_DIRS}) + target_compile_options(test_embed PRIVATE ${PYBIND11_CPP_STANDARD}) + target_link_libraries(test_embed PRIVATE ${PYTHON_LIBRARIES}) +endif() + +find_package(Threads REQUIRED) +target_link_libraries(test_embed PUBLIC ${CMAKE_THREAD_LIBS_INIT}) + +add_custom_target(cpptest COMMAND $ + WORKING_DIRECTORY ${CMAKE_CURRENT_SOURCE_DIR}) + +pybind11_add_module(external_module THIN_LTO external_module.cpp) +set_target_properties(external_module PROPERTIES LIBRARY_OUTPUT_DIRECTORY ${CMAKE_CURRENT_SOURCE_DIR}) +add_dependencies(cpptest external_module) + +add_dependencies(check cpptest) diff --git a/wrap/python/pybind11/tests/test_embed/catch.cpp b/wrap/python/pybind11/tests/test_embed/catch.cpp new file mode 100644 index 000000000..dd137385c --- /dev/null +++ b/wrap/python/pybind11/tests/test_embed/catch.cpp @@ -0,0 +1,22 @@ +// The Catch implementation is compiled here. This is a standalone +// translation unit to avoid recompiling it for every test change. + +#include + +#ifdef _MSC_VER +// Silence MSVC C++17 deprecation warning from Catch regarding std::uncaught_exceptions (up to catch +// 2.0.1; this should be fixed in the next catch release after 2.0.1). +# pragma warning(disable: 4996) +#endif + +#define CATCH_CONFIG_RUNNER +#include + +namespace py = pybind11; + +int main(int argc, char *argv[]) { + py::scoped_interpreter guard{}; + auto result = Catch::Session().run(argc, argv); + + return result < 0xff ? result : 0xff; +} diff --git a/wrap/python/pybind11/tests/test_embed/external_module.cpp b/wrap/python/pybind11/tests/test_embed/external_module.cpp new file mode 100644 index 000000000..e9a6058b1 --- /dev/null +++ b/wrap/python/pybind11/tests/test_embed/external_module.cpp @@ -0,0 +1,23 @@ +#include + +namespace py = pybind11; + +/* Simple test module/test class to check that the referenced internals data of external pybind11 + * modules aren't preserved over a finalize/initialize. + */ + +PYBIND11_MODULE(external_module, m) { + class A { + public: + A(int value) : v{value} {}; + int v; + }; + + py::class_(m, "A") + .def(py::init()) + .def_readwrite("value", &A::v); + + m.def("internals_at", []() { + return reinterpret_cast(&py::detail::get_internals()); + }); +} diff --git a/wrap/python/pybind11/tests/test_embed/test_interpreter.cpp b/wrap/python/pybind11/tests/test_embed/test_interpreter.cpp new file mode 100644 index 000000000..222bd565f --- /dev/null +++ b/wrap/python/pybind11/tests/test_embed/test_interpreter.cpp @@ -0,0 +1,284 @@ +#include + +#ifdef _MSC_VER +// Silence MSVC C++17 deprecation warning from Catch regarding std::uncaught_exceptions (up to catch +// 2.0.1; this should be fixed in the next catch release after 2.0.1). +# pragma warning(disable: 4996) +#endif + +#include + +#include +#include +#include + +namespace py = pybind11; +using namespace py::literals; + +class Widget { +public: + Widget(std::string message) : message(message) { } + virtual ~Widget() = default; + + std::string the_message() const { return message; } + virtual int the_answer() const = 0; + +private: + std::string message; +}; + +class PyWidget final : public Widget { + using Widget::Widget; + + int the_answer() const override { PYBIND11_OVERLOAD_PURE(int, Widget, the_answer); } +}; + +PYBIND11_EMBEDDED_MODULE(widget_module, m) { + py::class_(m, "Widget") + .def(py::init()) + .def_property_readonly("the_message", &Widget::the_message); + + m.def("add", [](int i, int j) { return i + j; }); +} + +PYBIND11_EMBEDDED_MODULE(throw_exception, ) { + throw std::runtime_error("C++ Error"); +} + +PYBIND11_EMBEDDED_MODULE(throw_error_already_set, ) { + auto d = py::dict(); + d["missing"].cast(); +} + +TEST_CASE("Pass classes and data between modules defined in C++ and Python") { + auto module = py::module::import("test_interpreter"); + REQUIRE(py::hasattr(module, "DerivedWidget")); + + auto locals = py::dict("hello"_a="Hello, World!", "x"_a=5, **module.attr("__dict__")); + py::exec(R"( + widget = DerivedWidget("{} - {}".format(hello, x)) + message = widget.the_message + )", py::globals(), locals); + REQUIRE(locals["message"].cast() == "Hello, World! - 5"); + + auto py_widget = module.attr("DerivedWidget")("The question"); + auto message = py_widget.attr("the_message"); + REQUIRE(message.cast() == "The question"); + + const auto &cpp_widget = py_widget.cast(); + REQUIRE(cpp_widget.the_answer() == 42); +} + +TEST_CASE("Import error handling") { + REQUIRE_NOTHROW(py::module::import("widget_module")); + REQUIRE_THROWS_WITH(py::module::import("throw_exception"), + "ImportError: C++ Error"); + REQUIRE_THROWS_WITH(py::module::import("throw_error_already_set"), + Catch::Contains("ImportError: KeyError")); +} + +TEST_CASE("There can be only one interpreter") { + static_assert(std::is_move_constructible::value, ""); + static_assert(!std::is_move_assignable::value, ""); + static_assert(!std::is_copy_constructible::value, ""); + static_assert(!std::is_copy_assignable::value, ""); + + REQUIRE_THROWS_WITH(py::initialize_interpreter(), "The interpreter is already running"); + REQUIRE_THROWS_WITH(py::scoped_interpreter(), "The interpreter is already running"); + + py::finalize_interpreter(); + REQUIRE_NOTHROW(py::scoped_interpreter()); + { + auto pyi1 = py::scoped_interpreter(); + auto pyi2 = std::move(pyi1); + } + py::initialize_interpreter(); +} + +bool has_pybind11_internals_builtin() { + auto builtins = py::handle(PyEval_GetBuiltins()); + return builtins.contains(PYBIND11_INTERNALS_ID); +}; + +bool has_pybind11_internals_static() { + auto **&ipp = py::detail::get_internals_pp(); + return ipp && *ipp; +} + +TEST_CASE("Restart the interpreter") { + // Verify pre-restart state. + REQUIRE(py::module::import("widget_module").attr("add")(1, 2).cast() == 3); + REQUIRE(has_pybind11_internals_builtin()); + REQUIRE(has_pybind11_internals_static()); + REQUIRE(py::module::import("external_module").attr("A")(123).attr("value").cast() == 123); + + // local and foreign module internals should point to the same internals: + REQUIRE(reinterpret_cast(*py::detail::get_internals_pp()) == + py::module::import("external_module").attr("internals_at")().cast()); + + // Restart the interpreter. + py::finalize_interpreter(); + REQUIRE(Py_IsInitialized() == 0); + + py::initialize_interpreter(); + REQUIRE(Py_IsInitialized() == 1); + + // Internals are deleted after a restart. + REQUIRE_FALSE(has_pybind11_internals_builtin()); + REQUIRE_FALSE(has_pybind11_internals_static()); + pybind11::detail::get_internals(); + REQUIRE(has_pybind11_internals_builtin()); + REQUIRE(has_pybind11_internals_static()); + REQUIRE(reinterpret_cast(*py::detail::get_internals_pp()) == + py::module::import("external_module").attr("internals_at")().cast()); + + // Make sure that an interpreter with no get_internals() created until finalize still gets the + // internals destroyed + py::finalize_interpreter(); + py::initialize_interpreter(); + bool ran = false; + py::module::import("__main__").attr("internals_destroy_test") = + py::capsule(&ran, [](void *ran) { py::detail::get_internals(); *static_cast(ran) = true; }); + REQUIRE_FALSE(has_pybind11_internals_builtin()); + REQUIRE_FALSE(has_pybind11_internals_static()); + REQUIRE_FALSE(ran); + py::finalize_interpreter(); + REQUIRE(ran); + py::initialize_interpreter(); + REQUIRE_FALSE(has_pybind11_internals_builtin()); + REQUIRE_FALSE(has_pybind11_internals_static()); + + // C++ modules can be reloaded. + auto cpp_module = py::module::import("widget_module"); + REQUIRE(cpp_module.attr("add")(1, 2).cast() == 3); + + // C++ type information is reloaded and can be used in python modules. + auto py_module = py::module::import("test_interpreter"); + auto py_widget = py_module.attr("DerivedWidget")("Hello after restart"); + REQUIRE(py_widget.attr("the_message").cast() == "Hello after restart"); +} + +TEST_CASE("Subinterpreter") { + // Add tags to the modules in the main interpreter and test the basics. + py::module::import("__main__").attr("main_tag") = "main interpreter"; + { + auto m = py::module::import("widget_module"); + m.attr("extension_module_tag") = "added to module in main interpreter"; + + REQUIRE(m.attr("add")(1, 2).cast() == 3); + } + REQUIRE(has_pybind11_internals_builtin()); + REQUIRE(has_pybind11_internals_static()); + + /// Create and switch to a subinterpreter. + auto main_tstate = PyThreadState_Get(); + auto sub_tstate = Py_NewInterpreter(); + + // Subinterpreters get their own copy of builtins. detail::get_internals() still + // works by returning from the static variable, i.e. all interpreters share a single + // global pybind11::internals; + REQUIRE_FALSE(has_pybind11_internals_builtin()); + REQUIRE(has_pybind11_internals_static()); + + // Modules tags should be gone. + REQUIRE_FALSE(py::hasattr(py::module::import("__main__"), "tag")); + { + auto m = py::module::import("widget_module"); + REQUIRE_FALSE(py::hasattr(m, "extension_module_tag")); + + // Function bindings should still work. + REQUIRE(m.attr("add")(1, 2).cast() == 3); + } + + // Restore main interpreter. + Py_EndInterpreter(sub_tstate); + PyThreadState_Swap(main_tstate); + + REQUIRE(py::hasattr(py::module::import("__main__"), "main_tag")); + REQUIRE(py::hasattr(py::module::import("widget_module"), "extension_module_tag")); +} + +TEST_CASE("Execution frame") { + // When the interpreter is embedded, there is no execution frame, but `py::exec` + // should still function by using reasonable globals: `__main__.__dict__`. + py::exec("var = dict(number=42)"); + REQUIRE(py::globals()["var"]["number"].cast() == 42); +} + +TEST_CASE("Threads") { + // Restart interpreter to ensure threads are not initialized + py::finalize_interpreter(); + py::initialize_interpreter(); + REQUIRE_FALSE(has_pybind11_internals_static()); + + constexpr auto num_threads = 10; + auto locals = py::dict("count"_a=0); + + { + py::gil_scoped_release gil_release{}; + REQUIRE(has_pybind11_internals_static()); + + auto threads = std::vector(); + for (auto i = 0; i < num_threads; ++i) { + threads.emplace_back([&]() { + py::gil_scoped_acquire gil{}; + locals["count"] = locals["count"].cast() + 1; + }); + } + + for (auto &thread : threads) { + thread.join(); + } + } + + REQUIRE(locals["count"].cast() == num_threads); +} + +// Scope exit utility https://stackoverflow.com/a/36644501/7255855 +struct scope_exit { + std::function f_; + explicit scope_exit(std::function f) noexcept : f_(std::move(f)) {} + ~scope_exit() { if (f_) f_(); } +}; + +TEST_CASE("Reload module from file") { + // Disable generation of cached bytecode (.pyc files) for this test, otherwise + // Python might pick up an old version from the cache instead of the new versions + // of the .py files generated below + auto sys = py::module::import("sys"); + bool dont_write_bytecode = sys.attr("dont_write_bytecode").cast(); + sys.attr("dont_write_bytecode") = true; + // Reset the value at scope exit + scope_exit reset_dont_write_bytecode([&]() { + sys.attr("dont_write_bytecode") = dont_write_bytecode; + }); + + std::string module_name = "test_module_reload"; + std::string module_file = module_name + ".py"; + + // Create the module .py file + std::ofstream test_module(module_file); + test_module << "def test():\n"; + test_module << " return 1\n"; + test_module.close(); + // Delete the file at scope exit + scope_exit delete_module_file([&]() { + std::remove(module_file.c_str()); + }); + + // Import the module from file + auto module = py::module::import(module_name.c_str()); + int result = module.attr("test")().cast(); + REQUIRE(result == 1); + + // Update the module .py file with a small change + test_module.open(module_file); + test_module << "def test():\n"; + test_module << " return 2\n"; + test_module.close(); + + // Reload the module + module.reload(); + result = module.attr("test")().cast(); + REQUIRE(result == 2); +} diff --git a/wrap/python/pybind11/tests/test_embed/test_interpreter.py b/wrap/python/pybind11/tests/test_embed/test_interpreter.py new file mode 100644 index 000000000..26a047921 --- /dev/null +++ b/wrap/python/pybind11/tests/test_embed/test_interpreter.py @@ -0,0 +1,9 @@ +from widget_module import Widget + + +class DerivedWidget(Widget): + def __init__(self, message): + super(DerivedWidget, self).__init__(message) + + def the_answer(self): + return 42 diff --git a/wrap/python/pybind11/tests/test_enum.cpp b/wrap/python/pybind11/tests/test_enum.cpp new file mode 100644 index 000000000..498a00e16 --- /dev/null +++ b/wrap/python/pybind11/tests/test_enum.cpp @@ -0,0 +1,85 @@ +/* + tests/test_enums.cpp -- enumerations + + Copyright (c) 2016 Wenzel Jakob + + All rights reserved. Use of this source code is governed by a + BSD-style license that can be found in the LICENSE file. +*/ + +#include "pybind11_tests.h" + +TEST_SUBMODULE(enums, m) { + // test_unscoped_enum + enum UnscopedEnum { + EOne = 1, + ETwo + }; + py::enum_(m, "UnscopedEnum", py::arithmetic(), "An unscoped enumeration") + .value("EOne", EOne, "Docstring for EOne") + .value("ETwo", ETwo, "Docstring for ETwo") + .export_values(); + + // test_scoped_enum + enum class ScopedEnum { + Two = 2, + Three + }; + py::enum_(m, "ScopedEnum", py::arithmetic()) + .value("Two", ScopedEnum::Two) + .value("Three", ScopedEnum::Three); + + m.def("test_scoped_enum", [](ScopedEnum z) { + return "ScopedEnum::" + std::string(z == ScopedEnum::Two ? "Two" : "Three"); + }); + + // test_binary_operators + enum Flags { + Read = 4, + Write = 2, + Execute = 1 + }; + py::enum_(m, "Flags", py::arithmetic()) + .value("Read", Flags::Read) + .value("Write", Flags::Write) + .value("Execute", Flags::Execute) + .export_values(); + + // test_implicit_conversion + class ClassWithUnscopedEnum { + public: + enum EMode { + EFirstMode = 1, + ESecondMode + }; + + static EMode test_function(EMode mode) { + return mode; + } + }; + py::class_ exenum_class(m, "ClassWithUnscopedEnum"); + exenum_class.def_static("test_function", &ClassWithUnscopedEnum::test_function); + py::enum_(exenum_class, "EMode") + .value("EFirstMode", ClassWithUnscopedEnum::EFirstMode) + .value("ESecondMode", ClassWithUnscopedEnum::ESecondMode) + .export_values(); + + // test_enum_to_int + m.def("test_enum_to_int", [](int) { }); + m.def("test_enum_to_uint", [](uint32_t) { }); + m.def("test_enum_to_long_long", [](long long) { }); + + // test_duplicate_enum_name + enum SimpleEnum + { + ONE, TWO, THREE + }; + + m.def("register_bad_enum", [m]() { + py::enum_(m, "SimpleEnum") + .value("ONE", SimpleEnum::ONE) //NOTE: all value function calls are called with the same first parameter value + .value("ONE", SimpleEnum::TWO) + .value("ONE", SimpleEnum::THREE) + .export_values(); + }); +} diff --git a/wrap/python/pybind11/tests/test_enum.py b/wrap/python/pybind11/tests/test_enum.py new file mode 100644 index 000000000..d0989adcd --- /dev/null +++ b/wrap/python/pybind11/tests/test_enum.py @@ -0,0 +1,167 @@ +import pytest +from pybind11_tests import enums as m + + +def test_unscoped_enum(): + assert str(m.UnscopedEnum.EOne) == "UnscopedEnum.EOne" + assert str(m.UnscopedEnum.ETwo) == "UnscopedEnum.ETwo" + assert str(m.EOne) == "UnscopedEnum.EOne" + + # name property + assert m.UnscopedEnum.EOne.name == "EOne" + assert m.UnscopedEnum.ETwo.name == "ETwo" + assert m.EOne.name == "EOne" + # name readonly + with pytest.raises(AttributeError): + m.UnscopedEnum.EOne.name = "" + # name returns a copy + foo = m.UnscopedEnum.EOne.name + foo = "bar" + assert m.UnscopedEnum.EOne.name == "EOne" + + # __members__ property + assert m.UnscopedEnum.__members__ == \ + {"EOne": m.UnscopedEnum.EOne, "ETwo": m.UnscopedEnum.ETwo} + # __members__ readonly + with pytest.raises(AttributeError): + m.UnscopedEnum.__members__ = {} + # __members__ returns a copy + foo = m.UnscopedEnum.__members__ + foo["bar"] = "baz" + assert m.UnscopedEnum.__members__ == \ + {"EOne": m.UnscopedEnum.EOne, "ETwo": m.UnscopedEnum.ETwo} + + assert m.UnscopedEnum.__doc__ == \ + '''An unscoped enumeration + +Members: + + EOne : Docstring for EOne + + ETwo : Docstring for ETwo''' or m.UnscopedEnum.__doc__ == \ + '''An unscoped enumeration + +Members: + + ETwo : Docstring for ETwo + + EOne : Docstring for EOne''' + + # Unscoped enums will accept ==/!= int comparisons + y = m.UnscopedEnum.ETwo + assert y == 2 + assert 2 == y + assert y != 3 + assert 3 != y + + assert int(m.UnscopedEnum.ETwo) == 2 + assert str(m.UnscopedEnum(2)) == "UnscopedEnum.ETwo" + + # order + assert m.UnscopedEnum.EOne < m.UnscopedEnum.ETwo + assert m.UnscopedEnum.EOne < 2 + assert m.UnscopedEnum.ETwo > m.UnscopedEnum.EOne + assert m.UnscopedEnum.ETwo > 1 + assert m.UnscopedEnum.ETwo <= 2 + assert m.UnscopedEnum.ETwo >= 2 + assert m.UnscopedEnum.EOne <= m.UnscopedEnum.ETwo + assert m.UnscopedEnum.EOne <= 2 + assert m.UnscopedEnum.ETwo >= m.UnscopedEnum.EOne + assert m.UnscopedEnum.ETwo >= 1 + assert not (m.UnscopedEnum.ETwo < m.UnscopedEnum.EOne) + assert not (2 < m.UnscopedEnum.EOne) + + +def test_scoped_enum(): + assert m.test_scoped_enum(m.ScopedEnum.Three) == "ScopedEnum::Three" + z = m.ScopedEnum.Two + assert m.test_scoped_enum(z) == "ScopedEnum::Two" + + # Scoped enums will *NOT* accept ==/!= int comparisons (Will always return False) + assert not z == 3 + assert not 3 == z + assert z != 3 + assert 3 != z + # Scoped enums will *NOT* accept >, <, >= and <= int comparisons (Will throw exceptions) + with pytest.raises(TypeError): + z > 3 + with pytest.raises(TypeError): + z < 3 + with pytest.raises(TypeError): + z >= 3 + with pytest.raises(TypeError): + z <= 3 + + # order + assert m.ScopedEnum.Two < m.ScopedEnum.Three + assert m.ScopedEnum.Three > m.ScopedEnum.Two + assert m.ScopedEnum.Two <= m.ScopedEnum.Three + assert m.ScopedEnum.Two <= m.ScopedEnum.Two + assert m.ScopedEnum.Two >= m.ScopedEnum.Two + assert m.ScopedEnum.Three >= m.ScopedEnum.Two + + +def test_implicit_conversion(): + assert str(m.ClassWithUnscopedEnum.EMode.EFirstMode) == "EMode.EFirstMode" + assert str(m.ClassWithUnscopedEnum.EFirstMode) == "EMode.EFirstMode" + + f = m.ClassWithUnscopedEnum.test_function + first = m.ClassWithUnscopedEnum.EFirstMode + second = m.ClassWithUnscopedEnum.ESecondMode + + assert f(first) == 1 + + assert f(first) == f(first) + assert not f(first) != f(first) + + assert f(first) != f(second) + assert not f(first) == f(second) + + assert f(first) == int(f(first)) + assert not f(first) != int(f(first)) + + assert f(first) != int(f(second)) + assert not f(first) == int(f(second)) + + # noinspection PyDictCreation + x = {f(first): 1, f(second): 2} + x[f(first)] = 3 + x[f(second)] = 4 + # Hashing test + assert str(x) == "{EMode.EFirstMode: 3, EMode.ESecondMode: 4}" + + +def test_binary_operators(): + assert int(m.Flags.Read) == 4 + assert int(m.Flags.Write) == 2 + assert int(m.Flags.Execute) == 1 + assert int(m.Flags.Read | m.Flags.Write | m.Flags.Execute) == 7 + assert int(m.Flags.Read | m.Flags.Write) == 6 + assert int(m.Flags.Read | m.Flags.Execute) == 5 + assert int(m.Flags.Write | m.Flags.Execute) == 3 + assert int(m.Flags.Write | 1) == 3 + + state = m.Flags.Read | m.Flags.Write + assert (state & m.Flags.Read) != 0 + assert (state & m.Flags.Write) != 0 + assert (state & m.Flags.Execute) == 0 + assert (state & 1) == 0 + + state2 = ~state + assert state2 == -7 + assert int(state ^ state2) == -1 + + +def test_enum_to_int(): + m.test_enum_to_int(m.Flags.Read) + m.test_enum_to_int(m.ClassWithUnscopedEnum.EMode.EFirstMode) + m.test_enum_to_uint(m.Flags.Read) + m.test_enum_to_uint(m.ClassWithUnscopedEnum.EMode.EFirstMode) + m.test_enum_to_long_long(m.Flags.Read) + m.test_enum_to_long_long(m.ClassWithUnscopedEnum.EMode.EFirstMode) + + +def test_duplicate_enum_name(): + with pytest.raises(ValueError) as excinfo: + m.register_bad_enum() + assert str(excinfo.value) == 'SimpleEnum: element "ONE" already exists!' diff --git a/wrap/python/pybind11/tests/test_eval.cpp b/wrap/python/pybind11/tests/test_eval.cpp new file mode 100644 index 000000000..e09482191 --- /dev/null +++ b/wrap/python/pybind11/tests/test_eval.cpp @@ -0,0 +1,91 @@ +/* + tests/test_eval.cpp -- Usage of eval() and eval_file() + + Copyright (c) 2016 Klemens D. Morgenstern + + All rights reserved. Use of this source code is governed by a + BSD-style license that can be found in the LICENSE file. +*/ + + +#include +#include "pybind11_tests.h" + +TEST_SUBMODULE(eval_, m) { + // test_evals + + auto global = py::dict(py::module::import("__main__").attr("__dict__")); + + m.def("test_eval_statements", [global]() { + auto local = py::dict(); + local["call_test"] = py::cpp_function([&]() -> int { + return 42; + }); + + // Regular string literal + py::exec( + "message = 'Hello World!'\n" + "x = call_test()", + global, local + ); + + // Multi-line raw string literal + py::exec(R"( + if x == 42: + print(message) + else: + raise RuntimeError + )", global, local + ); + auto x = local["x"].cast(); + + return x == 42; + }); + + m.def("test_eval", [global]() { + auto local = py::dict(); + local["x"] = py::int_(42); + auto x = py::eval("x", global, local); + return x.cast() == 42; + }); + + m.def("test_eval_single_statement", []() { + auto local = py::dict(); + local["call_test"] = py::cpp_function([&]() -> int { + return 42; + }); + + auto result = py::eval("x = call_test()", py::dict(), local); + auto x = local["x"].cast(); + return result.is_none() && x == 42; + }); + + m.def("test_eval_file", [global](py::str filename) { + auto local = py::dict(); + local["y"] = py::int_(43); + + int val_out; + local["call_test2"] = py::cpp_function([&](int value) { val_out = value; }); + + auto result = py::eval_file(filename, global, local); + return val_out == 43 && result.is_none(); + }); + + m.def("test_eval_failure", []() { + try { + py::eval("nonsense code ..."); + } catch (py::error_already_set &) { + return true; + } + return false; + }); + + m.def("test_eval_file_failure", []() { + try { + py::eval_file("non-existing file"); + } catch (std::exception &) { + return true; + } + return false; + }); +} diff --git a/wrap/python/pybind11/tests/test_eval.py b/wrap/python/pybind11/tests/test_eval.py new file mode 100644 index 000000000..bda4ef6bf --- /dev/null +++ b/wrap/python/pybind11/tests/test_eval.py @@ -0,0 +1,17 @@ +import os +from pybind11_tests import eval_ as m + + +def test_evals(capture): + with capture: + assert m.test_eval_statements() + assert capture == "Hello World!" + + assert m.test_eval() + assert m.test_eval_single_statement() + + filename = os.path.join(os.path.dirname(__file__), "test_eval_call.py") + assert m.test_eval_file(filename) + + assert m.test_eval_failure() + assert m.test_eval_file_failure() diff --git a/wrap/python/pybind11/tests/test_eval_call.py b/wrap/python/pybind11/tests/test_eval_call.py new file mode 100644 index 000000000..53c7e721f --- /dev/null +++ b/wrap/python/pybind11/tests/test_eval_call.py @@ -0,0 +1,4 @@ +# This file is called from 'test_eval.py' + +if 'call_test2' in locals(): + call_test2(y) # noqa: F821 undefined name diff --git a/wrap/python/pybind11/tests/test_exceptions.cpp b/wrap/python/pybind11/tests/test_exceptions.cpp new file mode 100644 index 000000000..d30139037 --- /dev/null +++ b/wrap/python/pybind11/tests/test_exceptions.cpp @@ -0,0 +1,196 @@ +/* + tests/test_custom-exceptions.cpp -- exception translation + + Copyright (c) 2016 Pim Schellart + + All rights reserved. Use of this source code is governed by a + BSD-style license that can be found in the LICENSE file. +*/ + +#include "pybind11_tests.h" + +// A type that should be raised as an exception in Python +class MyException : public std::exception { +public: + explicit MyException(const char * m) : message{m} {} + virtual const char * what() const noexcept override {return message.c_str();} +private: + std::string message = ""; +}; + +// A type that should be translated to a standard Python exception +class MyException2 : public std::exception { +public: + explicit MyException2(const char * m) : message{m} {} + virtual const char * what() const noexcept override {return message.c_str();} +private: + std::string message = ""; +}; + +// A type that is not derived from std::exception (and is thus unknown) +class MyException3 { +public: + explicit MyException3(const char * m) : message{m} {} + virtual const char * what() const noexcept {return message.c_str();} +private: + std::string message = ""; +}; + +// A type that should be translated to MyException +// and delegated to its exception translator +class MyException4 : public std::exception { +public: + explicit MyException4(const char * m) : message{m} {} + virtual const char * what() const noexcept override {return message.c_str();} +private: + std::string message = ""; +}; + + +// Like the above, but declared via the helper function +class MyException5 : public std::logic_error { +public: + explicit MyException5(const std::string &what) : std::logic_error(what) {} +}; + +// Inherits from MyException5 +class MyException5_1 : public MyException5 { + using MyException5::MyException5; +}; + +struct PythonCallInDestructor { + PythonCallInDestructor(const py::dict &d) : d(d) {} + ~PythonCallInDestructor() { d["good"] = true; } + + py::dict d; +}; + +TEST_SUBMODULE(exceptions, m) { + m.def("throw_std_exception", []() { + throw std::runtime_error("This exception was intentionally thrown."); + }); + + // make a new custom exception and use it as a translation target + static py::exception ex(m, "MyException"); + py::register_exception_translator([](std::exception_ptr p) { + try { + if (p) std::rethrow_exception(p); + } catch (const MyException &e) { + // Set MyException as the active python error + ex(e.what()); + } + }); + + // register new translator for MyException2 + // no need to store anything here because this type will + // never by visible from Python + py::register_exception_translator([](std::exception_ptr p) { + try { + if (p) std::rethrow_exception(p); + } catch (const MyException2 &e) { + // Translate this exception to a standard RuntimeError + PyErr_SetString(PyExc_RuntimeError, e.what()); + } + }); + + // register new translator for MyException4 + // which will catch it and delegate to the previously registered + // translator for MyException by throwing a new exception + py::register_exception_translator([](std::exception_ptr p) { + try { + if (p) std::rethrow_exception(p); + } catch (const MyException4 &e) { + throw MyException(e.what()); + } + }); + + // A simple exception translation: + auto ex5 = py::register_exception(m, "MyException5"); + // A slightly more complicated one that declares MyException5_1 as a subclass of MyException5 + py::register_exception(m, "MyException5_1", ex5.ptr()); + + m.def("throws1", []() { throw MyException("this error should go to a custom type"); }); + m.def("throws2", []() { throw MyException2("this error should go to a standard Python exception"); }); + m.def("throws3", []() { throw MyException3("this error cannot be translated"); }); + m.def("throws4", []() { throw MyException4("this error is rethrown"); }); + m.def("throws5", []() { throw MyException5("this is a helper-defined translated exception"); }); + m.def("throws5_1", []() { throw MyException5_1("MyException5 subclass"); }); + m.def("throws_logic_error", []() { throw std::logic_error("this error should fall through to the standard handler"); }); + m.def("exception_matches", []() { + py::dict foo; + try { + // Assign to a py::object to force read access of nonexistent dict entry + py::object o = foo["bar"]; + } + catch (py::error_already_set& ex) { + if (!ex.matches(PyExc_KeyError)) throw; + return true; + } + return false; + }); + m.def("exception_matches_base", []() { + py::dict foo; + try { + // Assign to a py::object to force read access of nonexistent dict entry + py::object o = foo["bar"]; + } + catch (py::error_already_set &ex) { + if (!ex.matches(PyExc_Exception)) throw; + return true; + } + return false; + }); + m.def("modulenotfound_exception_matches_base", []() { + try { + // On Python >= 3.6, this raises a ModuleNotFoundError, a subclass of ImportError + py::module::import("nonexistent"); + } + catch (py::error_already_set &ex) { + if (!ex.matches(PyExc_ImportError)) throw; + return true; + } + return false; + }); + + m.def("throw_already_set", [](bool err) { + if (err) + PyErr_SetString(PyExc_ValueError, "foo"); + try { + throw py::error_already_set(); + } catch (const std::runtime_error& e) { + if ((err && e.what() != std::string("ValueError: foo")) || + (!err && e.what() != std::string("Unknown internal error occurred"))) + { + PyErr_Clear(); + throw std::runtime_error("error message mismatch"); + } + } + PyErr_Clear(); + if (err) + PyErr_SetString(PyExc_ValueError, "foo"); + throw py::error_already_set(); + }); + + m.def("python_call_in_destructor", [](py::dict d) { + try { + PythonCallInDestructor set_dict_in_destructor(d); + PyErr_SetString(PyExc_ValueError, "foo"); + throw py::error_already_set(); + } catch (const py::error_already_set&) { + return true; + } + return false; + }); + + // test_nested_throws + m.def("try_catch", [m](py::object exc_type, py::function f, py::args args) { + try { f(*args); } + catch (py::error_already_set &ex) { + if (ex.matches(exc_type)) + py::print(ex.what()); + else + throw; + } + }); + +} diff --git a/wrap/python/pybind11/tests/test_exceptions.py b/wrap/python/pybind11/tests/test_exceptions.py new file mode 100644 index 000000000..6edff9fe4 --- /dev/null +++ b/wrap/python/pybind11/tests/test_exceptions.py @@ -0,0 +1,146 @@ +import pytest + +from pybind11_tests import exceptions as m +import pybind11_cross_module_tests as cm + + +def test_std_exception(msg): + with pytest.raises(RuntimeError) as excinfo: + m.throw_std_exception() + assert msg(excinfo.value) == "This exception was intentionally thrown." + + +def test_error_already_set(msg): + with pytest.raises(RuntimeError) as excinfo: + m.throw_already_set(False) + assert msg(excinfo.value) == "Unknown internal error occurred" + + with pytest.raises(ValueError) as excinfo: + m.throw_already_set(True) + assert msg(excinfo.value) == "foo" + + +def test_cross_module_exceptions(): + with pytest.raises(RuntimeError) as excinfo: + cm.raise_runtime_error() + assert str(excinfo.value) == "My runtime error" + + with pytest.raises(ValueError) as excinfo: + cm.raise_value_error() + assert str(excinfo.value) == "My value error" + + with pytest.raises(ValueError) as excinfo: + cm.throw_pybind_value_error() + assert str(excinfo.value) == "pybind11 value error" + + with pytest.raises(TypeError) as excinfo: + cm.throw_pybind_type_error() + assert str(excinfo.value) == "pybind11 type error" + + with pytest.raises(StopIteration) as excinfo: + cm.throw_stop_iteration() + + +def test_python_call_in_catch(): + d = {} + assert m.python_call_in_destructor(d) is True + assert d["good"] is True + + +def test_exception_matches(): + assert m.exception_matches() + assert m.exception_matches_base() + assert m.modulenotfound_exception_matches_base() + + +def test_custom(msg): + # Can we catch a MyException? + with pytest.raises(m.MyException) as excinfo: + m.throws1() + assert msg(excinfo.value) == "this error should go to a custom type" + + # Can we translate to standard Python exceptions? + with pytest.raises(RuntimeError) as excinfo: + m.throws2() + assert msg(excinfo.value) == "this error should go to a standard Python exception" + + # Can we handle unknown exceptions? + with pytest.raises(RuntimeError) as excinfo: + m.throws3() + assert msg(excinfo.value) == "Caught an unknown exception!" + + # Can we delegate to another handler by rethrowing? + with pytest.raises(m.MyException) as excinfo: + m.throws4() + assert msg(excinfo.value) == "this error is rethrown" + + # Can we fall-through to the default handler? + with pytest.raises(RuntimeError) as excinfo: + m.throws_logic_error() + assert msg(excinfo.value) == "this error should fall through to the standard handler" + + # Can we handle a helper-declared exception? + with pytest.raises(m.MyException5) as excinfo: + m.throws5() + assert msg(excinfo.value) == "this is a helper-defined translated exception" + + # Exception subclassing: + with pytest.raises(m.MyException5) as excinfo: + m.throws5_1() + assert msg(excinfo.value) == "MyException5 subclass" + assert isinstance(excinfo.value, m.MyException5_1) + + with pytest.raises(m.MyException5_1) as excinfo: + m.throws5_1() + assert msg(excinfo.value) == "MyException5 subclass" + + with pytest.raises(m.MyException5) as excinfo: + try: + m.throws5() + except m.MyException5_1: + raise RuntimeError("Exception error: caught child from parent") + assert msg(excinfo.value) == "this is a helper-defined translated exception" + + +def test_nested_throws(capture): + """Tests nested (e.g. C++ -> Python -> C++) exception handling""" + + def throw_myex(): + raise m.MyException("nested error") + + def throw_myex5(): + raise m.MyException5("nested error 5") + + # In the comments below, the exception is caught in the first step, thrown in the last step + + # C++ -> Python + with capture: + m.try_catch(m.MyException5, throw_myex5) + assert str(capture).startswith("MyException5: nested error 5") + + # Python -> C++ -> Python + with pytest.raises(m.MyException) as excinfo: + m.try_catch(m.MyException5, throw_myex) + assert str(excinfo.value) == "nested error" + + def pycatch(exctype, f, *args): + try: + f(*args) + except m.MyException as e: + print(e) + + # C++ -> Python -> C++ -> Python + with capture: + m.try_catch( + m.MyException5, pycatch, m.MyException, m.try_catch, m.MyException, throw_myex5) + assert str(capture).startswith("MyException5: nested error 5") + + # C++ -> Python -> C++ + with capture: + m.try_catch(m.MyException, pycatch, m.MyException5, m.throws4) + assert capture == "this error is rethrown" + + # Python -> C++ -> Python -> C++ + with pytest.raises(m.MyException5) as excinfo: + m.try_catch(m.MyException, pycatch, m.MyException, m.throws5) + assert str(excinfo.value) == "this is a helper-defined translated exception" diff --git a/wrap/python/pybind11/tests/test_factory_constructors.cpp b/wrap/python/pybind11/tests/test_factory_constructors.cpp new file mode 100644 index 000000000..5cfbfdc3f --- /dev/null +++ b/wrap/python/pybind11/tests/test_factory_constructors.cpp @@ -0,0 +1,338 @@ +/* + tests/test_factory_constructors.cpp -- tests construction from a factory function + via py::init_factory() + + Copyright (c) 2017 Jason Rhinelander + + All rights reserved. Use of this source code is governed by a + BSD-style license that can be found in the LICENSE file. +*/ + +#include "pybind11_tests.h" +#include "constructor_stats.h" +#include + +// Classes for testing python construction via C++ factory function: +// Not publicly constructible, copyable, or movable: +class TestFactory1 { + friend class TestFactoryHelper; + TestFactory1() : value("(empty)") { print_default_created(this); } + TestFactory1(int v) : value(std::to_string(v)) { print_created(this, value); } + TestFactory1(std::string v) : value(std::move(v)) { print_created(this, value); } + TestFactory1(TestFactory1 &&) = delete; + TestFactory1(const TestFactory1 &) = delete; + TestFactory1 &operator=(TestFactory1 &&) = delete; + TestFactory1 &operator=(const TestFactory1 &) = delete; +public: + std::string value; + ~TestFactory1() { print_destroyed(this); } +}; +// Non-public construction, but moveable: +class TestFactory2 { + friend class TestFactoryHelper; + TestFactory2() : value("(empty2)") { print_default_created(this); } + TestFactory2(int v) : value(std::to_string(v)) { print_created(this, value); } + TestFactory2(std::string v) : value(std::move(v)) { print_created(this, value); } +public: + TestFactory2(TestFactory2 &&m) { value = std::move(m.value); print_move_created(this); } + TestFactory2 &operator=(TestFactory2 &&m) { value = std::move(m.value); print_move_assigned(this); return *this; } + std::string value; + ~TestFactory2() { print_destroyed(this); } +}; +// Mixed direct/factory construction: +class TestFactory3 { +protected: + friend class TestFactoryHelper; + TestFactory3() : value("(empty3)") { print_default_created(this); } + TestFactory3(int v) : value(std::to_string(v)) { print_created(this, value); } +public: + TestFactory3(std::string v) : value(std::move(v)) { print_created(this, value); } + TestFactory3(TestFactory3 &&m) { value = std::move(m.value); print_move_created(this); } + TestFactory3 &operator=(TestFactory3 &&m) { value = std::move(m.value); print_move_assigned(this); return *this; } + std::string value; + virtual ~TestFactory3() { print_destroyed(this); } +}; +// Inheritance test +class TestFactory4 : public TestFactory3 { +public: + TestFactory4() : TestFactory3() { print_default_created(this); } + TestFactory4(int v) : TestFactory3(v) { print_created(this, v); } + virtual ~TestFactory4() { print_destroyed(this); } +}; +// Another class for an invalid downcast test +class TestFactory5 : public TestFactory3 { +public: + TestFactory5(int i) : TestFactory3(i) { print_created(this, i); } + virtual ~TestFactory5() { print_destroyed(this); } +}; + +class TestFactory6 { +protected: + int value; + bool alias = false; +public: + TestFactory6(int i) : value{i} { print_created(this, i); } + TestFactory6(TestFactory6 &&f) { print_move_created(this); value = f.value; alias = f.alias; } + TestFactory6(const TestFactory6 &f) { print_copy_created(this); value = f.value; alias = f.alias; } + virtual ~TestFactory6() { print_destroyed(this); } + virtual int get() { return value; } + bool has_alias() { return alias; } +}; +class PyTF6 : public TestFactory6 { +public: + // Special constructor that allows the factory to construct a PyTF6 from a TestFactory6 only + // when an alias is needed: + PyTF6(TestFactory6 &&base) : TestFactory6(std::move(base)) { alias = true; print_created(this, "move", value); } + PyTF6(int i) : TestFactory6(i) { alias = true; print_created(this, i); } + PyTF6(PyTF6 &&f) : TestFactory6(std::move(f)) { print_move_created(this); } + PyTF6(const PyTF6 &f) : TestFactory6(f) { print_copy_created(this); } + PyTF6(std::string s) : TestFactory6((int) s.size()) { alias = true; print_created(this, s); } + virtual ~PyTF6() { print_destroyed(this); } + int get() override { PYBIND11_OVERLOAD(int, TestFactory6, get, /*no args*/); } +}; + +class TestFactory7 { +protected: + int value; + bool alias = false; +public: + TestFactory7(int i) : value{i} { print_created(this, i); } + TestFactory7(TestFactory7 &&f) { print_move_created(this); value = f.value; alias = f.alias; } + TestFactory7(const TestFactory7 &f) { print_copy_created(this); value = f.value; alias = f.alias; } + virtual ~TestFactory7() { print_destroyed(this); } + virtual int get() { return value; } + bool has_alias() { return alias; } +}; +class PyTF7 : public TestFactory7 { +public: + PyTF7(int i) : TestFactory7(i) { alias = true; print_created(this, i); } + PyTF7(PyTF7 &&f) : TestFactory7(std::move(f)) { print_move_created(this); } + PyTF7(const PyTF7 &f) : TestFactory7(f) { print_copy_created(this); } + virtual ~PyTF7() { print_destroyed(this); } + int get() override { PYBIND11_OVERLOAD(int, TestFactory7, get, /*no args*/); } +}; + + +class TestFactoryHelper { +public: + // Non-movable, non-copyable type: + // Return via pointer: + static TestFactory1 *construct1() { return new TestFactory1(); } + // Holder: + static std::unique_ptr construct1(int a) { return std::unique_ptr(new TestFactory1(a)); } + // pointer again + static TestFactory1 *construct1_string(std::string a) { return new TestFactory1(a); } + + // Moveable type: + // pointer: + static TestFactory2 *construct2() { return new TestFactory2(); } + // holder: + static std::unique_ptr construct2(int a) { return std::unique_ptr(new TestFactory2(a)); } + // by value moving: + static TestFactory2 construct2(std::string a) { return TestFactory2(a); } + + // shared_ptr holder type: + // pointer: + static TestFactory3 *construct3() { return new TestFactory3(); } + // holder: + static std::shared_ptr construct3(int a) { return std::shared_ptr(new TestFactory3(a)); } +}; + +TEST_SUBMODULE(factory_constructors, m) { + + // Define various trivial types to allow simpler overload resolution: + py::module m_tag = m.def_submodule("tag"); +#define MAKE_TAG_TYPE(Name) \ + struct Name##_tag {}; \ + py::class_(m_tag, #Name "_tag").def(py::init<>()); \ + m_tag.attr(#Name) = py::cast(Name##_tag{}) + MAKE_TAG_TYPE(pointer); + MAKE_TAG_TYPE(unique_ptr); + MAKE_TAG_TYPE(move); + MAKE_TAG_TYPE(shared_ptr); + MAKE_TAG_TYPE(derived); + MAKE_TAG_TYPE(TF4); + MAKE_TAG_TYPE(TF5); + MAKE_TAG_TYPE(null_ptr); + MAKE_TAG_TYPE(base); + MAKE_TAG_TYPE(invalid_base); + MAKE_TAG_TYPE(alias); + MAKE_TAG_TYPE(unaliasable); + MAKE_TAG_TYPE(mixed); + + // test_init_factory_basic, test_bad_type + py::class_(m, "TestFactory1") + .def(py::init([](unique_ptr_tag, int v) { return TestFactoryHelper::construct1(v); })) + .def(py::init(&TestFactoryHelper::construct1_string)) // raw function pointer + .def(py::init([](pointer_tag) { return TestFactoryHelper::construct1(); })) + .def(py::init([](py::handle, int v, py::handle) { return TestFactoryHelper::construct1(v); })) + .def_readwrite("value", &TestFactory1::value) + ; + py::class_(m, "TestFactory2") + .def(py::init([](pointer_tag, int v) { return TestFactoryHelper::construct2(v); })) + .def(py::init([](unique_ptr_tag, std::string v) { return TestFactoryHelper::construct2(v); })) + .def(py::init([](move_tag) { return TestFactoryHelper::construct2(); })) + .def_readwrite("value", &TestFactory2::value) + ; + + // Stateful & reused: + int c = 1; + auto c4a = [c](pointer_tag, TF4_tag, int a) { (void) c; return new TestFactory4(a);}; + + // test_init_factory_basic, test_init_factory_casting + py::class_>(m, "TestFactory3") + .def(py::init([](pointer_tag, int v) { return TestFactoryHelper::construct3(v); })) + .def(py::init([](shared_ptr_tag) { return TestFactoryHelper::construct3(); })) + .def("__init__", [](TestFactory3 &self, std::string v) { new (&self) TestFactory3(v); }) // placement-new ctor + + // factories returning a derived type: + .def(py::init(c4a)) // derived ptr + .def(py::init([](pointer_tag, TF5_tag, int a) { return new TestFactory5(a); })) + // derived shared ptr: + .def(py::init([](shared_ptr_tag, TF4_tag, int a) { return std::make_shared(a); })) + .def(py::init([](shared_ptr_tag, TF5_tag, int a) { return std::make_shared(a); })) + + // Returns nullptr: + .def(py::init([](null_ptr_tag) { return (TestFactory3 *) nullptr; })) + + .def_readwrite("value", &TestFactory3::value) + ; + + // test_init_factory_casting + py::class_>(m, "TestFactory4") + .def(py::init(c4a)) // pointer + ; + + // Doesn't need to be registered, but registering makes getting ConstructorStats easier: + py::class_>(m, "TestFactory5"); + + // test_init_factory_alias + // Alias testing + py::class_(m, "TestFactory6") + .def(py::init([](base_tag, int i) { return TestFactory6(i); })) + .def(py::init([](alias_tag, int i) { return PyTF6(i); })) + .def(py::init([](alias_tag, std::string s) { return PyTF6(s); })) + .def(py::init([](alias_tag, pointer_tag, int i) { return new PyTF6(i); })) + .def(py::init([](base_tag, pointer_tag, int i) { return new TestFactory6(i); })) + .def(py::init([](base_tag, alias_tag, pointer_tag, int i) { return (TestFactory6 *) new PyTF6(i); })) + + .def("get", &TestFactory6::get) + .def("has_alias", &TestFactory6::has_alias) + + .def_static("get_cstats", &ConstructorStats::get, py::return_value_policy::reference) + .def_static("get_alias_cstats", &ConstructorStats::get, py::return_value_policy::reference) + ; + + // test_init_factory_dual + // Separate alias constructor testing + py::class_>(m, "TestFactory7") + .def(py::init( + [](int i) { return TestFactory7(i); }, + [](int i) { return PyTF7(i); })) + .def(py::init( + [](pointer_tag, int i) { return new TestFactory7(i); }, + [](pointer_tag, int i) { return new PyTF7(i); })) + .def(py::init( + [](mixed_tag, int i) { return new TestFactory7(i); }, + [](mixed_tag, int i) { return PyTF7(i); })) + .def(py::init( + [](mixed_tag, std::string s) { return TestFactory7((int) s.size()); }, + [](mixed_tag, std::string s) { return new PyTF7((int) s.size()); })) + .def(py::init( + [](base_tag, pointer_tag, int i) { return new TestFactory7(i); }, + [](base_tag, pointer_tag, int i) { return (TestFactory7 *) new PyTF7(i); })) + .def(py::init( + [](alias_tag, pointer_tag, int i) { return new PyTF7(i); }, + [](alias_tag, pointer_tag, int i) { return new PyTF7(10*i); })) + .def(py::init( + [](shared_ptr_tag, base_tag, int i) { return std::make_shared(i); }, + [](shared_ptr_tag, base_tag, int i) { auto *p = new PyTF7(i); return std::shared_ptr(p); })) + .def(py::init( + [](shared_ptr_tag, invalid_base_tag, int i) { return std::make_shared(i); }, + [](shared_ptr_tag, invalid_base_tag, int i) { return std::make_shared(i); })) // <-- invalid alias factory + + .def("get", &TestFactory7::get) + .def("has_alias", &TestFactory7::has_alias) + + .def_static("get_cstats", &ConstructorStats::get, py::return_value_policy::reference) + .def_static("get_alias_cstats", &ConstructorStats::get, py::return_value_policy::reference) + ; + + // test_placement_new_alternative + // Class with a custom new operator but *without* a placement new operator (issue #948) + class NoPlacementNew { + public: + NoPlacementNew(int i) : i(i) { } + static void *operator new(std::size_t s) { + auto *p = ::operator new(s); + py::print("operator new called, returning", reinterpret_cast(p)); + return p; + } + static void operator delete(void *p) { + py::print("operator delete called on", reinterpret_cast(p)); + ::operator delete(p); + } + int i; + }; + // As of 2.2, `py::init` no longer requires placement new + py::class_(m, "NoPlacementNew") + .def(py::init()) + .def(py::init([]() { return new NoPlacementNew(100); })) + .def_readwrite("i", &NoPlacementNew::i) + ; + + + // test_reallocations + // Class that has verbose operator_new/operator_delete calls + struct NoisyAlloc { + NoisyAlloc(const NoisyAlloc &) = default; + NoisyAlloc(int i) { py::print(py::str("NoisyAlloc(int {})").format(i)); } + NoisyAlloc(double d) { py::print(py::str("NoisyAlloc(double {})").format(d)); } + ~NoisyAlloc() { py::print("~NoisyAlloc()"); } + + static void *operator new(size_t s) { py::print("noisy new"); return ::operator new(s); } + static void *operator new(size_t, void *p) { py::print("noisy placement new"); return p; } + static void operator delete(void *p, size_t) { py::print("noisy delete"); ::operator delete(p); } + static void operator delete(void *, void *) { py::print("noisy placement delete"); } +#if defined(_MSC_VER) && _MSC_VER < 1910 + // MSVC 2015 bug: the above "noisy delete" isn't invoked (fixed in MSVC 2017) + static void operator delete(void *p) { py::print("noisy delete"); ::operator delete(p); } +#endif + }; + py::class_(m, "NoisyAlloc") + // Since these overloads have the same number of arguments, the dispatcher will try each of + // them until the arguments convert. Thus we can get a pre-allocation here when passing a + // single non-integer: + .def("__init__", [](NoisyAlloc *a, int i) { new (a) NoisyAlloc(i); }) // Regular constructor, runs first, requires preallocation + .def(py::init([](double d) { return new NoisyAlloc(d); })) + + // The two-argument version: first the factory pointer overload. + .def(py::init([](int i, int) { return new NoisyAlloc(i); })) + // Return-by-value: + .def(py::init([](double d, int) { return NoisyAlloc(d); })) + // Old-style placement new init; requires preallocation + .def("__init__", [](NoisyAlloc &a, double d, double) { new (&a) NoisyAlloc(d); }) + // Requires deallocation of previous overload preallocated value: + .def(py::init([](int i, double) { return new NoisyAlloc(i); })) + // Regular again: requires yet another preallocation + .def("__init__", [](NoisyAlloc &a, int i, std::string) { new (&a) NoisyAlloc(i); }) + ; + + + + + // static_assert testing (the following def's should all fail with appropriate compilation errors): +#if 0 + struct BadF1Base {}; + struct BadF1 : BadF1Base {}; + struct PyBadF1 : BadF1 {}; + py::class_> bf1(m, "BadF1"); + // wrapped factory function must return a compatible pointer, holder, or value + bf1.def(py::init([]() { return 3; })); + // incompatible factory function pointer return type + bf1.def(py::init([]() { static int three = 3; return &three; })); + // incompatible factory function std::shared_ptr return type: cannot convert shared_ptr to holder + // (non-polymorphic base) + bf1.def(py::init([]() { return std::shared_ptr(new BadF1()); })); +#endif +} diff --git a/wrap/python/pybind11/tests/test_factory_constructors.py b/wrap/python/pybind11/tests/test_factory_constructors.py new file mode 100644 index 000000000..78a3910ad --- /dev/null +++ b/wrap/python/pybind11/tests/test_factory_constructors.py @@ -0,0 +1,459 @@ +import pytest +import re + +from pybind11_tests import factory_constructors as m +from pybind11_tests.factory_constructors import tag +from pybind11_tests import ConstructorStats + + +def test_init_factory_basic(): + """Tests py::init_factory() wrapper around various ways of returning the object""" + + cstats = [ConstructorStats.get(c) for c in [m.TestFactory1, m.TestFactory2, m.TestFactory3]] + cstats[0].alive() # force gc + n_inst = ConstructorStats.detail_reg_inst() + + x1 = m.TestFactory1(tag.unique_ptr, 3) + assert x1.value == "3" + y1 = m.TestFactory1(tag.pointer) + assert y1.value == "(empty)" + z1 = m.TestFactory1("hi!") + assert z1.value == "hi!" + + assert ConstructorStats.detail_reg_inst() == n_inst + 3 + + x2 = m.TestFactory2(tag.move) + assert x2.value == "(empty2)" + y2 = m.TestFactory2(tag.pointer, 7) + assert y2.value == "7" + z2 = m.TestFactory2(tag.unique_ptr, "hi again") + assert z2.value == "hi again" + + assert ConstructorStats.detail_reg_inst() == n_inst + 6 + + x3 = m.TestFactory3(tag.shared_ptr) + assert x3.value == "(empty3)" + y3 = m.TestFactory3(tag.pointer, 42) + assert y3.value == "42" + z3 = m.TestFactory3("bye") + assert z3.value == "bye" + + with pytest.raises(TypeError) as excinfo: + m.TestFactory3(tag.null_ptr) + assert str(excinfo.value) == "pybind11::init(): factory function returned nullptr" + + assert [i.alive() for i in cstats] == [3, 3, 3] + assert ConstructorStats.detail_reg_inst() == n_inst + 9 + + del x1, y2, y3, z3 + assert [i.alive() for i in cstats] == [2, 2, 1] + assert ConstructorStats.detail_reg_inst() == n_inst + 5 + del x2, x3, y1, z1, z2 + assert [i.alive() for i in cstats] == [0, 0, 0] + assert ConstructorStats.detail_reg_inst() == n_inst + + assert [i.values() for i in cstats] == [ + ["3", "hi!"], + ["7", "hi again"], + ["42", "bye"] + ] + assert [i.default_constructions for i in cstats] == [1, 1, 1] + + +def test_init_factory_signature(msg): + with pytest.raises(TypeError) as excinfo: + m.TestFactory1("invalid", "constructor", "arguments") + assert msg(excinfo.value) == """ + __init__(): incompatible constructor arguments. The following argument types are supported: + 1. m.factory_constructors.TestFactory1(arg0: m.factory_constructors.tag.unique_ptr_tag, arg1: int) + 2. m.factory_constructors.TestFactory1(arg0: str) + 3. m.factory_constructors.TestFactory1(arg0: m.factory_constructors.tag.pointer_tag) + 4. m.factory_constructors.TestFactory1(arg0: handle, arg1: int, arg2: handle) + + Invoked with: 'invalid', 'constructor', 'arguments' + """ # noqa: E501 line too long + + assert msg(m.TestFactory1.__init__.__doc__) == """ + __init__(*args, **kwargs) + Overloaded function. + + 1. __init__(self: m.factory_constructors.TestFactory1, arg0: m.factory_constructors.tag.unique_ptr_tag, arg1: int) -> None + + 2. __init__(self: m.factory_constructors.TestFactory1, arg0: str) -> None + + 3. __init__(self: m.factory_constructors.TestFactory1, arg0: m.factory_constructors.tag.pointer_tag) -> None + + 4. __init__(self: m.factory_constructors.TestFactory1, arg0: handle, arg1: int, arg2: handle) -> None + """ # noqa: E501 line too long + + +def test_init_factory_casting(): + """Tests py::init_factory() wrapper with various upcasting and downcasting returns""" + + cstats = [ConstructorStats.get(c) for c in [m.TestFactory3, m.TestFactory4, m.TestFactory5]] + cstats[0].alive() # force gc + n_inst = ConstructorStats.detail_reg_inst() + + # Construction from derived references: + a = m.TestFactory3(tag.pointer, tag.TF4, 4) + assert a.value == "4" + b = m.TestFactory3(tag.shared_ptr, tag.TF4, 5) + assert b.value == "5" + c = m.TestFactory3(tag.pointer, tag.TF5, 6) + assert c.value == "6" + d = m.TestFactory3(tag.shared_ptr, tag.TF5, 7) + assert d.value == "7" + + assert ConstructorStats.detail_reg_inst() == n_inst + 4 + + # Shared a lambda with TF3: + e = m.TestFactory4(tag.pointer, tag.TF4, 8) + assert e.value == "8" + + assert ConstructorStats.detail_reg_inst() == n_inst + 5 + assert [i.alive() for i in cstats] == [5, 3, 2] + + del a + assert [i.alive() for i in cstats] == [4, 2, 2] + assert ConstructorStats.detail_reg_inst() == n_inst + 4 + + del b, c, e + assert [i.alive() for i in cstats] == [1, 0, 1] + assert ConstructorStats.detail_reg_inst() == n_inst + 1 + + del d + assert [i.alive() for i in cstats] == [0, 0, 0] + assert ConstructorStats.detail_reg_inst() == n_inst + + assert [i.values() for i in cstats] == [ + ["4", "5", "6", "7", "8"], + ["4", "5", "8"], + ["6", "7"] + ] + + +def test_init_factory_alias(): + """Tests py::init_factory() wrapper with value conversions and alias types""" + + cstats = [m.TestFactory6.get_cstats(), m.TestFactory6.get_alias_cstats()] + cstats[0].alive() # force gc + n_inst = ConstructorStats.detail_reg_inst() + + a = m.TestFactory6(tag.base, 1) + assert a.get() == 1 + assert not a.has_alias() + b = m.TestFactory6(tag.alias, "hi there") + assert b.get() == 8 + assert b.has_alias() + c = m.TestFactory6(tag.alias, 3) + assert c.get() == 3 + assert c.has_alias() + d = m.TestFactory6(tag.alias, tag.pointer, 4) + assert d.get() == 4 + assert d.has_alias() + e = m.TestFactory6(tag.base, tag.pointer, 5) + assert e.get() == 5 + assert not e.has_alias() + f = m.TestFactory6(tag.base, tag.alias, tag.pointer, 6) + assert f.get() == 6 + assert f.has_alias() + + assert ConstructorStats.detail_reg_inst() == n_inst + 6 + assert [i.alive() for i in cstats] == [6, 4] + + del a, b, e + assert [i.alive() for i in cstats] == [3, 3] + assert ConstructorStats.detail_reg_inst() == n_inst + 3 + del f, c, d + assert [i.alive() for i in cstats] == [0, 0] + assert ConstructorStats.detail_reg_inst() == n_inst + + class MyTest(m.TestFactory6): + def __init__(self, *args): + m.TestFactory6.__init__(self, *args) + + def get(self): + return -5 + m.TestFactory6.get(self) + + # Return Class by value, moved into new alias: + z = MyTest(tag.base, 123) + assert z.get() == 118 + assert z.has_alias() + + # Return alias by value, moved into new alias: + y = MyTest(tag.alias, "why hello!") + assert y.get() == 5 + assert y.has_alias() + + # Return Class by pointer, moved into new alias then original destroyed: + x = MyTest(tag.base, tag.pointer, 47) + assert x.get() == 42 + assert x.has_alias() + + assert ConstructorStats.detail_reg_inst() == n_inst + 3 + assert [i.alive() for i in cstats] == [3, 3] + del x, y, z + assert [i.alive() for i in cstats] == [0, 0] + assert ConstructorStats.detail_reg_inst() == n_inst + + assert [i.values() for i in cstats] == [ + ["1", "8", "3", "4", "5", "6", "123", "10", "47"], + ["hi there", "3", "4", "6", "move", "123", "why hello!", "move", "47"] + ] + + +def test_init_factory_dual(): + """Tests init factory functions with dual main/alias factory functions""" + from pybind11_tests.factory_constructors import TestFactory7 + + cstats = [TestFactory7.get_cstats(), TestFactory7.get_alias_cstats()] + cstats[0].alive() # force gc + n_inst = ConstructorStats.detail_reg_inst() + + class PythFactory7(TestFactory7): + def get(self): + return 100 + TestFactory7.get(self) + + a1 = TestFactory7(1) + a2 = PythFactory7(2) + assert a1.get() == 1 + assert a2.get() == 102 + assert not a1.has_alias() + assert a2.has_alias() + + b1 = TestFactory7(tag.pointer, 3) + b2 = PythFactory7(tag.pointer, 4) + assert b1.get() == 3 + assert b2.get() == 104 + assert not b1.has_alias() + assert b2.has_alias() + + c1 = TestFactory7(tag.mixed, 5) + c2 = PythFactory7(tag.mixed, 6) + assert c1.get() == 5 + assert c2.get() == 106 + assert not c1.has_alias() + assert c2.has_alias() + + d1 = TestFactory7(tag.base, tag.pointer, 7) + d2 = PythFactory7(tag.base, tag.pointer, 8) + assert d1.get() == 7 + assert d2.get() == 108 + assert not d1.has_alias() + assert d2.has_alias() + + # Both return an alias; the second multiplies the value by 10: + e1 = TestFactory7(tag.alias, tag.pointer, 9) + e2 = PythFactory7(tag.alias, tag.pointer, 10) + assert e1.get() == 9 + assert e2.get() == 200 + assert e1.has_alias() + assert e2.has_alias() + + f1 = TestFactory7(tag.shared_ptr, tag.base, 11) + f2 = PythFactory7(tag.shared_ptr, tag.base, 12) + assert f1.get() == 11 + assert f2.get() == 112 + assert not f1.has_alias() + assert f2.has_alias() + + g1 = TestFactory7(tag.shared_ptr, tag.invalid_base, 13) + assert g1.get() == 13 + assert not g1.has_alias() + with pytest.raises(TypeError) as excinfo: + PythFactory7(tag.shared_ptr, tag.invalid_base, 14) + assert (str(excinfo.value) == + "pybind11::init(): construction failed: returned holder-wrapped instance is not an " + "alias instance") + + assert [i.alive() for i in cstats] == [13, 7] + assert ConstructorStats.detail_reg_inst() == n_inst + 13 + + del a1, a2, b1, d1, e1, e2 + assert [i.alive() for i in cstats] == [7, 4] + assert ConstructorStats.detail_reg_inst() == n_inst + 7 + del b2, c1, c2, d2, f1, f2, g1 + assert [i.alive() for i in cstats] == [0, 0] + assert ConstructorStats.detail_reg_inst() == n_inst + + assert [i.values() for i in cstats] == [ + ["1", "2", "3", "4", "5", "6", "7", "8", "9", "100", "11", "12", "13", "14"], + ["2", "4", "6", "8", "9", "100", "12"] + ] + + +def test_no_placement_new(capture): + """Prior to 2.2, `py::init<...>` relied on the type supporting placement + new; this tests a class without placement new support.""" + with capture: + a = m.NoPlacementNew(123) + + found = re.search(r'^operator new called, returning (\d+)\n$', str(capture)) + assert found + assert a.i == 123 + with capture: + del a + pytest.gc_collect() + assert capture == "operator delete called on " + found.group(1) + + with capture: + b = m.NoPlacementNew() + + found = re.search(r'^operator new called, returning (\d+)\n$', str(capture)) + assert found + assert b.i == 100 + with capture: + del b + pytest.gc_collect() + assert capture == "operator delete called on " + found.group(1) + + +def test_multiple_inheritance(): + class MITest(m.TestFactory1, m.TestFactory2): + def __init__(self): + m.TestFactory1.__init__(self, tag.unique_ptr, 33) + m.TestFactory2.__init__(self, tag.move) + + a = MITest() + assert m.TestFactory1.value.fget(a) == "33" + assert m.TestFactory2.value.fget(a) == "(empty2)" + + +def create_and_destroy(*args): + a = m.NoisyAlloc(*args) + print("---") + del a + pytest.gc_collect() + + +def strip_comments(s): + return re.sub(r'\s+#.*', '', s) + + +def test_reallocations(capture, msg): + """When the constructor is overloaded, previous overloads can require a preallocated value. + This test makes sure that such preallocated values only happen when they might be necessary, + and that they are deallocated properly""" + + pytest.gc_collect() + + with capture: + create_and_destroy(1) + assert msg(capture) == """ + noisy new + noisy placement new + NoisyAlloc(int 1) + --- + ~NoisyAlloc() + noisy delete + """ + with capture: + create_and_destroy(1.5) + assert msg(capture) == strip_comments(""" + noisy new # allocation required to attempt first overload + noisy delete # have to dealloc before considering factory init overload + noisy new # pointer factory calling "new", part 1: allocation + NoisyAlloc(double 1.5) # ... part two, invoking constructor + --- + ~NoisyAlloc() # Destructor + noisy delete # operator delete + """) + + with capture: + create_and_destroy(2, 3) + assert msg(capture) == strip_comments(""" + noisy new # pointer factory calling "new", allocation + NoisyAlloc(int 2) # constructor + --- + ~NoisyAlloc() # Destructor + noisy delete # operator delete + """) + + with capture: + create_and_destroy(2.5, 3) + assert msg(capture) == strip_comments(""" + NoisyAlloc(double 2.5) # construction (local func variable: operator_new not called) + noisy new # return-by-value "new" part 1: allocation + ~NoisyAlloc() # moved-away local func variable destruction + --- + ~NoisyAlloc() # Destructor + noisy delete # operator delete + """) + + with capture: + create_and_destroy(3.5, 4.5) + assert msg(capture) == strip_comments(""" + noisy new # preallocation needed before invoking placement-new overload + noisy placement new # Placement new + NoisyAlloc(double 3.5) # construction + --- + ~NoisyAlloc() # Destructor + noisy delete # operator delete + """) + + with capture: + create_and_destroy(4, 0.5) + assert msg(capture) == strip_comments(""" + noisy new # preallocation needed before invoking placement-new overload + noisy delete # deallocation of preallocated storage + noisy new # Factory pointer allocation + NoisyAlloc(int 4) # factory pointer construction + --- + ~NoisyAlloc() # Destructor + noisy delete # operator delete + """) + + with capture: + create_and_destroy(5, "hi") + assert msg(capture) == strip_comments(""" + noisy new # preallocation needed before invoking first placement new + noisy delete # delete before considering new-style constructor + noisy new # preallocation for second placement new + noisy placement new # Placement new in the second placement new overload + NoisyAlloc(int 5) # construction + --- + ~NoisyAlloc() # Destructor + noisy delete # operator delete + """) + + +@pytest.unsupported_on_py2 +def test_invalid_self(): + """Tests invocation of the pybind-registered base class with an invalid `self` argument. You + can only actually do this on Python 3: Python 2 raises an exception itself if you try.""" + class NotPybindDerived(object): + pass + + # Attempts to initialize with an invalid type passed as `self`: + class BrokenTF1(m.TestFactory1): + def __init__(self, bad): + if bad == 1: + a = m.TestFactory2(tag.pointer, 1) + m.TestFactory1.__init__(a, tag.pointer) + elif bad == 2: + a = NotPybindDerived() + m.TestFactory1.__init__(a, tag.pointer) + + # Same as above, but for a class with an alias: + class BrokenTF6(m.TestFactory6): + def __init__(self, bad): + if bad == 1: + a = m.TestFactory2(tag.pointer, 1) + m.TestFactory6.__init__(a, tag.base, 1) + elif bad == 2: + a = m.TestFactory2(tag.pointer, 1) + m.TestFactory6.__init__(a, tag.alias, 1) + elif bad == 3: + m.TestFactory6.__init__(NotPybindDerived.__new__(NotPybindDerived), tag.base, 1) + elif bad == 4: + m.TestFactory6.__init__(NotPybindDerived.__new__(NotPybindDerived), tag.alias, 1) + + for arg in (1, 2): + with pytest.raises(TypeError) as excinfo: + BrokenTF1(arg) + assert str(excinfo.value) == "__init__(self, ...) called with invalid `self` argument" + + for arg in (1, 2, 3, 4): + with pytest.raises(TypeError) as excinfo: + BrokenTF6(arg) + assert str(excinfo.value) == "__init__(self, ...) called with invalid `self` argument" diff --git a/wrap/python/pybind11/tests/test_gil_scoped.cpp b/wrap/python/pybind11/tests/test_gil_scoped.cpp new file mode 100644 index 000000000..cb0010ee6 --- /dev/null +++ b/wrap/python/pybind11/tests/test_gil_scoped.cpp @@ -0,0 +1,44 @@ +/* + tests/test_gil_scoped.cpp -- acquire and release gil + + Copyright (c) 2017 Borja Zarco (Google LLC) + + All rights reserved. Use of this source code is governed by a + BSD-style license that can be found in the LICENSE file. +*/ + +#include "pybind11_tests.h" +#include + + +class VirtClass { +public: + virtual ~VirtClass() {} + virtual void virtual_func() {} + virtual void pure_virtual_func() = 0; +}; + +class PyVirtClass : public VirtClass { + void virtual_func() override { + PYBIND11_OVERLOAD(void, VirtClass, virtual_func,); + } + void pure_virtual_func() override { + PYBIND11_OVERLOAD_PURE(void, VirtClass, pure_virtual_func,); + } +}; + +TEST_SUBMODULE(gil_scoped, m) { + py::class_(m, "VirtClass") + .def(py::init<>()) + .def("virtual_func", &VirtClass::virtual_func) + .def("pure_virtual_func", &VirtClass::pure_virtual_func); + + m.def("test_callback_py_obj", + [](py::object func) { func(); }); + m.def("test_callback_std_func", + [](const std::function &func) { func(); }); + m.def("test_callback_virtual_func", + [](VirtClass &virt) { virt.virtual_func(); }); + m.def("test_callback_pure_virtual_func", + [](VirtClass &virt) { virt.pure_virtual_func(); }); +} diff --git a/wrap/python/pybind11/tests/test_gil_scoped.py b/wrap/python/pybind11/tests/test_gil_scoped.py new file mode 100644 index 000000000..2c72fc6d6 --- /dev/null +++ b/wrap/python/pybind11/tests/test_gil_scoped.py @@ -0,0 +1,80 @@ +import multiprocessing +import threading +from pybind11_tests import gil_scoped as m + + +def _run_in_process(target, *args, **kwargs): + """Runs target in process and returns its exitcode after 10s (None if still alive).""" + process = multiprocessing.Process(target=target, args=args, kwargs=kwargs) + process.daemon = True + try: + process.start() + # Do not need to wait much, 10s should be more than enough. + process.join(timeout=10) + return process.exitcode + finally: + if process.is_alive(): + process.terminate() + + +def _python_to_cpp_to_python(): + """Calls different C++ functions that come back to Python.""" + class ExtendedVirtClass(m.VirtClass): + def virtual_func(self): + pass + + def pure_virtual_func(self): + pass + + extended = ExtendedVirtClass() + m.test_callback_py_obj(lambda: None) + m.test_callback_std_func(lambda: None) + m.test_callback_virtual_func(extended) + m.test_callback_pure_virtual_func(extended) + + +def _python_to_cpp_to_python_from_threads(num_threads, parallel=False): + """Calls different C++ functions that come back to Python, from Python threads.""" + threads = [] + for _ in range(num_threads): + thread = threading.Thread(target=_python_to_cpp_to_python) + thread.daemon = True + thread.start() + if parallel: + threads.append(thread) + else: + thread.join() + for thread in threads: + thread.join() + + +def test_python_to_cpp_to_python_from_thread(): + """Makes sure there is no GIL deadlock when running in a thread. + + It runs in a separate process to be able to stop and assert if it deadlocks. + """ + assert _run_in_process(_python_to_cpp_to_python_from_threads, 1) == 0 + + +def test_python_to_cpp_to_python_from_thread_multiple_parallel(): + """Makes sure there is no GIL deadlock when running in a thread multiple times in parallel. + + It runs in a separate process to be able to stop and assert if it deadlocks. + """ + assert _run_in_process(_python_to_cpp_to_python_from_threads, 8, parallel=True) == 0 + + +def test_python_to_cpp_to_python_from_thread_multiple_sequential(): + """Makes sure there is no GIL deadlock when running in a thread multiple times sequentially. + + It runs in a separate process to be able to stop and assert if it deadlocks. + """ + assert _run_in_process(_python_to_cpp_to_python_from_threads, 8, parallel=False) == 0 + + +def test_python_to_cpp_to_python_from_process(): + """Makes sure there is no GIL deadlock when using processes. + + This test is for completion, but it was never an issue. + """ + assert _run_in_process(_python_to_cpp_to_python) == 0 diff --git a/wrap/python/pybind11/tests/test_iostream.cpp b/wrap/python/pybind11/tests/test_iostream.cpp new file mode 100644 index 000000000..e67f88af5 --- /dev/null +++ b/wrap/python/pybind11/tests/test_iostream.cpp @@ -0,0 +1,73 @@ +/* + tests/test_iostream.cpp -- Usage of scoped_output_redirect + + Copyright (c) 2017 Henry F. Schreiner + + All rights reserved. Use of this source code is governed by a + BSD-style license that can be found in the LICENSE file. +*/ + + +#include +#include "pybind11_tests.h" +#include + + +void noisy_function(std::string msg, bool flush) { + + std::cout << msg; + if (flush) + std::cout << std::flush; +} + +void noisy_funct_dual(std::string msg, std::string emsg) { + std::cout << msg; + std::cerr << emsg; +} + +TEST_SUBMODULE(iostream, m) { + + add_ostream_redirect(m); + + // test_evals + + m.def("captured_output_default", [](std::string msg) { + py::scoped_ostream_redirect redir; + std::cout << msg << std::flush; + }); + + m.def("captured_output", [](std::string msg) { + py::scoped_ostream_redirect redir(std::cout, py::module::import("sys").attr("stdout")); + std::cout << msg << std::flush; + }); + + m.def("guard_output", &noisy_function, + py::call_guard(), + py::arg("msg"), py::arg("flush")=true); + + m.def("captured_err", [](std::string msg) { + py::scoped_ostream_redirect redir(std::cerr, py::module::import("sys").attr("stderr")); + std::cerr << msg << std::flush; + }); + + m.def("noisy_function", &noisy_function, py::arg("msg"), py::arg("flush") = true); + + m.def("dual_guard", &noisy_funct_dual, + py::call_guard(), + py::arg("msg"), py::arg("emsg")); + + m.def("raw_output", [](std::string msg) { + std::cout << msg << std::flush; + }); + + m.def("raw_err", [](std::string msg) { + std::cerr << msg << std::flush; + }); + + m.def("captured_dual", [](std::string msg, std::string emsg) { + py::scoped_ostream_redirect redirout(std::cout, py::module::import("sys").attr("stdout")); + py::scoped_ostream_redirect redirerr(std::cerr, py::module::import("sys").attr("stderr")); + std::cout << msg << std::flush; + std::cerr << emsg << std::flush; + }); +} diff --git a/wrap/python/pybind11/tests/test_iostream.py b/wrap/python/pybind11/tests/test_iostream.py new file mode 100644 index 000000000..27095b270 --- /dev/null +++ b/wrap/python/pybind11/tests/test_iostream.py @@ -0,0 +1,214 @@ +from pybind11_tests import iostream as m +import sys + +from contextlib import contextmanager + +try: + # Python 3 + from io import StringIO +except ImportError: + # Python 2 + try: + from cStringIO import StringIO + except ImportError: + from StringIO import StringIO + +try: + # Python 3.4 + from contextlib import redirect_stdout +except ImportError: + @contextmanager + def redirect_stdout(target): + original = sys.stdout + sys.stdout = target + yield + sys.stdout = original + +try: + # Python 3.5 + from contextlib import redirect_stderr +except ImportError: + @contextmanager + def redirect_stderr(target): + original = sys.stderr + sys.stderr = target + yield + sys.stderr = original + + +def test_captured(capsys): + msg = "I've been redirected to Python, I hope!" + m.captured_output(msg) + stdout, stderr = capsys.readouterr() + assert stdout == msg + assert stderr == '' + + m.captured_output_default(msg) + stdout, stderr = capsys.readouterr() + assert stdout == msg + assert stderr == '' + + m.captured_err(msg) + stdout, stderr = capsys.readouterr() + assert stdout == '' + assert stderr == msg + + +def test_captured_large_string(capsys): + # Make this bigger than the buffer used on the C++ side: 1024 chars + msg = "I've been redirected to Python, I hope!" + msg = msg * (1024 // len(msg) + 1) + + m.captured_output_default(msg) + stdout, stderr = capsys.readouterr() + assert stdout == msg + assert stderr == '' + + +def test_guard_capture(capsys): + msg = "I've been redirected to Python, I hope!" + m.guard_output(msg) + stdout, stderr = capsys.readouterr() + assert stdout == msg + assert stderr == '' + + +def test_series_captured(capture): + with capture: + m.captured_output("a") + m.captured_output("b") + assert capture == "ab" + + +def test_flush(capfd): + msg = "(not flushed)" + msg2 = "(flushed)" + + with m.ostream_redirect(): + m.noisy_function(msg, flush=False) + stdout, stderr = capfd.readouterr() + assert stdout == '' + + m.noisy_function(msg2, flush=True) + stdout, stderr = capfd.readouterr() + assert stdout == msg + msg2 + + m.noisy_function(msg, flush=False) + + stdout, stderr = capfd.readouterr() + assert stdout == msg + + +def test_not_captured(capfd): + msg = "Something that should not show up in log" + stream = StringIO() + with redirect_stdout(stream): + m.raw_output(msg) + stdout, stderr = capfd.readouterr() + assert stdout == msg + assert stderr == '' + assert stream.getvalue() == '' + + stream = StringIO() + with redirect_stdout(stream): + m.captured_output(msg) + stdout, stderr = capfd.readouterr() + assert stdout == '' + assert stderr == '' + assert stream.getvalue() == msg + + +def test_err(capfd): + msg = "Something that should not show up in log" + stream = StringIO() + with redirect_stderr(stream): + m.raw_err(msg) + stdout, stderr = capfd.readouterr() + assert stdout == '' + assert stderr == msg + assert stream.getvalue() == '' + + stream = StringIO() + with redirect_stderr(stream): + m.captured_err(msg) + stdout, stderr = capfd.readouterr() + assert stdout == '' + assert stderr == '' + assert stream.getvalue() == msg + + +def test_multi_captured(capfd): + stream = StringIO() + with redirect_stdout(stream): + m.captured_output("a") + m.raw_output("b") + m.captured_output("c") + m.raw_output("d") + stdout, stderr = capfd.readouterr() + assert stdout == 'bd' + assert stream.getvalue() == 'ac' + + +def test_dual(capsys): + m.captured_dual("a", "b") + stdout, stderr = capsys.readouterr() + assert stdout == "a" + assert stderr == "b" + + +def test_redirect(capfd): + msg = "Should not be in log!" + stream = StringIO() + with redirect_stdout(stream): + m.raw_output(msg) + stdout, stderr = capfd.readouterr() + assert stdout == msg + assert stream.getvalue() == '' + + stream = StringIO() + with redirect_stdout(stream): + with m.ostream_redirect(): + m.raw_output(msg) + stdout, stderr = capfd.readouterr() + assert stdout == '' + assert stream.getvalue() == msg + + stream = StringIO() + with redirect_stdout(stream): + m.raw_output(msg) + stdout, stderr = capfd.readouterr() + assert stdout == msg + assert stream.getvalue() == '' + + +def test_redirect_err(capfd): + msg = "StdOut" + msg2 = "StdErr" + + stream = StringIO() + with redirect_stderr(stream): + with m.ostream_redirect(stdout=False): + m.raw_output(msg) + m.raw_err(msg2) + stdout, stderr = capfd.readouterr() + assert stdout == msg + assert stderr == '' + assert stream.getvalue() == msg2 + + +def test_redirect_both(capfd): + msg = "StdOut" + msg2 = "StdErr" + + stream = StringIO() + stream2 = StringIO() + with redirect_stdout(stream): + with redirect_stderr(stream2): + with m.ostream_redirect(): + m.raw_output(msg) + m.raw_err(msg2) + stdout, stderr = capfd.readouterr() + assert stdout == '' + assert stderr == '' + assert stream.getvalue() == msg + assert stream2.getvalue() == msg2 diff --git a/wrap/python/pybind11/tests/test_kwargs_and_defaults.cpp b/wrap/python/pybind11/tests/test_kwargs_and_defaults.cpp new file mode 100644 index 000000000..6563fb9ad --- /dev/null +++ b/wrap/python/pybind11/tests/test_kwargs_and_defaults.cpp @@ -0,0 +1,102 @@ +/* + tests/test_kwargs_and_defaults.cpp -- keyword arguments and default values + + Copyright (c) 2016 Wenzel Jakob + + All rights reserved. Use of this source code is governed by a + BSD-style license that can be found in the LICENSE file. +*/ + +#include "pybind11_tests.h" +#include "constructor_stats.h" +#include + +TEST_SUBMODULE(kwargs_and_defaults, m) { + auto kw_func = [](int x, int y) { return "x=" + std::to_string(x) + ", y=" + std::to_string(y); }; + + // test_named_arguments + m.def("kw_func0", kw_func); + m.def("kw_func1", kw_func, py::arg("x"), py::arg("y")); + m.def("kw_func2", kw_func, py::arg("x") = 100, py::arg("y") = 200); + m.def("kw_func3", [](const char *) { }, py::arg("data") = std::string("Hello world!")); + + /* A fancier default argument */ + std::vector list{{13, 17}}; + m.def("kw_func4", [](const std::vector &entries) { + std::string ret = "{"; + for (int i : entries) + ret += std::to_string(i) + " "; + ret.back() = '}'; + return ret; + }, py::arg("myList") = list); + + m.def("kw_func_udl", kw_func, "x"_a, "y"_a=300); + m.def("kw_func_udl_z", kw_func, "x"_a, "y"_a=0); + + // test_args_and_kwargs + m.def("args_function", [](py::args args) -> py::tuple { + return std::move(args); + }); + m.def("args_kwargs_function", [](py::args args, py::kwargs kwargs) { + return py::make_tuple(args, kwargs); + }); + + // test_mixed_args_and_kwargs + m.def("mixed_plus_args", [](int i, double j, py::args args) { + return py::make_tuple(i, j, args); + }); + m.def("mixed_plus_kwargs", [](int i, double j, py::kwargs kwargs) { + return py::make_tuple(i, j, kwargs); + }); + auto mixed_plus_both = [](int i, double j, py::args args, py::kwargs kwargs) { + return py::make_tuple(i, j, args, kwargs); + }; + m.def("mixed_plus_args_kwargs", mixed_plus_both); + + m.def("mixed_plus_args_kwargs_defaults", mixed_plus_both, + py::arg("i") = 1, py::arg("j") = 3.14159); + + // test_args_refcount + // PyPy needs a garbage collection to get the reference count values to match CPython's behaviour + #ifdef PYPY_VERSION + #define GC_IF_NEEDED ConstructorStats::gc() + #else + #define GC_IF_NEEDED + #endif + m.def("arg_refcount_h", [](py::handle h) { GC_IF_NEEDED; return h.ref_count(); }); + m.def("arg_refcount_h", [](py::handle h, py::handle, py::handle) { GC_IF_NEEDED; return h.ref_count(); }); + m.def("arg_refcount_o", [](py::object o) { GC_IF_NEEDED; return o.ref_count(); }); + m.def("args_refcount", [](py::args a) { + GC_IF_NEEDED; + py::tuple t(a.size()); + for (size_t i = 0; i < a.size(); i++) + // Use raw Python API here to avoid an extra, intermediate incref on the tuple item: + t[i] = (int) Py_REFCNT(PyTuple_GET_ITEM(a.ptr(), static_cast(i))); + return t; + }); + m.def("mixed_args_refcount", [](py::object o, py::args a) { + GC_IF_NEEDED; + py::tuple t(a.size() + 1); + t[0] = o.ref_count(); + for (size_t i = 0; i < a.size(); i++) + // Use raw Python API here to avoid an extra, intermediate incref on the tuple item: + t[i + 1] = (int) Py_REFCNT(PyTuple_GET_ITEM(a.ptr(), static_cast(i))); + return t; + }); + + // pybind11 won't allow these to be bound: args and kwargs, if present, must be at the end. + // Uncomment these to test that the static_assert is indeed working: +// m.def("bad_args1", [](py::args, int) {}); +// m.def("bad_args2", [](py::kwargs, int) {}); +// m.def("bad_args3", [](py::kwargs, py::args) {}); +// m.def("bad_args4", [](py::args, int, py::kwargs) {}); +// m.def("bad_args5", [](py::args, py::kwargs, int) {}); +// m.def("bad_args6", [](py::args, py::args) {}); +// m.def("bad_args7", [](py::kwargs, py::kwargs) {}); + + // test_function_signatures (along with most of the above) + struct KWClass { void foo(int, float) {} }; + py::class_(m, "KWClass") + .def("foo0", &KWClass::foo) + .def("foo1", &KWClass::foo, "x"_a, "y"_a); +} diff --git a/wrap/python/pybind11/tests/test_kwargs_and_defaults.py b/wrap/python/pybind11/tests/test_kwargs_and_defaults.py new file mode 100644 index 000000000..27a05a024 --- /dev/null +++ b/wrap/python/pybind11/tests/test_kwargs_and_defaults.py @@ -0,0 +1,147 @@ +import pytest +from pybind11_tests import kwargs_and_defaults as m + + +def test_function_signatures(doc): + assert doc(m.kw_func0) == "kw_func0(arg0: int, arg1: int) -> str" + assert doc(m.kw_func1) == "kw_func1(x: int, y: int) -> str" + assert doc(m.kw_func2) == "kw_func2(x: int = 100, y: int = 200) -> str" + assert doc(m.kw_func3) == "kw_func3(data: str = 'Hello world!') -> None" + assert doc(m.kw_func4) == "kw_func4(myList: List[int] = [13, 17]) -> str" + assert doc(m.kw_func_udl) == "kw_func_udl(x: int, y: int = 300) -> str" + assert doc(m.kw_func_udl_z) == "kw_func_udl_z(x: int, y: int = 0) -> str" + assert doc(m.args_function) == "args_function(*args) -> tuple" + assert doc(m.args_kwargs_function) == "args_kwargs_function(*args, **kwargs) -> tuple" + assert doc(m.KWClass.foo0) == \ + "foo0(self: m.kwargs_and_defaults.KWClass, arg0: int, arg1: float) -> None" + assert doc(m.KWClass.foo1) == \ + "foo1(self: m.kwargs_and_defaults.KWClass, x: int, y: float) -> None" + + +def test_named_arguments(msg): + assert m.kw_func0(5, 10) == "x=5, y=10" + + assert m.kw_func1(5, 10) == "x=5, y=10" + assert m.kw_func1(5, y=10) == "x=5, y=10" + assert m.kw_func1(y=10, x=5) == "x=5, y=10" + + assert m.kw_func2() == "x=100, y=200" + assert m.kw_func2(5) == "x=5, y=200" + assert m.kw_func2(x=5) == "x=5, y=200" + assert m.kw_func2(y=10) == "x=100, y=10" + assert m.kw_func2(5, 10) == "x=5, y=10" + assert m.kw_func2(x=5, y=10) == "x=5, y=10" + + with pytest.raises(TypeError) as excinfo: + # noinspection PyArgumentList + m.kw_func2(x=5, y=10, z=12) + assert excinfo.match( + r'(?s)^kw_func2\(\): incompatible.*Invoked with: kwargs: ((x=5|y=10|z=12)(, |$))' + '{3}$') + + assert m.kw_func4() == "{13 17}" + assert m.kw_func4(myList=[1, 2, 3]) == "{1 2 3}" + + assert m.kw_func_udl(x=5, y=10) == "x=5, y=10" + assert m.kw_func_udl_z(x=5) == "x=5, y=0" + + +def test_arg_and_kwargs(): + args = 'arg1_value', 'arg2_value', 3 + assert m.args_function(*args) == args + + args = 'a1', 'a2' + kwargs = dict(arg3='a3', arg4=4) + assert m.args_kwargs_function(*args, **kwargs) == (args, kwargs) + + +def test_mixed_args_and_kwargs(msg): + mpa = m.mixed_plus_args + mpk = m.mixed_plus_kwargs + mpak = m.mixed_plus_args_kwargs + mpakd = m.mixed_plus_args_kwargs_defaults + + assert mpa(1, 2.5, 4, 99.5, None) == (1, 2.5, (4, 99.5, None)) + assert mpa(1, 2.5) == (1, 2.5, ()) + with pytest.raises(TypeError) as excinfo: + assert mpa(1) + assert msg(excinfo.value) == """ + mixed_plus_args(): incompatible function arguments. The following argument types are supported: + 1. (arg0: int, arg1: float, *args) -> tuple + + Invoked with: 1 + """ # noqa: E501 line too long + with pytest.raises(TypeError) as excinfo: + assert mpa() + assert msg(excinfo.value) == """ + mixed_plus_args(): incompatible function arguments. The following argument types are supported: + 1. (arg0: int, arg1: float, *args) -> tuple + + Invoked with: + """ # noqa: E501 line too long + + assert mpk(-2, 3.5, pi=3.14159, e=2.71828) == (-2, 3.5, {'e': 2.71828, 'pi': 3.14159}) + assert mpak(7, 7.7, 7.77, 7.777, 7.7777, minusseven=-7) == ( + 7, 7.7, (7.77, 7.777, 7.7777), {'minusseven': -7}) + assert mpakd() == (1, 3.14159, (), {}) + assert mpakd(3) == (3, 3.14159, (), {}) + assert mpakd(j=2.71828) == (1, 2.71828, (), {}) + assert mpakd(k=42) == (1, 3.14159, (), {'k': 42}) + assert mpakd(1, 1, 2, 3, 5, 8, then=13, followedby=21) == ( + 1, 1, (2, 3, 5, 8), {'then': 13, 'followedby': 21}) + # Arguments specified both positionally and via kwargs should fail: + with pytest.raises(TypeError) as excinfo: + assert mpakd(1, i=1) + assert msg(excinfo.value) == """ + mixed_plus_args_kwargs_defaults(): incompatible function arguments. The following argument types are supported: + 1. (i: int = 1, j: float = 3.14159, *args, **kwargs) -> tuple + + Invoked with: 1; kwargs: i=1 + """ # noqa: E501 line too long + with pytest.raises(TypeError) as excinfo: + assert mpakd(1, 2, j=1) + assert msg(excinfo.value) == """ + mixed_plus_args_kwargs_defaults(): incompatible function arguments. The following argument types are supported: + 1. (i: int = 1, j: float = 3.14159, *args, **kwargs) -> tuple + + Invoked with: 1, 2; kwargs: j=1 + """ # noqa: E501 line too long + + +def test_args_refcount(): + """Issue/PR #1216 - py::args elements get double-inc_ref()ed when combined with regular + arguments""" + refcount = m.arg_refcount_h + + myval = 54321 + expected = refcount(myval) + assert m.arg_refcount_h(myval) == expected + assert m.arg_refcount_o(myval) == expected + 1 + assert m.arg_refcount_h(myval) == expected + assert refcount(myval) == expected + + assert m.mixed_plus_args(1, 2.0, "a", myval) == (1, 2.0, ("a", myval)) + assert refcount(myval) == expected + + assert m.mixed_plus_kwargs(3, 4.0, a=1, b=myval) == (3, 4.0, {"a": 1, "b": myval}) + assert refcount(myval) == expected + + assert m.args_function(-1, myval) == (-1, myval) + assert refcount(myval) == expected + + assert m.mixed_plus_args_kwargs(5, 6.0, myval, a=myval) == (5, 6.0, (myval,), {"a": myval}) + assert refcount(myval) == expected + + assert m.args_kwargs_function(7, 8, myval, a=1, b=myval) == \ + ((7, 8, myval), {"a": 1, "b": myval}) + assert refcount(myval) == expected + + exp3 = refcount(myval, myval, myval) + assert m.args_refcount(myval, myval, myval) == (exp3, exp3, exp3) + assert refcount(myval) == expected + + # This function takes the first arg as a `py::object` and the rest as a `py::args`. Unlike the + # previous case, when we have both positional and `py::args` we need to construct a new tuple + # for the `py::args`; in the previous case, we could simply inc_ref and pass on Python's input + # tuple without having to inc_ref the individual elements, but here we can't, hence the extra + # refs. + assert m.mixed_args_refcount(myval, myval, myval) == (exp3 + 3, exp3 + 3, exp3 + 3) diff --git a/wrap/python/pybind11/tests/test_local_bindings.cpp b/wrap/python/pybind11/tests/test_local_bindings.cpp new file mode 100644 index 000000000..97c02dbeb --- /dev/null +++ b/wrap/python/pybind11/tests/test_local_bindings.cpp @@ -0,0 +1,101 @@ +/* + tests/test_local_bindings.cpp -- tests the py::module_local class feature which makes a class + binding local to the module in which it is defined. + + Copyright (c) 2017 Jason Rhinelander + + All rights reserved. Use of this source code is governed by a + BSD-style license that can be found in the LICENSE file. +*/ + +#include "pybind11_tests.h" +#include "local_bindings.h" +#include +#include +#include + +TEST_SUBMODULE(local_bindings, m) { + // test_load_external + m.def("load_external1", [](ExternalType1 &e) { return e.i; }); + m.def("load_external2", [](ExternalType2 &e) { return e.i; }); + + // test_local_bindings + // Register a class with py::module_local: + bind_local(m, "LocalType", py::module_local()) + .def("get3", [](LocalType &t) { return t.i + 3; }) + ; + + m.def("local_value", [](LocalType &l) { return l.i; }); + + // test_nonlocal_failure + // The main pybind11 test module is loaded first, so this registration will succeed (the second + // one, in pybind11_cross_module_tests.cpp, is designed to fail): + bind_local(m, "NonLocalType") + .def(py::init()) + .def("get", [](LocalType &i) { return i.i; }) + ; + + // test_duplicate_local + // py::module_local declarations should be visible across compilation units that get linked together; + // this tries to register a duplicate local. It depends on a definition in test_class.cpp and + // should raise a runtime error from the duplicate definition attempt. If test_class isn't + // available it *also* throws a runtime error (with "test_class not enabled" as value). + m.def("register_local_external", [m]() { + auto main = py::module::import("pybind11_tests"); + if (py::hasattr(main, "class_")) { + bind_local(m, "LocalExternal", py::module_local()); + } + else throw std::runtime_error("test_class not enabled"); + }); + + // test_stl_bind_local + // stl_bind.h binders defaults to py::module_local if the types are local or converting: + py::bind_vector(m, "LocalVec"); + py::bind_map(m, "LocalMap"); + // and global if the type (or one of the types, for the map) is global: + py::bind_vector(m, "NonLocalVec"); + py::bind_map(m, "NonLocalMap"); + + // test_stl_bind_global + // They can, however, be overridden to global using `py::module_local(false)`: + bind_local(m, "NonLocal2"); + py::bind_vector(m, "LocalVec2", py::module_local()); + py::bind_map(m, "NonLocalMap2", py::module_local(false)); + + // test_mixed_local_global + // We try this both with the global type registered first and vice versa (the order shouldn't + // matter). + m.def("register_mixed_global", [m]() { + bind_local(m, "MixedGlobalLocal", py::module_local(false)); + }); + m.def("register_mixed_local", [m]() { + bind_local(m, "MixedLocalGlobal", py::module_local()); + }); + m.def("get_mixed_gl", [](int i) { return MixedGlobalLocal(i); }); + m.def("get_mixed_lg", [](int i) { return MixedLocalGlobal(i); }); + + // test_internal_locals_differ + m.def("local_cpp_types_addr", []() { return (uintptr_t) &py::detail::registered_local_types_cpp(); }); + + // test_stl_caster_vs_stl_bind + m.def("load_vector_via_caster", [](std::vector v) { + return std::accumulate(v.begin(), v.end(), 0); + }); + + // test_cross_module_calls + m.def("return_self", [](LocalVec *v) { return v; }); + m.def("return_copy", [](const LocalVec &v) { return LocalVec(v); }); + + class Cat : public pets::Pet { public: Cat(std::string name) : Pet(name) {}; }; + py::class_(m, "Pet", py::module_local()) + .def("get_name", &pets::Pet::name); + // Binding for local extending class: + py::class_(m, "Cat") + .def(py::init()); + m.def("pet_name", [](pets::Pet &p) { return p.name(); }); + + py::class_(m, "MixGL").def(py::init()); + m.def("get_gl_value", [](MixGL &o) { return o.i + 10; }); + + py::class_(m, "MixGL2").def(py::init()); +} diff --git a/wrap/python/pybind11/tests/test_local_bindings.py b/wrap/python/pybind11/tests/test_local_bindings.py new file mode 100644 index 000000000..b3dc3619c --- /dev/null +++ b/wrap/python/pybind11/tests/test_local_bindings.py @@ -0,0 +1,226 @@ +import pytest + +from pybind11_tests import local_bindings as m + + +def test_load_external(): + """Load a `py::module_local` type that's only registered in an external module""" + import pybind11_cross_module_tests as cm + + assert m.load_external1(cm.ExternalType1(11)) == 11 + assert m.load_external2(cm.ExternalType2(22)) == 22 + + with pytest.raises(TypeError) as excinfo: + assert m.load_external2(cm.ExternalType1(21)) == 21 + assert "incompatible function arguments" in str(excinfo.value) + + with pytest.raises(TypeError) as excinfo: + assert m.load_external1(cm.ExternalType2(12)) == 12 + assert "incompatible function arguments" in str(excinfo.value) + + +def test_local_bindings(): + """Tests that duplicate `py::module_local` class bindings work across modules""" + + # Make sure we can load the second module with the conflicting (but local) definition: + import pybind11_cross_module_tests as cm + + i1 = m.LocalType(5) + assert i1.get() == 4 + assert i1.get3() == 8 + + i2 = cm.LocalType(10) + assert i2.get() == 11 + assert i2.get2() == 12 + + assert not hasattr(i1, 'get2') + assert not hasattr(i2, 'get3') + + # Loading within the local module + assert m.local_value(i1) == 5 + assert cm.local_value(i2) == 10 + + # Cross-module loading works as well (on failure, the type loader looks for + # external module-local converters): + assert m.local_value(i2) == 10 + assert cm.local_value(i1) == 5 + + +def test_nonlocal_failure(): + """Tests that attempting to register a non-local type in multiple modules fails""" + import pybind11_cross_module_tests as cm + + with pytest.raises(RuntimeError) as excinfo: + cm.register_nonlocal() + assert str(excinfo.value) == 'generic_type: type "NonLocalType" is already registered!' + + +def test_duplicate_local(): + """Tests expected failure when registering a class twice with py::local in the same module""" + with pytest.raises(RuntimeError) as excinfo: + m.register_local_external() + import pybind11_tests + assert str(excinfo.value) == ( + 'generic_type: type "LocalExternal" is already registered!' + if hasattr(pybind11_tests, 'class_') else 'test_class not enabled') + + +def test_stl_bind_local(): + import pybind11_cross_module_tests as cm + + v1, v2 = m.LocalVec(), cm.LocalVec() + v1.append(m.LocalType(1)) + v1.append(m.LocalType(2)) + v2.append(cm.LocalType(1)) + v2.append(cm.LocalType(2)) + + # Cross module value loading: + v1.append(cm.LocalType(3)) + v2.append(m.LocalType(3)) + + assert [i.get() for i in v1] == [0, 1, 2] + assert [i.get() for i in v2] == [2, 3, 4] + + v3, v4 = m.NonLocalVec(), cm.NonLocalVec2() + v3.append(m.NonLocalType(1)) + v3.append(m.NonLocalType(2)) + v4.append(m.NonLocal2(3)) + v4.append(m.NonLocal2(4)) + + assert [i.get() for i in v3] == [1, 2] + assert [i.get() for i in v4] == [13, 14] + + d1, d2 = m.LocalMap(), cm.LocalMap() + d1["a"] = v1[0] + d1["b"] = v1[1] + d2["c"] = v2[0] + d2["d"] = v2[1] + assert {i: d1[i].get() for i in d1} == {'a': 0, 'b': 1} + assert {i: d2[i].get() for i in d2} == {'c': 2, 'd': 3} + + +def test_stl_bind_global(): + import pybind11_cross_module_tests as cm + + with pytest.raises(RuntimeError) as excinfo: + cm.register_nonlocal_map() + assert str(excinfo.value) == 'generic_type: type "NonLocalMap" is already registered!' + + with pytest.raises(RuntimeError) as excinfo: + cm.register_nonlocal_vec() + assert str(excinfo.value) == 'generic_type: type "NonLocalVec" is already registered!' + + with pytest.raises(RuntimeError) as excinfo: + cm.register_nonlocal_map2() + assert str(excinfo.value) == 'generic_type: type "NonLocalMap2" is already registered!' + + +def test_mixed_local_global(): + """Local types take precedence over globally registered types: a module with a `module_local` + type can be registered even if the type is already registered globally. With the module, + casting will go to the local type; outside the module casting goes to the global type.""" + import pybind11_cross_module_tests as cm + m.register_mixed_global() + m.register_mixed_local() + + a = [] + a.append(m.MixedGlobalLocal(1)) + a.append(m.MixedLocalGlobal(2)) + a.append(m.get_mixed_gl(3)) + a.append(m.get_mixed_lg(4)) + + assert [x.get() for x in a] == [101, 1002, 103, 1004] + + cm.register_mixed_global_local() + cm.register_mixed_local_global() + a.append(m.MixedGlobalLocal(5)) + a.append(m.MixedLocalGlobal(6)) + a.append(cm.MixedGlobalLocal(7)) + a.append(cm.MixedLocalGlobal(8)) + a.append(m.get_mixed_gl(9)) + a.append(m.get_mixed_lg(10)) + a.append(cm.get_mixed_gl(11)) + a.append(cm.get_mixed_lg(12)) + + assert [x.get() for x in a] == \ + [101, 1002, 103, 1004, 105, 1006, 207, 2008, 109, 1010, 211, 2012] + + +def test_internal_locals_differ(): + """Makes sure the internal local type map differs across the two modules""" + import pybind11_cross_module_tests as cm + assert m.local_cpp_types_addr() != cm.local_cpp_types_addr() + + +def test_stl_caster_vs_stl_bind(msg): + """One module uses a generic vector caster from `` while the other + exports `std::vector` via `py:bind_vector` and `py::module_local`""" + import pybind11_cross_module_tests as cm + + v1 = cm.VectorInt([1, 2, 3]) + assert m.load_vector_via_caster(v1) == 6 + assert cm.load_vector_via_binding(v1) == 6 + + v2 = [1, 2, 3] + assert m.load_vector_via_caster(v2) == 6 + with pytest.raises(TypeError) as excinfo: + cm.load_vector_via_binding(v2) == 6 + assert msg(excinfo.value) == """ + load_vector_via_binding(): incompatible function arguments. The following argument types are supported: + 1. (arg0: pybind11_cross_module_tests.VectorInt) -> int + + Invoked with: [1, 2, 3] + """ # noqa: E501 line too long + + +def test_cross_module_calls(): + import pybind11_cross_module_tests as cm + + v1 = m.LocalVec() + v1.append(m.LocalType(1)) + v2 = cm.LocalVec() + v2.append(cm.LocalType(2)) + + # Returning the self pointer should get picked up as returning an existing + # instance (even when that instance is of a foreign, non-local type). + assert m.return_self(v1) is v1 + assert cm.return_self(v2) is v2 + assert m.return_self(v2) is v2 + assert cm.return_self(v1) is v1 + + assert m.LocalVec is not cm.LocalVec + # Returning a copy, on the other hand, always goes to the local type, + # regardless of where the source type came from. + assert type(m.return_copy(v1)) is m.LocalVec + assert type(m.return_copy(v2)) is m.LocalVec + assert type(cm.return_copy(v1)) is cm.LocalVec + assert type(cm.return_copy(v2)) is cm.LocalVec + + # Test the example given in the documentation (which also tests inheritance casting): + mycat = m.Cat("Fluffy") + mydog = cm.Dog("Rover") + assert mycat.get_name() == "Fluffy" + assert mydog.name() == "Rover" + assert m.Cat.__base__.__name__ == "Pet" + assert cm.Dog.__base__.__name__ == "Pet" + assert m.Cat.__base__ is not cm.Dog.__base__ + assert m.pet_name(mycat) == "Fluffy" + assert m.pet_name(mydog) == "Rover" + assert cm.pet_name(mycat) == "Fluffy" + assert cm.pet_name(mydog) == "Rover" + + assert m.MixGL is not cm.MixGL + a = m.MixGL(1) + b = cm.MixGL(2) + assert m.get_gl_value(a) == 11 + assert m.get_gl_value(b) == 12 + assert cm.get_gl_value(a) == 101 + assert cm.get_gl_value(b) == 102 + + c, d = m.MixGL2(3), cm.MixGL2(4) + with pytest.raises(TypeError) as excinfo: + m.get_gl_value(c) + assert "incompatible function arguments" in str(excinfo) + with pytest.raises(TypeError) as excinfo: + m.get_gl_value(d) + assert "incompatible function arguments" in str(excinfo) diff --git a/wrap/python/pybind11/tests/test_methods_and_attributes.cpp b/wrap/python/pybind11/tests/test_methods_and_attributes.cpp new file mode 100644 index 000000000..fde152b9f --- /dev/null +++ b/wrap/python/pybind11/tests/test_methods_and_attributes.cpp @@ -0,0 +1,454 @@ +/* + tests/test_methods_and_attributes.cpp -- constructors, deconstructors, attribute access, + __str__, argument and return value conventions + + Copyright (c) 2016 Wenzel Jakob + + All rights reserved. Use of this source code is governed by a + BSD-style license that can be found in the LICENSE file. +*/ + +#include "pybind11_tests.h" +#include "constructor_stats.h" + +class ExampleMandA { +public: + ExampleMandA() { print_default_created(this); } + ExampleMandA(int value) : value(value) { print_created(this, value); } + ExampleMandA(const ExampleMandA &e) : value(e.value) { print_copy_created(this); } + ExampleMandA(ExampleMandA &&e) : value(e.value) { print_move_created(this); } + ~ExampleMandA() { print_destroyed(this); } + + std::string toString() { + return "ExampleMandA[value=" + std::to_string(value) + "]"; + } + + void operator=(const ExampleMandA &e) { print_copy_assigned(this); value = e.value; } + void operator=(ExampleMandA &&e) { print_move_assigned(this); value = e.value; } + + void add1(ExampleMandA other) { value += other.value; } // passing by value + void add2(ExampleMandA &other) { value += other.value; } // passing by reference + void add3(const ExampleMandA &other) { value += other.value; } // passing by const reference + void add4(ExampleMandA *other) { value += other->value; } // passing by pointer + void add5(const ExampleMandA *other) { value += other->value; } // passing by const pointer + + void add6(int other) { value += other; } // passing by value + void add7(int &other) { value += other; } // passing by reference + void add8(const int &other) { value += other; } // passing by const reference + void add9(int *other) { value += *other; } // passing by pointer + void add10(const int *other) { value += *other; } // passing by const pointer + + ExampleMandA self1() { return *this; } // return by value + ExampleMandA &self2() { return *this; } // return by reference + const ExampleMandA &self3() { return *this; } // return by const reference + ExampleMandA *self4() { return this; } // return by pointer + const ExampleMandA *self5() { return this; } // return by const pointer + + int internal1() { return value; } // return by value + int &internal2() { return value; } // return by reference + const int &internal3() { return value; } // return by const reference + int *internal4() { return &value; } // return by pointer + const int *internal5() { return &value; } // return by const pointer + + py::str overloaded() { return "()"; } + py::str overloaded(int) { return "(int)"; } + py::str overloaded(int, float) { return "(int, float)"; } + py::str overloaded(float, int) { return "(float, int)"; } + py::str overloaded(int, int) { return "(int, int)"; } + py::str overloaded(float, float) { return "(float, float)"; } + py::str overloaded(int) const { return "(int) const"; } + py::str overloaded(int, float) const { return "(int, float) const"; } + py::str overloaded(float, int) const { return "(float, int) const"; } + py::str overloaded(int, int) const { return "(int, int) const"; } + py::str overloaded(float, float) const { return "(float, float) const"; } + + static py::str overloaded(float) { return "static float"; } + + int value = 0; +}; + +struct TestProperties { + int value = 1; + static int static_value; + + int get() const { return value; } + void set(int v) { value = v; } + + static int static_get() { return static_value; } + static void static_set(int v) { static_value = v; } +}; +int TestProperties::static_value = 1; + +struct TestPropertiesOverride : TestProperties { + int value = 99; + static int static_value; +}; +int TestPropertiesOverride::static_value = 99; + +struct TestPropRVP { + UserType v1{1}; + UserType v2{1}; + static UserType sv1; + static UserType sv2; + + const UserType &get1() const { return v1; } + const UserType &get2() const { return v2; } + UserType get_rvalue() const { return v2; } + void set1(int v) { v1.set(v); } + void set2(int v) { v2.set(v); } +}; +UserType TestPropRVP::sv1(1); +UserType TestPropRVP::sv2(1); + +// py::arg/py::arg_v testing: these arguments just record their argument when invoked +class ArgInspector1 { public: std::string arg = "(default arg inspector 1)"; }; +class ArgInspector2 { public: std::string arg = "(default arg inspector 2)"; }; +class ArgAlwaysConverts { }; +namespace pybind11 { namespace detail { +template <> struct type_caster { +public: + PYBIND11_TYPE_CASTER(ArgInspector1, _("ArgInspector1")); + + bool load(handle src, bool convert) { + value.arg = "loading ArgInspector1 argument " + + std::string(convert ? "WITH" : "WITHOUT") + " conversion allowed. " + "Argument value = " + (std::string) str(src); + return true; + } + + static handle cast(const ArgInspector1 &src, return_value_policy, handle) { + return str(src.arg).release(); + } +}; +template <> struct type_caster { +public: + PYBIND11_TYPE_CASTER(ArgInspector2, _("ArgInspector2")); + + bool load(handle src, bool convert) { + value.arg = "loading ArgInspector2 argument " + + std::string(convert ? "WITH" : "WITHOUT") + " conversion allowed. " + "Argument value = " + (std::string) str(src); + return true; + } + + static handle cast(const ArgInspector2 &src, return_value_policy, handle) { + return str(src.arg).release(); + } +}; +template <> struct type_caster { +public: + PYBIND11_TYPE_CASTER(ArgAlwaysConverts, _("ArgAlwaysConverts")); + + bool load(handle, bool convert) { + return convert; + } + + static handle cast(const ArgAlwaysConverts &, return_value_policy, handle) { + return py::none().release(); + } +}; +}} + +// test_custom_caster_destruction +class DestructionTester { +public: + DestructionTester() { print_default_created(this); } + ~DestructionTester() { print_destroyed(this); } + DestructionTester(const DestructionTester &) { print_copy_created(this); } + DestructionTester(DestructionTester &&) { print_move_created(this); } + DestructionTester &operator=(const DestructionTester &) { print_copy_assigned(this); return *this; } + DestructionTester &operator=(DestructionTester &&) { print_move_assigned(this); return *this; } +}; +namespace pybind11 { namespace detail { +template <> struct type_caster { + PYBIND11_TYPE_CASTER(DestructionTester, _("DestructionTester")); + bool load(handle, bool) { return true; } + + static handle cast(const DestructionTester &, return_value_policy, handle) { + return py::bool_(true).release(); + } +}; +}} + +// Test None-allowed py::arg argument policy +class NoneTester { public: int answer = 42; }; +int none1(const NoneTester &obj) { return obj.answer; } +int none2(NoneTester *obj) { return obj ? obj->answer : -1; } +int none3(std::shared_ptr &obj) { return obj ? obj->answer : -1; } +int none4(std::shared_ptr *obj) { return obj && *obj ? (*obj)->answer : -1; } +int none5(std::shared_ptr obj) { return obj ? obj->answer : -1; } + +struct StrIssue { + int val = -1; + + StrIssue() = default; + StrIssue(int i) : val{i} {} +}; + +// Issues #854, #910: incompatible function args when member function/pointer is in unregistered base class +class UnregisteredBase { +public: + void do_nothing() const {} + void increase_value() { rw_value++; ro_value += 0.25; } + void set_int(int v) { rw_value = v; } + int get_int() const { return rw_value; } + double get_double() const { return ro_value; } + int rw_value = 42; + double ro_value = 1.25; +}; +class RegisteredDerived : public UnregisteredBase { +public: + using UnregisteredBase::UnregisteredBase; + double sum() const { return rw_value + ro_value; } +}; + +TEST_SUBMODULE(methods_and_attributes, m) { + // test_methods_and_attributes + py::class_ emna(m, "ExampleMandA"); + emna.def(py::init<>()) + .def(py::init()) + .def(py::init()) + .def("add1", &ExampleMandA::add1) + .def("add2", &ExampleMandA::add2) + .def("add3", &ExampleMandA::add3) + .def("add4", &ExampleMandA::add4) + .def("add5", &ExampleMandA::add5) + .def("add6", &ExampleMandA::add6) + .def("add7", &ExampleMandA::add7) + .def("add8", &ExampleMandA::add8) + .def("add9", &ExampleMandA::add9) + .def("add10", &ExampleMandA::add10) + .def("self1", &ExampleMandA::self1) + .def("self2", &ExampleMandA::self2) + .def("self3", &ExampleMandA::self3) + .def("self4", &ExampleMandA::self4) + .def("self5", &ExampleMandA::self5) + .def("internal1", &ExampleMandA::internal1) + .def("internal2", &ExampleMandA::internal2) + .def("internal3", &ExampleMandA::internal3) + .def("internal4", &ExampleMandA::internal4) + .def("internal5", &ExampleMandA::internal5) +#if defined(PYBIND11_OVERLOAD_CAST) + .def("overloaded", py::overload_cast<>(&ExampleMandA::overloaded)) + .def("overloaded", py::overload_cast(&ExampleMandA::overloaded)) + .def("overloaded", py::overload_cast(&ExampleMandA::overloaded)) + .def("overloaded", py::overload_cast(&ExampleMandA::overloaded)) + .def("overloaded", py::overload_cast(&ExampleMandA::overloaded)) + .def("overloaded", py::overload_cast(&ExampleMandA::overloaded)) + .def("overloaded_float", py::overload_cast(&ExampleMandA::overloaded)) + .def("overloaded_const", py::overload_cast(&ExampleMandA::overloaded, py::const_)) + .def("overloaded_const", py::overload_cast(&ExampleMandA::overloaded, py::const_)) + .def("overloaded_const", py::overload_cast(&ExampleMandA::overloaded, py::const_)) + .def("overloaded_const", py::overload_cast(&ExampleMandA::overloaded, py::const_)) + .def("overloaded_const", py::overload_cast(&ExampleMandA::overloaded, py::const_)) +#else + .def("overloaded", static_cast(&ExampleMandA::overloaded)) + .def("overloaded", static_cast(&ExampleMandA::overloaded)) + .def("overloaded", static_cast(&ExampleMandA::overloaded)) + .def("overloaded", static_cast(&ExampleMandA::overloaded)) + .def("overloaded", static_cast(&ExampleMandA::overloaded)) + .def("overloaded", static_cast(&ExampleMandA::overloaded)) + .def("overloaded_float", static_cast(&ExampleMandA::overloaded)) + .def("overloaded_const", static_cast(&ExampleMandA::overloaded)) + .def("overloaded_const", static_cast(&ExampleMandA::overloaded)) + .def("overloaded_const", static_cast(&ExampleMandA::overloaded)) + .def("overloaded_const", static_cast(&ExampleMandA::overloaded)) + .def("overloaded_const", static_cast(&ExampleMandA::overloaded)) +#endif + // test_no_mixed_overloads + // Raise error if trying to mix static/non-static overloads on the same name: + .def_static("add_mixed_overloads1", []() { + auto emna = py::reinterpret_borrow>(py::module::import("pybind11_tests.methods_and_attributes").attr("ExampleMandA")); + emna.def ("overload_mixed1", static_cast(&ExampleMandA::overloaded)) + .def_static("overload_mixed1", static_cast(&ExampleMandA::overloaded)); + }) + .def_static("add_mixed_overloads2", []() { + auto emna = py::reinterpret_borrow>(py::module::import("pybind11_tests.methods_and_attributes").attr("ExampleMandA")); + emna.def_static("overload_mixed2", static_cast(&ExampleMandA::overloaded)) + .def ("overload_mixed2", static_cast(&ExampleMandA::overloaded)); + }) + .def("__str__", &ExampleMandA::toString) + .def_readwrite("value", &ExampleMandA::value); + + // test_copy_method + // Issue #443: can't call copied methods in Python 3 + emna.attr("add2b") = emna.attr("add2"); + + // test_properties, test_static_properties, test_static_cls + py::class_(m, "TestProperties") + .def(py::init<>()) + .def_readonly("def_readonly", &TestProperties::value) + .def_readwrite("def_readwrite", &TestProperties::value) + .def_property("def_writeonly", nullptr, + [](TestProperties& s,int v) { s.value = v; } ) + .def_property("def_property_writeonly", nullptr, &TestProperties::set) + .def_property_readonly("def_property_readonly", &TestProperties::get) + .def_property("def_property", &TestProperties::get, &TestProperties::set) + .def_property("def_property_impossible", nullptr, nullptr) + .def_readonly_static("def_readonly_static", &TestProperties::static_value) + .def_readwrite_static("def_readwrite_static", &TestProperties::static_value) + .def_property_static("def_writeonly_static", nullptr, + [](py::object, int v) { TestProperties::static_value = v; }) + .def_property_readonly_static("def_property_readonly_static", + [](py::object) { return TestProperties::static_get(); }) + .def_property_static("def_property_writeonly_static", nullptr, + [](py::object, int v) { return TestProperties::static_set(v); }) + .def_property_static("def_property_static", + [](py::object) { return TestProperties::static_get(); }, + [](py::object, int v) { TestProperties::static_set(v); }) + .def_property_static("static_cls", + [](py::object cls) { return cls; }, + [](py::object cls, py::function f) { f(cls); }); + + py::class_(m, "TestPropertiesOverride") + .def(py::init<>()) + .def_readonly("def_readonly", &TestPropertiesOverride::value) + .def_readonly_static("def_readonly_static", &TestPropertiesOverride::static_value); + + auto static_get1 = [](py::object) -> const UserType & { return TestPropRVP::sv1; }; + auto static_get2 = [](py::object) -> const UserType & { return TestPropRVP::sv2; }; + auto static_set1 = [](py::object, int v) { TestPropRVP::sv1.set(v); }; + auto static_set2 = [](py::object, int v) { TestPropRVP::sv2.set(v); }; + auto rvp_copy = py::return_value_policy::copy; + + // test_property_return_value_policies + py::class_(m, "TestPropRVP") + .def(py::init<>()) + .def_property_readonly("ro_ref", &TestPropRVP::get1) + .def_property_readonly("ro_copy", &TestPropRVP::get2, rvp_copy) + .def_property_readonly("ro_func", py::cpp_function(&TestPropRVP::get2, rvp_copy)) + .def_property("rw_ref", &TestPropRVP::get1, &TestPropRVP::set1) + .def_property("rw_copy", &TestPropRVP::get2, &TestPropRVP::set2, rvp_copy) + .def_property("rw_func", py::cpp_function(&TestPropRVP::get2, rvp_copy), &TestPropRVP::set2) + .def_property_readonly_static("static_ro_ref", static_get1) + .def_property_readonly_static("static_ro_copy", static_get2, rvp_copy) + .def_property_readonly_static("static_ro_func", py::cpp_function(static_get2, rvp_copy)) + .def_property_static("static_rw_ref", static_get1, static_set1) + .def_property_static("static_rw_copy", static_get2, static_set2, rvp_copy) + .def_property_static("static_rw_func", py::cpp_function(static_get2, rvp_copy), static_set2) + // test_property_rvalue_policy + .def_property_readonly("rvalue", &TestPropRVP::get_rvalue) + .def_property_readonly_static("static_rvalue", [](py::object) { return UserType(1); }); + + // test_metaclass_override + struct MetaclassOverride { }; + py::class_(m, "MetaclassOverride", py::metaclass((PyObject *) &PyType_Type)) + .def_property_readonly_static("readonly", [](py::object) { return 1; }); + +#if !defined(PYPY_VERSION) + // test_dynamic_attributes + class DynamicClass { + public: + DynamicClass() { print_default_created(this); } + ~DynamicClass() { print_destroyed(this); } + }; + py::class_(m, "DynamicClass", py::dynamic_attr()) + .def(py::init()); + + class CppDerivedDynamicClass : public DynamicClass { }; + py::class_(m, "CppDerivedDynamicClass") + .def(py::init()); +#endif + + // test_noconvert_args + // + // Test converting. The ArgAlwaysConverts is just there to make the first no-conversion pass + // fail so that our call always ends up happening via the second dispatch (the one that allows + // some conversion). + class ArgInspector { + public: + ArgInspector1 f(ArgInspector1 a, ArgAlwaysConverts) { return a; } + std::string g(ArgInspector1 a, const ArgInspector1 &b, int c, ArgInspector2 *d, ArgAlwaysConverts) { + return a.arg + "\n" + b.arg + "\n" + std::to_string(c) + "\n" + d->arg; + } + static ArgInspector2 h(ArgInspector2 a, ArgAlwaysConverts) { return a; } + }; + py::class_(m, "ArgInspector") + .def(py::init<>()) + .def("f", &ArgInspector::f, py::arg(), py::arg() = ArgAlwaysConverts()) + .def("g", &ArgInspector::g, "a"_a.noconvert(), "b"_a, "c"_a.noconvert()=13, "d"_a=ArgInspector2(), py::arg() = ArgAlwaysConverts()) + .def_static("h", &ArgInspector::h, py::arg().noconvert(), py::arg() = ArgAlwaysConverts()) + ; + m.def("arg_inspect_func", [](ArgInspector2 a, ArgInspector1 b, ArgAlwaysConverts) { return a.arg + "\n" + b.arg; }, + py::arg().noconvert(false), py::arg_v(nullptr, ArgInspector1()).noconvert(true), py::arg() = ArgAlwaysConverts()); + + m.def("floats_preferred", [](double f) { return 0.5 * f; }, py::arg("f")); + m.def("floats_only", [](double f) { return 0.5 * f; }, py::arg("f").noconvert()); + m.def("ints_preferred", [](int i) { return i / 2; }, py::arg("i")); + m.def("ints_only", [](int i) { return i / 2; }, py::arg("i").noconvert()); + + // test_bad_arg_default + // Issue/PR #648: bad arg default debugging output +#if !defined(NDEBUG) + m.attr("debug_enabled") = true; +#else + m.attr("debug_enabled") = false; +#endif + m.def("bad_arg_def_named", []{ + auto m = py::module::import("pybind11_tests"); + m.def("should_fail", [](int, UnregisteredType) {}, py::arg(), py::arg("a") = UnregisteredType()); + }); + m.def("bad_arg_def_unnamed", []{ + auto m = py::module::import("pybind11_tests"); + m.def("should_fail", [](int, UnregisteredType) {}, py::arg(), py::arg() = UnregisteredType()); + }); + + // test_accepts_none + py::class_>(m, "NoneTester") + .def(py::init<>()); + m.def("no_none1", &none1, py::arg().none(false)); + m.def("no_none2", &none2, py::arg().none(false)); + m.def("no_none3", &none3, py::arg().none(false)); + m.def("no_none4", &none4, py::arg().none(false)); + m.def("no_none5", &none5, py::arg().none(false)); + m.def("ok_none1", &none1); + m.def("ok_none2", &none2, py::arg().none(true)); + m.def("ok_none3", &none3); + m.def("ok_none4", &none4, py::arg().none(true)); + m.def("ok_none5", &none5); + + // test_str_issue + // Issue #283: __str__ called on uninitialized instance when constructor arguments invalid + py::class_(m, "StrIssue") + .def(py::init()) + .def(py::init<>()) + .def("__str__", [](const StrIssue &si) { + return "StrIssue[" + std::to_string(si.val) + "]"; } + ); + + // test_unregistered_base_implementations + // + // Issues #854/910: incompatible function args when member function/pointer is in unregistered + // base class The methods and member pointers below actually resolve to members/pointers in + // UnregisteredBase; before this test/fix they would be registered via lambda with a first + // argument of an unregistered type, and thus uncallable. + py::class_(m, "RegisteredDerived") + .def(py::init<>()) + .def("do_nothing", &RegisteredDerived::do_nothing) + .def("increase_value", &RegisteredDerived::increase_value) + .def_readwrite("rw_value", &RegisteredDerived::rw_value) + .def_readonly("ro_value", &RegisteredDerived::ro_value) + // These should trigger a static_assert if uncommented + //.def_readwrite("fails", &UserType::value) // should trigger a static_assert if uncommented + //.def_readonly("fails", &UserType::value) // should trigger a static_assert if uncommented + .def_property("rw_value_prop", &RegisteredDerived::get_int, &RegisteredDerived::set_int) + .def_property_readonly("ro_value_prop", &RegisteredDerived::get_double) + // This one is in the registered class: + .def("sum", &RegisteredDerived::sum) + ; + + using Adapted = decltype(py::method_adaptor(&RegisteredDerived::do_nothing)); + static_assert(std::is_same::value, ""); + + // test_custom_caster_destruction + // Test that `take_ownership` works on types with a custom type caster when given a pointer + + // default policy: don't take ownership: + m.def("custom_caster_no_destroy", []() { static auto *dt = new DestructionTester(); return dt; }); + + m.def("custom_caster_destroy", []() { return new DestructionTester(); }, + py::return_value_policy::take_ownership); // Takes ownership: destroy when finished + m.def("custom_caster_destroy_const", []() -> const DestructionTester * { return new DestructionTester(); }, + py::return_value_policy::take_ownership); // Likewise (const doesn't inhibit destruction) + m.def("destruction_tester_cstats", &ConstructorStats::get, py::return_value_policy::reference); +} diff --git a/wrap/python/pybind11/tests/test_methods_and_attributes.py b/wrap/python/pybind11/tests/test_methods_and_attributes.py new file mode 100644 index 000000000..86b2c3b4b --- /dev/null +++ b/wrap/python/pybind11/tests/test_methods_and_attributes.py @@ -0,0 +1,512 @@ +import pytest +from pybind11_tests import methods_and_attributes as m +from pybind11_tests import ConstructorStats + + +def test_methods_and_attributes(): + instance1 = m.ExampleMandA() + instance2 = m.ExampleMandA(32) + + instance1.add1(instance2) + instance1.add2(instance2) + instance1.add3(instance2) + instance1.add4(instance2) + instance1.add5(instance2) + instance1.add6(32) + instance1.add7(32) + instance1.add8(32) + instance1.add9(32) + instance1.add10(32) + + assert str(instance1) == "ExampleMandA[value=320]" + assert str(instance2) == "ExampleMandA[value=32]" + assert str(instance1.self1()) == "ExampleMandA[value=320]" + assert str(instance1.self2()) == "ExampleMandA[value=320]" + assert str(instance1.self3()) == "ExampleMandA[value=320]" + assert str(instance1.self4()) == "ExampleMandA[value=320]" + assert str(instance1.self5()) == "ExampleMandA[value=320]" + + assert instance1.internal1() == 320 + assert instance1.internal2() == 320 + assert instance1.internal3() == 320 + assert instance1.internal4() == 320 + assert instance1.internal5() == 320 + + assert instance1.overloaded() == "()" + assert instance1.overloaded(0) == "(int)" + assert instance1.overloaded(1, 1.0) == "(int, float)" + assert instance1.overloaded(2.0, 2) == "(float, int)" + assert instance1.overloaded(3, 3) == "(int, int)" + assert instance1.overloaded(4., 4.) == "(float, float)" + assert instance1.overloaded_const(-3) == "(int) const" + assert instance1.overloaded_const(5, 5.0) == "(int, float) const" + assert instance1.overloaded_const(6.0, 6) == "(float, int) const" + assert instance1.overloaded_const(7, 7) == "(int, int) const" + assert instance1.overloaded_const(8., 8.) == "(float, float) const" + assert instance1.overloaded_float(1, 1) == "(float, float)" + assert instance1.overloaded_float(1, 1.) == "(float, float)" + assert instance1.overloaded_float(1., 1) == "(float, float)" + assert instance1.overloaded_float(1., 1.) == "(float, float)" + + assert instance1.value == 320 + instance1.value = 100 + assert str(instance1) == "ExampleMandA[value=100]" + + cstats = ConstructorStats.get(m.ExampleMandA) + assert cstats.alive() == 2 + del instance1, instance2 + assert cstats.alive() == 0 + assert cstats.values() == ["32"] + assert cstats.default_constructions == 1 + assert cstats.copy_constructions == 3 + assert cstats.move_constructions >= 1 + assert cstats.copy_assignments == 0 + assert cstats.move_assignments == 0 + + +def test_copy_method(): + """Issue #443: calling copied methods fails in Python 3""" + + m.ExampleMandA.add2c = m.ExampleMandA.add2 + m.ExampleMandA.add2d = m.ExampleMandA.add2b + a = m.ExampleMandA(123) + assert a.value == 123 + a.add2(m.ExampleMandA(-100)) + assert a.value == 23 + a.add2b(m.ExampleMandA(20)) + assert a.value == 43 + a.add2c(m.ExampleMandA(6)) + assert a.value == 49 + a.add2d(m.ExampleMandA(-7)) + assert a.value == 42 + + +def test_properties(): + instance = m.TestProperties() + + assert instance.def_readonly == 1 + with pytest.raises(AttributeError): + instance.def_readonly = 2 + + instance.def_readwrite = 2 + assert instance.def_readwrite == 2 + + assert instance.def_property_readonly == 2 + with pytest.raises(AttributeError): + instance.def_property_readonly = 3 + + instance.def_property = 3 + assert instance.def_property == 3 + + with pytest.raises(AttributeError) as excinfo: + dummy = instance.def_property_writeonly # noqa: F841 unused var + assert "unreadable attribute" in str(excinfo) + + instance.def_property_writeonly = 4 + assert instance.def_property_readonly == 4 + + with pytest.raises(AttributeError) as excinfo: + dummy = instance.def_property_impossible # noqa: F841 unused var + assert "unreadable attribute" in str(excinfo) + + with pytest.raises(AttributeError) as excinfo: + instance.def_property_impossible = 5 + assert "can't set attribute" in str(excinfo) + + +def test_static_properties(): + assert m.TestProperties.def_readonly_static == 1 + with pytest.raises(AttributeError) as excinfo: + m.TestProperties.def_readonly_static = 2 + assert "can't set attribute" in str(excinfo) + + m.TestProperties.def_readwrite_static = 2 + assert m.TestProperties.def_readwrite_static == 2 + + with pytest.raises(AttributeError) as excinfo: + dummy = m.TestProperties.def_writeonly_static # noqa: F841 unused var + assert "unreadable attribute" in str(excinfo) + + m.TestProperties.def_writeonly_static = 3 + assert m.TestProperties.def_readonly_static == 3 + + assert m.TestProperties.def_property_readonly_static == 3 + with pytest.raises(AttributeError) as excinfo: + m.TestProperties.def_property_readonly_static = 99 + assert "can't set attribute" in str(excinfo) + + m.TestProperties.def_property_static = 4 + assert m.TestProperties.def_property_static == 4 + + with pytest.raises(AttributeError) as excinfo: + dummy = m.TestProperties.def_property_writeonly_static + assert "unreadable attribute" in str(excinfo) + + m.TestProperties.def_property_writeonly_static = 5 + assert m.TestProperties.def_property_static == 5 + + # Static property read and write via instance + instance = m.TestProperties() + + m.TestProperties.def_readwrite_static = 0 + assert m.TestProperties.def_readwrite_static == 0 + assert instance.def_readwrite_static == 0 + + instance.def_readwrite_static = 2 + assert m.TestProperties.def_readwrite_static == 2 + assert instance.def_readwrite_static == 2 + + with pytest.raises(AttributeError) as excinfo: + dummy = instance.def_property_writeonly_static # noqa: F841 unused var + assert "unreadable attribute" in str(excinfo) + + instance.def_property_writeonly_static = 4 + assert instance.def_property_static == 4 + + # It should be possible to override properties in derived classes + assert m.TestPropertiesOverride().def_readonly == 99 + assert m.TestPropertiesOverride.def_readonly_static == 99 + + +def test_static_cls(): + """Static property getter and setters expect the type object as the their only argument""" + + instance = m.TestProperties() + assert m.TestProperties.static_cls is m.TestProperties + assert instance.static_cls is m.TestProperties + + def check_self(self): + assert self is m.TestProperties + + m.TestProperties.static_cls = check_self + instance.static_cls = check_self + + +def test_metaclass_override(): + """Overriding pybind11's default metaclass changes the behavior of `static_property`""" + + assert type(m.ExampleMandA).__name__ == "pybind11_type" + assert type(m.MetaclassOverride).__name__ == "type" + + assert m.MetaclassOverride.readonly == 1 + assert type(m.MetaclassOverride.__dict__["readonly"]).__name__ == "pybind11_static_property" + + # Regular `type` replaces the property instead of calling `__set__()` + m.MetaclassOverride.readonly = 2 + assert m.MetaclassOverride.readonly == 2 + assert isinstance(m.MetaclassOverride.__dict__["readonly"], int) + + +def test_no_mixed_overloads(): + from pybind11_tests import debug_enabled + + with pytest.raises(RuntimeError) as excinfo: + m.ExampleMandA.add_mixed_overloads1() + assert (str(excinfo.value) == + "overloading a method with both static and instance methods is not supported; " + + ("compile in debug mode for more details" if not debug_enabled else + "error while attempting to bind static method ExampleMandA.overload_mixed1" + "(arg0: float) -> str") + ) + + with pytest.raises(RuntimeError) as excinfo: + m.ExampleMandA.add_mixed_overloads2() + assert (str(excinfo.value) == + "overloading a method with both static and instance methods is not supported; " + + ("compile in debug mode for more details" if not debug_enabled else + "error while attempting to bind instance method ExampleMandA.overload_mixed2" + "(self: pybind11_tests.methods_and_attributes.ExampleMandA, arg0: int, arg1: int)" + " -> str") + ) + + +@pytest.mark.parametrize("access", ["ro", "rw", "static_ro", "static_rw"]) +def test_property_return_value_policies(access): + if not access.startswith("static"): + obj = m.TestPropRVP() + else: + obj = m.TestPropRVP + + ref = getattr(obj, access + "_ref") + assert ref.value == 1 + ref.value = 2 + assert getattr(obj, access + "_ref").value == 2 + ref.value = 1 # restore original value for static properties + + copy = getattr(obj, access + "_copy") + assert copy.value == 1 + copy.value = 2 + assert getattr(obj, access + "_copy").value == 1 + + copy = getattr(obj, access + "_func") + assert copy.value == 1 + copy.value = 2 + assert getattr(obj, access + "_func").value == 1 + + +def test_property_rvalue_policy(): + """When returning an rvalue, the return value policy is automatically changed from + `reference(_internal)` to `move`. The following would not work otherwise.""" + + instance = m.TestPropRVP() + o = instance.rvalue + assert o.value == 1 + + os = m.TestPropRVP.static_rvalue + assert os.value == 1 + + +# https://bitbucket.org/pypy/pypy/issues/2447 +@pytest.unsupported_on_pypy +def test_dynamic_attributes(): + instance = m.DynamicClass() + assert not hasattr(instance, "foo") + assert "foo" not in dir(instance) + + # Dynamically add attribute + instance.foo = 42 + assert hasattr(instance, "foo") + assert instance.foo == 42 + assert "foo" in dir(instance) + + # __dict__ should be accessible and replaceable + assert "foo" in instance.__dict__ + instance.__dict__ = {"bar": True} + assert not hasattr(instance, "foo") + assert hasattr(instance, "bar") + + with pytest.raises(TypeError) as excinfo: + instance.__dict__ = [] + assert str(excinfo.value) == "__dict__ must be set to a dictionary, not a 'list'" + + cstats = ConstructorStats.get(m.DynamicClass) + assert cstats.alive() == 1 + del instance + assert cstats.alive() == 0 + + # Derived classes should work as well + class PythonDerivedDynamicClass(m.DynamicClass): + pass + + for cls in m.CppDerivedDynamicClass, PythonDerivedDynamicClass: + derived = cls() + derived.foobar = 100 + assert derived.foobar == 100 + + assert cstats.alive() == 1 + del derived + assert cstats.alive() == 0 + + +# https://bitbucket.org/pypy/pypy/issues/2447 +@pytest.unsupported_on_pypy +def test_cyclic_gc(): + # One object references itself + instance = m.DynamicClass() + instance.circular_reference = instance + + cstats = ConstructorStats.get(m.DynamicClass) + assert cstats.alive() == 1 + del instance + assert cstats.alive() == 0 + + # Two object reference each other + i1 = m.DynamicClass() + i2 = m.DynamicClass() + i1.cycle = i2 + i2.cycle = i1 + + assert cstats.alive() == 2 + del i1, i2 + assert cstats.alive() == 0 + + +def test_noconvert_args(msg): + a = m.ArgInspector() + assert msg(a.f("hi")) == """ + loading ArgInspector1 argument WITH conversion allowed. Argument value = hi + """ + assert msg(a.g("this is a", "this is b")) == """ + loading ArgInspector1 argument WITHOUT conversion allowed. Argument value = this is a + loading ArgInspector1 argument WITH conversion allowed. Argument value = this is b + 13 + loading ArgInspector2 argument WITH conversion allowed. Argument value = (default arg inspector 2) + """ # noqa: E501 line too long + assert msg(a.g("this is a", "this is b", 42)) == """ + loading ArgInspector1 argument WITHOUT conversion allowed. Argument value = this is a + loading ArgInspector1 argument WITH conversion allowed. Argument value = this is b + 42 + loading ArgInspector2 argument WITH conversion allowed. Argument value = (default arg inspector 2) + """ # noqa: E501 line too long + assert msg(a.g("this is a", "this is b", 42, "this is d")) == """ + loading ArgInspector1 argument WITHOUT conversion allowed. Argument value = this is a + loading ArgInspector1 argument WITH conversion allowed. Argument value = this is b + 42 + loading ArgInspector2 argument WITH conversion allowed. Argument value = this is d + """ + assert (a.h("arg 1") == + "loading ArgInspector2 argument WITHOUT conversion allowed. Argument value = arg 1") + assert msg(m.arg_inspect_func("A1", "A2")) == """ + loading ArgInspector2 argument WITH conversion allowed. Argument value = A1 + loading ArgInspector1 argument WITHOUT conversion allowed. Argument value = A2 + """ + + assert m.floats_preferred(4) == 2.0 + assert m.floats_only(4.0) == 2.0 + with pytest.raises(TypeError) as excinfo: + m.floats_only(4) + assert msg(excinfo.value) == """ + floats_only(): incompatible function arguments. The following argument types are supported: + 1. (f: float) -> float + + Invoked with: 4 + """ + + assert m.ints_preferred(4) == 2 + assert m.ints_preferred(True) == 0 + with pytest.raises(TypeError) as excinfo: + m.ints_preferred(4.0) + assert msg(excinfo.value) == """ + ints_preferred(): incompatible function arguments. The following argument types are supported: + 1. (i: int) -> int + + Invoked with: 4.0 + """ # noqa: E501 line too long + + assert m.ints_only(4) == 2 + with pytest.raises(TypeError) as excinfo: + m.ints_only(4.0) + assert msg(excinfo.value) == """ + ints_only(): incompatible function arguments. The following argument types are supported: + 1. (i: int) -> int + + Invoked with: 4.0 + """ + + +def test_bad_arg_default(msg): + from pybind11_tests import debug_enabled + + with pytest.raises(RuntimeError) as excinfo: + m.bad_arg_def_named() + assert msg(excinfo.value) == ( + "arg(): could not convert default argument 'a: UnregisteredType' in function " + "'should_fail' into a Python object (type not registered yet?)" + if debug_enabled else + "arg(): could not convert default argument into a Python object (type not registered " + "yet?). Compile in debug mode for more information." + ) + + with pytest.raises(RuntimeError) as excinfo: + m.bad_arg_def_unnamed() + assert msg(excinfo.value) == ( + "arg(): could not convert default argument 'UnregisteredType' in function " + "'should_fail' into a Python object (type not registered yet?)" + if debug_enabled else + "arg(): could not convert default argument into a Python object (type not registered " + "yet?). Compile in debug mode for more information." + ) + + +def test_accepts_none(msg): + a = m.NoneTester() + assert m.no_none1(a) == 42 + assert m.no_none2(a) == 42 + assert m.no_none3(a) == 42 + assert m.no_none4(a) == 42 + assert m.no_none5(a) == 42 + assert m.ok_none1(a) == 42 + assert m.ok_none2(a) == 42 + assert m.ok_none3(a) == 42 + assert m.ok_none4(a) == 42 + assert m.ok_none5(a) == 42 + + with pytest.raises(TypeError) as excinfo: + m.no_none1(None) + assert "incompatible function arguments" in str(excinfo.value) + with pytest.raises(TypeError) as excinfo: + m.no_none2(None) + assert "incompatible function arguments" in str(excinfo.value) + with pytest.raises(TypeError) as excinfo: + m.no_none3(None) + assert "incompatible function arguments" in str(excinfo.value) + with pytest.raises(TypeError) as excinfo: + m.no_none4(None) + assert "incompatible function arguments" in str(excinfo.value) + with pytest.raises(TypeError) as excinfo: + m.no_none5(None) + assert "incompatible function arguments" in str(excinfo.value) + + # The first one still raises because you can't pass None as a lvalue reference arg: + with pytest.raises(TypeError) as excinfo: + assert m.ok_none1(None) == -1 + assert msg(excinfo.value) == """ + ok_none1(): incompatible function arguments. The following argument types are supported: + 1. (arg0: m.methods_and_attributes.NoneTester) -> int + + Invoked with: None + """ + + # The rest take the argument as pointer or holder, and accept None: + assert m.ok_none2(None) == -1 + assert m.ok_none3(None) == -1 + assert m.ok_none4(None) == -1 + assert m.ok_none5(None) == -1 + + +def test_str_issue(msg): + """#283: __str__ called on uninitialized instance when constructor arguments invalid""" + + assert str(m.StrIssue(3)) == "StrIssue[3]" + + with pytest.raises(TypeError) as excinfo: + str(m.StrIssue("no", "such", "constructor")) + assert msg(excinfo.value) == """ + __init__(): incompatible constructor arguments. The following argument types are supported: + 1. m.methods_and_attributes.StrIssue(arg0: int) + 2. m.methods_and_attributes.StrIssue() + + Invoked with: 'no', 'such', 'constructor' + """ + + +def test_unregistered_base_implementations(): + a = m.RegisteredDerived() + a.do_nothing() + assert a.rw_value == 42 + assert a.ro_value == 1.25 + a.rw_value += 5 + assert a.sum() == 48.25 + a.increase_value() + assert a.rw_value == 48 + assert a.ro_value == 1.5 + assert a.sum() == 49.5 + assert a.rw_value_prop == 48 + a.rw_value_prop += 1 + assert a.rw_value_prop == 49 + a.increase_value() + assert a.ro_value_prop == 1.75 + + +def test_custom_caster_destruction(): + """Tests that returning a pointer to a type that gets converted with a custom type caster gets + destroyed when the function has py::return_value_policy::take_ownership policy applied.""" + + cstats = m.destruction_tester_cstats() + # This one *doesn't* have take_ownership: the pointer should be used but not destroyed: + z = m.custom_caster_no_destroy() + assert cstats.alive() == 1 and cstats.default_constructions == 1 + assert z + + # take_ownership applied: this constructs a new object, casts it, then destroys it: + z = m.custom_caster_destroy() + assert z + assert cstats.default_constructions == 2 + + # Same, but with a const pointer return (which should *not* inhibit destruction): + z = m.custom_caster_destroy_const() + assert z + assert cstats.default_constructions == 3 + + # Make sure we still only have the original object (from ..._no_destroy()) alive: + assert cstats.alive() == 1 diff --git a/wrap/python/pybind11/tests/test_modules.cpp b/wrap/python/pybind11/tests/test_modules.cpp new file mode 100644 index 000000000..c1475fa62 --- /dev/null +++ b/wrap/python/pybind11/tests/test_modules.cpp @@ -0,0 +1,98 @@ +/* + tests/test_modules.cpp -- nested modules, importing modules, and + internal references + + Copyright (c) 2016 Wenzel Jakob + + All rights reserved. Use of this source code is governed by a + BSD-style license that can be found in the LICENSE file. +*/ + +#include "pybind11_tests.h" +#include "constructor_stats.h" + +TEST_SUBMODULE(modules, m) { + // test_nested_modules + py::module m_sub = m.def_submodule("subsubmodule"); + m_sub.def("submodule_func", []() { return "submodule_func()"; }); + + // test_reference_internal + class A { + public: + A(int v) : v(v) { print_created(this, v); } + ~A() { print_destroyed(this); } + A(const A&) { print_copy_created(this); } + A& operator=(const A ©) { print_copy_assigned(this); v = copy.v; return *this; } + std::string toString() { return "A[" + std::to_string(v) + "]"; } + private: + int v; + }; + py::class_(m_sub, "A") + .def(py::init()) + .def("__repr__", &A::toString); + + class B { + public: + B() { print_default_created(this); } + ~B() { print_destroyed(this); } + B(const B&) { print_copy_created(this); } + B& operator=(const B ©) { print_copy_assigned(this); a1 = copy.a1; a2 = copy.a2; return *this; } + A &get_a1() { return a1; } + A &get_a2() { return a2; } + + A a1{1}; + A a2{2}; + }; + py::class_(m_sub, "B") + .def(py::init<>()) + .def("get_a1", &B::get_a1, "Return the internal A 1", py::return_value_policy::reference_internal) + .def("get_a2", &B::get_a2, "Return the internal A 2", py::return_value_policy::reference_internal) + .def_readwrite("a1", &B::a1) // def_readonly uses an internal reference return policy by default + .def_readwrite("a2", &B::a2); + + m.attr("OD") = py::module::import("collections").attr("OrderedDict"); + + // test_duplicate_registration + // Registering two things with the same name + m.def("duplicate_registration", []() { + class Dupe1 { }; + class Dupe2 { }; + class Dupe3 { }; + class DupeException { }; + + auto dm = py::module("dummy"); + auto failures = py::list(); + + py::class_(dm, "Dupe1"); + py::class_(dm, "Dupe2"); + dm.def("dupe1_factory", []() { return Dupe1(); }); + py::exception(dm, "DupeException"); + + try { + py::class_(dm, "Dupe1"); + failures.append("Dupe1 class"); + } catch (std::runtime_error &) {} + try { + dm.def("Dupe1", []() { return Dupe1(); }); + failures.append("Dupe1 function"); + } catch (std::runtime_error &) {} + try { + py::class_(dm, "dupe1_factory"); + failures.append("dupe1_factory"); + } catch (std::runtime_error &) {} + try { + py::exception(dm, "Dupe2"); + failures.append("Dupe2"); + } catch (std::runtime_error &) {} + try { + dm.def("DupeException", []() { return 30; }); + failures.append("DupeException1"); + } catch (std::runtime_error &) {} + try { + py::class_(dm, "DupeException"); + failures.append("DupeException2"); + } catch (std::runtime_error &) {} + + return failures; + }); +} diff --git a/wrap/python/pybind11/tests/test_modules.py b/wrap/python/pybind11/tests/test_modules.py new file mode 100644 index 000000000..2552838c2 --- /dev/null +++ b/wrap/python/pybind11/tests/test_modules.py @@ -0,0 +1,72 @@ +from pybind11_tests import modules as m +from pybind11_tests.modules import subsubmodule as ms +from pybind11_tests import ConstructorStats + + +def test_nested_modules(): + import pybind11_tests + assert pybind11_tests.__name__ == "pybind11_tests" + assert pybind11_tests.modules.__name__ == "pybind11_tests.modules" + assert pybind11_tests.modules.subsubmodule.__name__ == "pybind11_tests.modules.subsubmodule" + assert m.__name__ == "pybind11_tests.modules" + assert ms.__name__ == "pybind11_tests.modules.subsubmodule" + + assert ms.submodule_func() == "submodule_func()" + + +def test_reference_internal(): + b = ms.B() + assert str(b.get_a1()) == "A[1]" + assert str(b.a1) == "A[1]" + assert str(b.get_a2()) == "A[2]" + assert str(b.a2) == "A[2]" + + b.a1 = ms.A(42) + b.a2 = ms.A(43) + assert str(b.get_a1()) == "A[42]" + assert str(b.a1) == "A[42]" + assert str(b.get_a2()) == "A[43]" + assert str(b.a2) == "A[43]" + + astats, bstats = ConstructorStats.get(ms.A), ConstructorStats.get(ms.B) + assert astats.alive() == 2 + assert bstats.alive() == 1 + del b + assert astats.alive() == 0 + assert bstats.alive() == 0 + assert astats.values() == ['1', '2', '42', '43'] + assert bstats.values() == [] + assert astats.default_constructions == 0 + assert bstats.default_constructions == 1 + assert astats.copy_constructions == 0 + assert bstats.copy_constructions == 0 + # assert astats.move_constructions >= 0 # Don't invoke any + # assert bstats.move_constructions >= 0 # Don't invoke any + assert astats.copy_assignments == 2 + assert bstats.copy_assignments == 0 + assert astats.move_assignments == 0 + assert bstats.move_assignments == 0 + + +def test_importing(): + from pybind11_tests.modules import OD + from collections import OrderedDict + + assert OD is OrderedDict + assert str(OD([(1, 'a'), (2, 'b')])) == "OrderedDict([(1, 'a'), (2, 'b')])" + + +def test_pydoc(): + """Pydoc needs to be able to provide help() for everything inside a pybind11 module""" + import pybind11_tests + import pydoc + + assert pybind11_tests.__name__ == "pybind11_tests" + assert pybind11_tests.__doc__ == "pybind11 test module" + assert pydoc.text.docmodule(pybind11_tests) + + +def test_duplicate_registration(): + """Registering two things with the same name""" + + assert m.duplicate_registration() == [] diff --git a/wrap/python/pybind11/tests/test_multiple_inheritance.cpp b/wrap/python/pybind11/tests/test_multiple_inheritance.cpp new file mode 100644 index 000000000..ba1674fb2 --- /dev/null +++ b/wrap/python/pybind11/tests/test_multiple_inheritance.cpp @@ -0,0 +1,220 @@ +/* + tests/test_multiple_inheritance.cpp -- multiple inheritance, + implicit MI casts + + Copyright (c) 2016 Wenzel Jakob + + All rights reserved. Use of this source code is governed by a + BSD-style license that can be found in the LICENSE file. +*/ + +#include "pybind11_tests.h" +#include "constructor_stats.h" + +// Many bases for testing that multiple inheritance from many classes (i.e. requiring extra +// space for holder constructed flags) works. +template struct BaseN { + BaseN(int i) : i(i) { } + int i; +}; + +// test_mi_static_properties +struct Vanilla { + std::string vanilla() { return "Vanilla"; }; +}; +struct WithStatic1 { + static std::string static_func1() { return "WithStatic1"; }; + static int static_value1; +}; +struct WithStatic2 { + static std::string static_func2() { return "WithStatic2"; }; + static int static_value2; +}; +struct VanillaStaticMix1 : Vanilla, WithStatic1, WithStatic2 { + static std::string static_func() { return "VanillaStaticMix1"; } + static int static_value; +}; +struct VanillaStaticMix2 : WithStatic1, Vanilla, WithStatic2 { + static std::string static_func() { return "VanillaStaticMix2"; } + static int static_value; +}; +int WithStatic1::static_value1 = 1; +int WithStatic2::static_value2 = 2; +int VanillaStaticMix1::static_value = 12; +int VanillaStaticMix2::static_value = 12; + +TEST_SUBMODULE(multiple_inheritance, m) { + + // test_multiple_inheritance_mix1 + // test_multiple_inheritance_mix2 + struct Base1 { + Base1(int i) : i(i) { } + int foo() { return i; } + int i; + }; + py::class_ b1(m, "Base1"); + b1.def(py::init()) + .def("foo", &Base1::foo); + + struct Base2 { + Base2(int i) : i(i) { } + int bar() { return i; } + int i; + }; + py::class_ b2(m, "Base2"); + b2.def(py::init()) + .def("bar", &Base2::bar); + + + // test_multiple_inheritance_cpp + struct Base12 : Base1, Base2 { + Base12(int i, int j) : Base1(i), Base2(j) { } + }; + struct MIType : Base12 { + MIType(int i, int j) : Base12(i, j) { } + }; + py::class_(m, "Base12"); + py::class_(m, "MIType") + .def(py::init()); + + + // test_multiple_inheritance_python_many_bases + #define PYBIND11_BASEN(N) py::class_>(m, "BaseN" #N).def(py::init()).def("f" #N, [](BaseN &b) { return b.i + N; }) + PYBIND11_BASEN( 1); PYBIND11_BASEN( 2); PYBIND11_BASEN( 3); PYBIND11_BASEN( 4); + PYBIND11_BASEN( 5); PYBIND11_BASEN( 6); PYBIND11_BASEN( 7); PYBIND11_BASEN( 8); + PYBIND11_BASEN( 9); PYBIND11_BASEN(10); PYBIND11_BASEN(11); PYBIND11_BASEN(12); + PYBIND11_BASEN(13); PYBIND11_BASEN(14); PYBIND11_BASEN(15); PYBIND11_BASEN(16); + PYBIND11_BASEN(17); + + // Uncommenting this should result in a compile time failure (MI can only be specified via + // template parameters because pybind has to know the types involved; see discussion in #742 for + // details). +// struct Base12v2 : Base1, Base2 { +// Base12v2(int i, int j) : Base1(i), Base2(j) { } +// }; +// py::class_(m, "Base12v2", b1, b2) +// .def(py::init()); + + + // test_multiple_inheritance_virtbase + // Test the case where not all base classes are specified, and where pybind11 requires the + // py::multiple_inheritance flag to perform proper casting between types. + struct Base1a { + Base1a(int i) : i(i) { } + int foo() { return i; } + int i; + }; + py::class_>(m, "Base1a") + .def(py::init()) + .def("foo", &Base1a::foo); + + struct Base2a { + Base2a(int i) : i(i) { } + int bar() { return i; } + int i; + }; + py::class_>(m, "Base2a") + .def(py::init()) + .def("bar", &Base2a::bar); + + struct Base12a : Base1a, Base2a { + Base12a(int i, int j) : Base1a(i), Base2a(j) { } + }; + py::class_>(m, "Base12a", py::multiple_inheritance()) + .def(py::init()); + + m.def("bar_base2a", [](Base2a *b) { return b->bar(); }); + m.def("bar_base2a_sharedptr", [](std::shared_ptr b) { return b->bar(); }); + + // test_mi_unaligned_base + // test_mi_base_return + // Issue #801: invalid casting to derived type with MI bases + struct I801B1 { int a = 1; I801B1() = default; I801B1(const I801B1 &) = default; virtual ~I801B1() = default; }; + struct I801B2 { int b = 2; I801B2() = default; I801B2(const I801B2 &) = default; virtual ~I801B2() = default; }; + struct I801C : I801B1, I801B2 {}; + struct I801D : I801C {}; // Indirect MI + // Unregistered classes: + struct I801B3 { int c = 3; virtual ~I801B3() = default; }; + struct I801E : I801B3, I801D {}; + + py::class_>(m, "I801B1").def(py::init<>()).def_readonly("a", &I801B1::a); + py::class_>(m, "I801B2").def(py::init<>()).def_readonly("b", &I801B2::b); + py::class_>(m, "I801C").def(py::init<>()); + py::class_>(m, "I801D").def(py::init<>()); + + // Two separate issues here: first, we want to recognize a pointer to a base type as being a + // known instance even when the pointer value is unequal (i.e. due to a non-first + // multiple-inheritance base class): + m.def("i801b1_c", [](I801C *c) { return static_cast(c); }); + m.def("i801b2_c", [](I801C *c) { return static_cast(c); }); + m.def("i801b1_d", [](I801D *d) { return static_cast(d); }); + m.def("i801b2_d", [](I801D *d) { return static_cast(d); }); + + // Second, when returned a base class pointer to a derived instance, we cannot assume that the + // pointer is `reinterpret_cast`able to the derived pointer because, like above, the base class + // pointer could be offset. + m.def("i801c_b1", []() -> I801B1 * { return new I801C(); }); + m.def("i801c_b2", []() -> I801B2 * { return new I801C(); }); + m.def("i801d_b1", []() -> I801B1 * { return new I801D(); }); + m.def("i801d_b2", []() -> I801B2 * { return new I801D(); }); + + // Return a base class pointer to a pybind-registered type when the actual derived type + // isn't pybind-registered (and uses multiple-inheritance to offset the pybind base) + m.def("i801e_c", []() -> I801C * { return new I801E(); }); + m.def("i801e_b2", []() -> I801B2 * { return new I801E(); }); + + + // test_mi_static_properties + py::class_(m, "Vanilla") + .def(py::init<>()) + .def("vanilla", &Vanilla::vanilla); + + py::class_(m, "WithStatic1") + .def(py::init<>()) + .def_static("static_func1", &WithStatic1::static_func1) + .def_readwrite_static("static_value1", &WithStatic1::static_value1); + + py::class_(m, "WithStatic2") + .def(py::init<>()) + .def_static("static_func2", &WithStatic2::static_func2) + .def_readwrite_static("static_value2", &WithStatic2::static_value2); + + py::class_( + m, "VanillaStaticMix1") + .def(py::init<>()) + .def_static("static_func", &VanillaStaticMix1::static_func) + .def_readwrite_static("static_value", &VanillaStaticMix1::static_value); + + py::class_( + m, "VanillaStaticMix2") + .def(py::init<>()) + .def_static("static_func", &VanillaStaticMix2::static_func) + .def_readwrite_static("static_value", &VanillaStaticMix2::static_value); + + +#if !defined(PYPY_VERSION) + struct WithDict { }; + struct VanillaDictMix1 : Vanilla, WithDict { }; + struct VanillaDictMix2 : WithDict, Vanilla { }; + py::class_(m, "WithDict", py::dynamic_attr()).def(py::init<>()); + py::class_(m, "VanillaDictMix1").def(py::init<>()); + py::class_(m, "VanillaDictMix2").def(py::init<>()); +#endif + + // test_diamond_inheritance + // Issue #959: segfault when constructing diamond inheritance instance + // All of these have int members so that there will be various unequal pointers involved. + struct B { int b; B() = default; B(const B&) = default; virtual ~B() = default; }; + struct C0 : public virtual B { int c0; }; + struct C1 : public virtual B { int c1; }; + struct D : public C0, public C1 { int d; }; + py::class_(m, "B") + .def("b", [](B *self) { return self; }); + py::class_(m, "C0") + .def("c0", [](C0 *self) { return self; }); + py::class_(m, "C1") + .def("c1", [](C1 *self) { return self; }); + py::class_(m, "D") + .def(py::init<>()); +} diff --git a/wrap/python/pybind11/tests/test_multiple_inheritance.py b/wrap/python/pybind11/tests/test_multiple_inheritance.py new file mode 100644 index 000000000..475dd3b3d --- /dev/null +++ b/wrap/python/pybind11/tests/test_multiple_inheritance.py @@ -0,0 +1,349 @@ +import pytest +from pybind11_tests import ConstructorStats +from pybind11_tests import multiple_inheritance as m + + +def test_multiple_inheritance_cpp(): + mt = m.MIType(3, 4) + + assert mt.foo() == 3 + assert mt.bar() == 4 + + +def test_multiple_inheritance_mix1(): + class Base1: + def __init__(self, i): + self.i = i + + def foo(self): + return self.i + + class MITypePy(Base1, m.Base2): + def __init__(self, i, j): + Base1.__init__(self, i) + m.Base2.__init__(self, j) + + mt = MITypePy(3, 4) + + assert mt.foo() == 3 + assert mt.bar() == 4 + + +def test_multiple_inheritance_mix2(): + + class Base2: + def __init__(self, i): + self.i = i + + def bar(self): + return self.i + + class MITypePy(m.Base1, Base2): + def __init__(self, i, j): + m.Base1.__init__(self, i) + Base2.__init__(self, j) + + mt = MITypePy(3, 4) + + assert mt.foo() == 3 + assert mt.bar() == 4 + + +def test_multiple_inheritance_python(): + + class MI1(m.Base1, m.Base2): + def __init__(self, i, j): + m.Base1.__init__(self, i) + m.Base2.__init__(self, j) + + class B1(object): + def v(self): + return 1 + + class MI2(B1, m.Base1, m.Base2): + def __init__(self, i, j): + B1.__init__(self) + m.Base1.__init__(self, i) + m.Base2.__init__(self, j) + + class MI3(MI2): + def __init__(self, i, j): + MI2.__init__(self, i, j) + + class MI4(MI3, m.Base2): + def __init__(self, i, j): + MI3.__init__(self, i, j) + # This should be ignored (Base2 is already initialized via MI2): + m.Base2.__init__(self, i + 100) + + class MI5(m.Base2, B1, m.Base1): + def __init__(self, i, j): + B1.__init__(self) + m.Base1.__init__(self, i) + m.Base2.__init__(self, j) + + class MI6(m.Base2, B1): + def __init__(self, i): + m.Base2.__init__(self, i) + B1.__init__(self) + + class B2(B1): + def v(self): + return 2 + + class B3(object): + def v(self): + return 3 + + class B4(B3, B2): + def v(self): + return 4 + + class MI7(B4, MI6): + def __init__(self, i): + B4.__init__(self) + MI6.__init__(self, i) + + class MI8(MI6, B3): + def __init__(self, i): + MI6.__init__(self, i) + B3.__init__(self) + + class MI8b(B3, MI6): + def __init__(self, i): + B3.__init__(self) + MI6.__init__(self, i) + + mi1 = MI1(1, 2) + assert mi1.foo() == 1 + assert mi1.bar() == 2 + + mi2 = MI2(3, 4) + assert mi2.v() == 1 + assert mi2.foo() == 3 + assert mi2.bar() == 4 + + mi3 = MI3(5, 6) + assert mi3.v() == 1 + assert mi3.foo() == 5 + assert mi3.bar() == 6 + + mi4 = MI4(7, 8) + assert mi4.v() == 1 + assert mi4.foo() == 7 + assert mi4.bar() == 8 + + mi5 = MI5(10, 11) + assert mi5.v() == 1 + assert mi5.foo() == 10 + assert mi5.bar() == 11 + + mi6 = MI6(12) + assert mi6.v() == 1 + assert mi6.bar() == 12 + + mi7 = MI7(13) + assert mi7.v() == 4 + assert mi7.bar() == 13 + + mi8 = MI8(14) + assert mi8.v() == 1 + assert mi8.bar() == 14 + + mi8b = MI8b(15) + assert mi8b.v() == 3 + assert mi8b.bar() == 15 + + +def test_multiple_inheritance_python_many_bases(): + + class MIMany14(m.BaseN1, m.BaseN2, m.BaseN3, m.BaseN4): + def __init__(self): + m.BaseN1.__init__(self, 1) + m.BaseN2.__init__(self, 2) + m.BaseN3.__init__(self, 3) + m.BaseN4.__init__(self, 4) + + class MIMany58(m.BaseN5, m.BaseN6, m.BaseN7, m.BaseN8): + def __init__(self): + m.BaseN5.__init__(self, 5) + m.BaseN6.__init__(self, 6) + m.BaseN7.__init__(self, 7) + m.BaseN8.__init__(self, 8) + + class MIMany916(m.BaseN9, m.BaseN10, m.BaseN11, m.BaseN12, m.BaseN13, m.BaseN14, m.BaseN15, + m.BaseN16): + def __init__(self): + m.BaseN9.__init__(self, 9) + m.BaseN10.__init__(self, 10) + m.BaseN11.__init__(self, 11) + m.BaseN12.__init__(self, 12) + m.BaseN13.__init__(self, 13) + m.BaseN14.__init__(self, 14) + m.BaseN15.__init__(self, 15) + m.BaseN16.__init__(self, 16) + + class MIMany19(MIMany14, MIMany58, m.BaseN9): + def __init__(self): + MIMany14.__init__(self) + MIMany58.__init__(self) + m.BaseN9.__init__(self, 9) + + class MIMany117(MIMany14, MIMany58, MIMany916, m.BaseN17): + def __init__(self): + MIMany14.__init__(self) + MIMany58.__init__(self) + MIMany916.__init__(self) + m.BaseN17.__init__(self, 17) + + # Inherits from 4 registered C++ classes: can fit in one pointer on any modern arch: + a = MIMany14() + for i in range(1, 4): + assert getattr(a, "f" + str(i))() == 2 * i + + # Inherits from 8: requires 1/2 pointers worth of holder flags on 32/64-bit arch: + b = MIMany916() + for i in range(9, 16): + assert getattr(b, "f" + str(i))() == 2 * i + + # Inherits from 9: requires >= 2 pointers worth of holder flags + c = MIMany19() + for i in range(1, 9): + assert getattr(c, "f" + str(i))() == 2 * i + + # Inherits from 17: requires >= 3 pointers worth of holder flags + d = MIMany117() + for i in range(1, 17): + assert getattr(d, "f" + str(i))() == 2 * i + + +def test_multiple_inheritance_virtbase(): + + class MITypePy(m.Base12a): + def __init__(self, i, j): + m.Base12a.__init__(self, i, j) + + mt = MITypePy(3, 4) + assert mt.bar() == 4 + assert m.bar_base2a(mt) == 4 + assert m.bar_base2a_sharedptr(mt) == 4 + + +def test_mi_static_properties(): + """Mixing bases with and without static properties should be possible + and the result should be independent of base definition order""" + + for d in (m.VanillaStaticMix1(), m.VanillaStaticMix2()): + assert d.vanilla() == "Vanilla" + assert d.static_func1() == "WithStatic1" + assert d.static_func2() == "WithStatic2" + assert d.static_func() == d.__class__.__name__ + + m.WithStatic1.static_value1 = 1 + m.WithStatic2.static_value2 = 2 + assert d.static_value1 == 1 + assert d.static_value2 == 2 + assert d.static_value == 12 + + d.static_value1 = 0 + assert d.static_value1 == 0 + d.static_value2 = 0 + assert d.static_value2 == 0 + d.static_value = 0 + assert d.static_value == 0 + + +@pytest.unsupported_on_pypy +def test_mi_dynamic_attributes(): + """Mixing bases with and without dynamic attribute support""" + + for d in (m.VanillaDictMix1(), m.VanillaDictMix2()): + d.dynamic = 1 + assert d.dynamic == 1 + + +def test_mi_unaligned_base(): + """Returning an offset (non-first MI) base class pointer should recognize the instance""" + + n_inst = ConstructorStats.detail_reg_inst() + + c = m.I801C() + d = m.I801D() + # + 4 below because we have the two instances, and each instance has offset base I801B2 + assert ConstructorStats.detail_reg_inst() == n_inst + 4 + b1c = m.i801b1_c(c) + assert b1c is c + b2c = m.i801b2_c(c) + assert b2c is c + b1d = m.i801b1_d(d) + assert b1d is d + b2d = m.i801b2_d(d) + assert b2d is d + + assert ConstructorStats.detail_reg_inst() == n_inst + 4 # no extra instances + del c, b1c, b2c + assert ConstructorStats.detail_reg_inst() == n_inst + 2 + del d, b1d, b2d + assert ConstructorStats.detail_reg_inst() == n_inst + + +def test_mi_base_return(): + """Tests returning an offset (non-first MI) base class pointer to a derived instance""" + + n_inst = ConstructorStats.detail_reg_inst() + + c1 = m.i801c_b1() + assert type(c1) is m.I801C + assert c1.a == 1 + assert c1.b == 2 + + d1 = m.i801d_b1() + assert type(d1) is m.I801D + assert d1.a == 1 + assert d1.b == 2 + + assert ConstructorStats.detail_reg_inst() == n_inst + 4 + + c2 = m.i801c_b2() + assert type(c2) is m.I801C + assert c2.a == 1 + assert c2.b == 2 + + d2 = m.i801d_b2() + assert type(d2) is m.I801D + assert d2.a == 1 + assert d2.b == 2 + + assert ConstructorStats.detail_reg_inst() == n_inst + 8 + + del c2 + assert ConstructorStats.detail_reg_inst() == n_inst + 6 + del c1, d1, d2 + assert ConstructorStats.detail_reg_inst() == n_inst + + # Returning an unregistered derived type with a registered base; we won't + # pick up the derived type, obviously, but should still work (as an object + # of whatever type was returned). + e1 = m.i801e_c() + assert type(e1) is m.I801C + assert e1.a == 1 + assert e1.b == 2 + + e2 = m.i801e_b2() + assert type(e2) is m.I801B2 + assert e2.b == 2 + + +def test_diamond_inheritance(): + """Tests that diamond inheritance works as expected (issue #959)""" + + # Issue #959: this shouldn't segfault: + d = m.D() + + # Make sure all the various distinct pointers are all recognized as registered instances: + assert d is d.c0() + assert d is d.c1() + assert d is d.b() + assert d is d.c0().b() + assert d is d.c1().b() + assert d is d.c0().c1().b().c0().b() diff --git a/wrap/python/pybind11/tests/test_numpy_array.cpp b/wrap/python/pybind11/tests/test_numpy_array.cpp new file mode 100644 index 000000000..cdf0b82df --- /dev/null +++ b/wrap/python/pybind11/tests/test_numpy_array.cpp @@ -0,0 +1,309 @@ +/* + tests/test_numpy_array.cpp -- test core array functionality + + Copyright (c) 2016 Ivan Smirnov + + All rights reserved. Use of this source code is governed by a + BSD-style license that can be found in the LICENSE file. +*/ + +#include "pybind11_tests.h" + +#include +#include + +#include + +using arr = py::array; +using arr_t = py::array_t; +static_assert(std::is_same::value, ""); + +template arr data(const arr& a, Ix... index) { + return arr(a.nbytes() - a.offset_at(index...), (const uint8_t *) a.data(index...)); +} + +template arr data_t(const arr_t& a, Ix... index) { + return arr(a.size() - a.index_at(index...), a.data(index...)); +} + +template arr& mutate_data(arr& a, Ix... index) { + auto ptr = (uint8_t *) a.mutable_data(index...); + for (ssize_t i = 0; i < a.nbytes() - a.offset_at(index...); i++) + ptr[i] = (uint8_t) (ptr[i] * 2); + return a; +} + +template arr_t& mutate_data_t(arr_t& a, Ix... index) { + auto ptr = a.mutable_data(index...); + for (ssize_t i = 0; i < a.size() - a.index_at(index...); i++) + ptr[i]++; + return a; +} + +template ssize_t index_at(const arr& a, Ix... idx) { return a.index_at(idx...); } +template ssize_t index_at_t(const arr_t& a, Ix... idx) { return a.index_at(idx...); } +template ssize_t offset_at(const arr& a, Ix... idx) { return a.offset_at(idx...); } +template ssize_t offset_at_t(const arr_t& a, Ix... idx) { return a.offset_at(idx...); } +template ssize_t at_t(const arr_t& a, Ix... idx) { return a.at(idx...); } +template arr_t& mutate_at_t(arr_t& a, Ix... idx) { a.mutable_at(idx...)++; return a; } + +#define def_index_fn(name, type) \ + sm.def(#name, [](type a) { return name(a); }); \ + sm.def(#name, [](type a, int i) { return name(a, i); }); \ + sm.def(#name, [](type a, int i, int j) { return name(a, i, j); }); \ + sm.def(#name, [](type a, int i, int j, int k) { return name(a, i, j, k); }); + +template py::handle auxiliaries(T &&r, T2 &&r2) { + if (r.ndim() != 2) throw std::domain_error("error: ndim != 2"); + py::list l; + l.append(*r.data(0, 0)); + l.append(*r2.mutable_data(0, 0)); + l.append(r.data(0, 1) == r2.mutable_data(0, 1)); + l.append(r.ndim()); + l.append(r.itemsize()); + l.append(r.shape(0)); + l.append(r.shape(1)); + l.append(r.size()); + l.append(r.nbytes()); + return l.release(); +} + +// note: declaration at local scope would create a dangling reference! +static int data_i = 42; + +TEST_SUBMODULE(numpy_array, sm) { + try { py::module::import("numpy"); } + catch (...) { return; } + + // test_array_attributes + sm.def("ndim", [](const arr& a) { return a.ndim(); }); + sm.def("shape", [](const arr& a) { return arr(a.ndim(), a.shape()); }); + sm.def("shape", [](const arr& a, ssize_t dim) { return a.shape(dim); }); + sm.def("strides", [](const arr& a) { return arr(a.ndim(), a.strides()); }); + sm.def("strides", [](const arr& a, ssize_t dim) { return a.strides(dim); }); + sm.def("writeable", [](const arr& a) { return a.writeable(); }); + sm.def("size", [](const arr& a) { return a.size(); }); + sm.def("itemsize", [](const arr& a) { return a.itemsize(); }); + sm.def("nbytes", [](const arr& a) { return a.nbytes(); }); + sm.def("owndata", [](const arr& a) { return a.owndata(); }); + + // test_index_offset + def_index_fn(index_at, const arr&); + def_index_fn(index_at_t, const arr_t&); + def_index_fn(offset_at, const arr&); + def_index_fn(offset_at_t, const arr_t&); + // test_data + def_index_fn(data, const arr&); + def_index_fn(data_t, const arr_t&); + // test_mutate_data, test_mutate_readonly + def_index_fn(mutate_data, arr&); + def_index_fn(mutate_data_t, arr_t&); + def_index_fn(at_t, const arr_t&); + def_index_fn(mutate_at_t, arr_t&); + + // test_make_c_f_array + sm.def("make_f_array", [] { return py::array_t({ 2, 2 }, { 4, 8 }); }); + sm.def("make_c_array", [] { return py::array_t({ 2, 2 }, { 8, 4 }); }); + + // test_empty_shaped_array + sm.def("make_empty_shaped_array", [] { return py::array(py::dtype("f"), {}, {}); }); + // test numpy scalars (empty shape, ndim==0) + sm.def("scalar_int", []() { return py::array(py::dtype("i"), {}, {}, &data_i); }); + + // test_wrap + sm.def("wrap", [](py::array a) { + return py::array( + a.dtype(), + {a.shape(), a.shape() + a.ndim()}, + {a.strides(), a.strides() + a.ndim()}, + a.data(), + a + ); + }); + + // test_numpy_view + struct ArrayClass { + int data[2] = { 1, 2 }; + ArrayClass() { py::print("ArrayClass()"); } + ~ArrayClass() { py::print("~ArrayClass()"); } + }; + py::class_(sm, "ArrayClass") + .def(py::init<>()) + .def("numpy_view", [](py::object &obj) { + py::print("ArrayClass::numpy_view()"); + ArrayClass &a = obj.cast(); + return py::array_t({2}, {4}, a.data, obj); + } + ); + + // test_cast_numpy_int64_to_uint64 + sm.def("function_taking_uint64", [](uint64_t) { }); + + // test_isinstance + sm.def("isinstance_untyped", [](py::object yes, py::object no) { + return py::isinstance(yes) && !py::isinstance(no); + }); + sm.def("isinstance_typed", [](py::object o) { + return py::isinstance>(o) && !py::isinstance>(o); + }); + + // test_constructors + sm.def("default_constructors", []() { + return py::dict( + "array"_a=py::array(), + "array_t"_a=py::array_t(), + "array_t"_a=py::array_t() + ); + }); + sm.def("converting_constructors", [](py::object o) { + return py::dict( + "array"_a=py::array(o), + "array_t"_a=py::array_t(o), + "array_t"_a=py::array_t(o) + ); + }); + + // test_overload_resolution + sm.def("overloaded", [](py::array_t) { return "double"; }); + sm.def("overloaded", [](py::array_t) { return "float"; }); + sm.def("overloaded", [](py::array_t) { return "int"; }); + sm.def("overloaded", [](py::array_t) { return "unsigned short"; }); + sm.def("overloaded", [](py::array_t) { return "long long"; }); + sm.def("overloaded", [](py::array_t>) { return "double complex"; }); + sm.def("overloaded", [](py::array_t>) { return "float complex"; }); + + sm.def("overloaded2", [](py::array_t>) { return "double complex"; }); + sm.def("overloaded2", [](py::array_t) { return "double"; }); + sm.def("overloaded2", [](py::array_t>) { return "float complex"; }); + sm.def("overloaded2", [](py::array_t) { return "float"; }); + + // Only accept the exact types: + sm.def("overloaded3", [](py::array_t) { return "int"; }, py::arg().noconvert()); + sm.def("overloaded3", [](py::array_t) { return "double"; }, py::arg().noconvert()); + + // Make sure we don't do unsafe coercion (e.g. float to int) when not using forcecast, but + // rather that float gets converted via the safe (conversion to double) overload: + sm.def("overloaded4", [](py::array_t) { return "long long"; }); + sm.def("overloaded4", [](py::array_t) { return "double"; }); + + // But we do allow conversion to int if forcecast is enabled (but only if no overload matches + // without conversion) + sm.def("overloaded5", [](py::array_t) { return "unsigned int"; }); + sm.def("overloaded5", [](py::array_t) { return "double"; }); + + // test_greedy_string_overload + // Issue 685: ndarray shouldn't go to std::string overload + sm.def("issue685", [](std::string) { return "string"; }); + sm.def("issue685", [](py::array) { return "array"; }); + sm.def("issue685", [](py::object) { return "other"; }); + + // test_array_unchecked_fixed_dims + sm.def("proxy_add2", [](py::array_t a, double v) { + auto r = a.mutable_unchecked<2>(); + for (ssize_t i = 0; i < r.shape(0); i++) + for (ssize_t j = 0; j < r.shape(1); j++) + r(i, j) += v; + }, py::arg().noconvert(), py::arg()); + + sm.def("proxy_init3", [](double start) { + py::array_t a({ 3, 3, 3 }); + auto r = a.mutable_unchecked<3>(); + for (ssize_t i = 0; i < r.shape(0); i++) + for (ssize_t j = 0; j < r.shape(1); j++) + for (ssize_t k = 0; k < r.shape(2); k++) + r(i, j, k) = start++; + return a; + }); + sm.def("proxy_init3F", [](double start) { + py::array_t a({ 3, 3, 3 }); + auto r = a.mutable_unchecked<3>(); + for (ssize_t k = 0; k < r.shape(2); k++) + for (ssize_t j = 0; j < r.shape(1); j++) + for (ssize_t i = 0; i < r.shape(0); i++) + r(i, j, k) = start++; + return a; + }); + sm.def("proxy_squared_L2_norm", [](py::array_t a) { + auto r = a.unchecked<1>(); + double sumsq = 0; + for (ssize_t i = 0; i < r.shape(0); i++) + sumsq += r[i] * r(i); // Either notation works for a 1D array + return sumsq; + }); + + sm.def("proxy_auxiliaries2", [](py::array_t a) { + auto r = a.unchecked<2>(); + auto r2 = a.mutable_unchecked<2>(); + return auxiliaries(r, r2); + }); + + // test_array_unchecked_dyn_dims + // Same as the above, but without a compile-time dimensions specification: + sm.def("proxy_add2_dyn", [](py::array_t a, double v) { + auto r = a.mutable_unchecked(); + if (r.ndim() != 2) throw std::domain_error("error: ndim != 2"); + for (ssize_t i = 0; i < r.shape(0); i++) + for (ssize_t j = 0; j < r.shape(1); j++) + r(i, j) += v; + }, py::arg().noconvert(), py::arg()); + sm.def("proxy_init3_dyn", [](double start) { + py::array_t a({ 3, 3, 3 }); + auto r = a.mutable_unchecked(); + if (r.ndim() != 3) throw std::domain_error("error: ndim != 3"); + for (ssize_t i = 0; i < r.shape(0); i++) + for (ssize_t j = 0; j < r.shape(1); j++) + for (ssize_t k = 0; k < r.shape(2); k++) + r(i, j, k) = start++; + return a; + }); + sm.def("proxy_auxiliaries2_dyn", [](py::array_t a) { + return auxiliaries(a.unchecked(), a.mutable_unchecked()); + }); + + sm.def("array_auxiliaries2", [](py::array_t a) { + return auxiliaries(a, a); + }); + + // test_array_failures + // Issue #785: Uninformative "Unknown internal error" exception when constructing array from empty object: + sm.def("array_fail_test", []() { return py::array(py::object()); }); + sm.def("array_t_fail_test", []() { return py::array_t(py::object()); }); + // Make sure the error from numpy is being passed through: + sm.def("array_fail_test_negative_size", []() { int c = 0; return py::array(-1, &c); }); + + // test_initializer_list + // Issue (unnumbered; reported in #788): regression: initializer lists can be ambiguous + sm.def("array_initializer_list1", []() { return py::array_t(1); }); // { 1 } also works, but clang warns about it + sm.def("array_initializer_list2", []() { return py::array_t({ 1, 2 }); }); + sm.def("array_initializer_list3", []() { return py::array_t({ 1, 2, 3 }); }); + sm.def("array_initializer_list4", []() { return py::array_t({ 1, 2, 3, 4 }); }); + + // test_array_resize + // reshape array to 2D without changing size + sm.def("array_reshape2", [](py::array_t a) { + const ssize_t dim_sz = (ssize_t)std::sqrt(a.size()); + if (dim_sz * dim_sz != a.size()) + throw std::domain_error("array_reshape2: input array total size is not a squared integer"); + a.resize({dim_sz, dim_sz}); + }); + + // resize to 3D array with each dimension = N + sm.def("array_resize3", [](py::array_t a, size_t N, bool refcheck) { + a.resize({N, N, N}, refcheck); + }); + + // test_array_create_and_resize + // return 2D array with Nrows = Ncols = N + sm.def("create_and_resize", [](size_t N) { + py::array_t a; + a.resize({N, N}); + std::fill(a.mutable_data(), a.mutable_data() + a.size(), 42.); + return a; + }); + +#if PY_MAJOR_VERSION >= 3 + sm.def("index_using_ellipsis", [](py::array a) { + return a[py::make_tuple(0, py::ellipsis(), 0)]; + }); +#endif +} diff --git a/wrap/python/pybind11/tests/test_numpy_array.py b/wrap/python/pybind11/tests/test_numpy_array.py new file mode 100644 index 000000000..8bacb7f6d --- /dev/null +++ b/wrap/python/pybind11/tests/test_numpy_array.py @@ -0,0 +1,421 @@ +import pytest +from pybind11_tests import numpy_array as m + +pytestmark = pytest.requires_numpy + +with pytest.suppress(ImportError): + import numpy as np + + +@pytest.fixture(scope='function') +def arr(): + return np.array([[1, 2, 3], [4, 5, 6]], '=u2') + + +def test_array_attributes(): + a = np.array(0, 'f8') + assert m.ndim(a) == 0 + assert all(m.shape(a) == []) + assert all(m.strides(a) == []) + with pytest.raises(IndexError) as excinfo: + m.shape(a, 0) + assert str(excinfo.value) == 'invalid axis: 0 (ndim = 0)' + with pytest.raises(IndexError) as excinfo: + m.strides(a, 0) + assert str(excinfo.value) == 'invalid axis: 0 (ndim = 0)' + assert m.writeable(a) + assert m.size(a) == 1 + assert m.itemsize(a) == 8 + assert m.nbytes(a) == 8 + assert m.owndata(a) + + a = np.array([[1, 2, 3], [4, 5, 6]], 'u2').view() + a.flags.writeable = False + assert m.ndim(a) == 2 + assert all(m.shape(a) == [2, 3]) + assert m.shape(a, 0) == 2 + assert m.shape(a, 1) == 3 + assert all(m.strides(a) == [6, 2]) + assert m.strides(a, 0) == 6 + assert m.strides(a, 1) == 2 + with pytest.raises(IndexError) as excinfo: + m.shape(a, 2) + assert str(excinfo.value) == 'invalid axis: 2 (ndim = 2)' + with pytest.raises(IndexError) as excinfo: + m.strides(a, 2) + assert str(excinfo.value) == 'invalid axis: 2 (ndim = 2)' + assert not m.writeable(a) + assert m.size(a) == 6 + assert m.itemsize(a) == 2 + assert m.nbytes(a) == 12 + assert not m.owndata(a) + + +@pytest.mark.parametrize('args, ret', [([], 0), ([0], 0), ([1], 3), ([0, 1], 1), ([1, 2], 5)]) +def test_index_offset(arr, args, ret): + assert m.index_at(arr, *args) == ret + assert m.index_at_t(arr, *args) == ret + assert m.offset_at(arr, *args) == ret * arr.dtype.itemsize + assert m.offset_at_t(arr, *args) == ret * arr.dtype.itemsize + + +def test_dim_check_fail(arr): + for func in (m.index_at, m.index_at_t, m.offset_at, m.offset_at_t, m.data, m.data_t, + m.mutate_data, m.mutate_data_t): + with pytest.raises(IndexError) as excinfo: + func(arr, 1, 2, 3) + assert str(excinfo.value) == 'too many indices for an array: 3 (ndim = 2)' + + +@pytest.mark.parametrize('args, ret', + [([], [1, 2, 3, 4, 5, 6]), + ([1], [4, 5, 6]), + ([0, 1], [2, 3, 4, 5, 6]), + ([1, 2], [6])]) +def test_data(arr, args, ret): + from sys import byteorder + assert all(m.data_t(arr, *args) == ret) + assert all(m.data(arr, *args)[(0 if byteorder == 'little' else 1)::2] == ret) + assert all(m.data(arr, *args)[(1 if byteorder == 'little' else 0)::2] == 0) + + +@pytest.mark.parametrize('dim', [0, 1, 3]) +def test_at_fail(arr, dim): + for func in m.at_t, m.mutate_at_t: + with pytest.raises(IndexError) as excinfo: + func(arr, *([0] * dim)) + assert str(excinfo.value) == 'index dimension mismatch: {} (ndim = 2)'.format(dim) + + +def test_at(arr): + assert m.at_t(arr, 0, 2) == 3 + assert m.at_t(arr, 1, 0) == 4 + + assert all(m.mutate_at_t(arr, 0, 2).ravel() == [1, 2, 4, 4, 5, 6]) + assert all(m.mutate_at_t(arr, 1, 0).ravel() == [1, 2, 4, 5, 5, 6]) + + +def test_mutate_readonly(arr): + arr.flags.writeable = False + for func, args in (m.mutate_data, ()), (m.mutate_data_t, ()), (m.mutate_at_t, (0, 0)): + with pytest.raises(ValueError) as excinfo: + func(arr, *args) + assert str(excinfo.value) == 'array is not writeable' + + +def test_mutate_data(arr): + assert all(m.mutate_data(arr).ravel() == [2, 4, 6, 8, 10, 12]) + assert all(m.mutate_data(arr).ravel() == [4, 8, 12, 16, 20, 24]) + assert all(m.mutate_data(arr, 1).ravel() == [4, 8, 12, 32, 40, 48]) + assert all(m.mutate_data(arr, 0, 1).ravel() == [4, 16, 24, 64, 80, 96]) + assert all(m.mutate_data(arr, 1, 2).ravel() == [4, 16, 24, 64, 80, 192]) + + assert all(m.mutate_data_t(arr).ravel() == [5, 17, 25, 65, 81, 193]) + assert all(m.mutate_data_t(arr).ravel() == [6, 18, 26, 66, 82, 194]) + assert all(m.mutate_data_t(arr, 1).ravel() == [6, 18, 26, 67, 83, 195]) + assert all(m.mutate_data_t(arr, 0, 1).ravel() == [6, 19, 27, 68, 84, 196]) + assert all(m.mutate_data_t(arr, 1, 2).ravel() == [6, 19, 27, 68, 84, 197]) + + +def test_bounds_check(arr): + for func in (m.index_at, m.index_at_t, m.data, m.data_t, + m.mutate_data, m.mutate_data_t, m.at_t, m.mutate_at_t): + with pytest.raises(IndexError) as excinfo: + func(arr, 2, 0) + assert str(excinfo.value) == 'index 2 is out of bounds for axis 0 with size 2' + with pytest.raises(IndexError) as excinfo: + func(arr, 0, 4) + assert str(excinfo.value) == 'index 4 is out of bounds for axis 1 with size 3' + + +def test_make_c_f_array(): + assert m.make_c_array().flags.c_contiguous + assert not m.make_c_array().flags.f_contiguous + assert m.make_f_array().flags.f_contiguous + assert not m.make_f_array().flags.c_contiguous + + +def test_make_empty_shaped_array(): + m.make_empty_shaped_array() + + # empty shape means numpy scalar, PEP 3118 + assert m.scalar_int().ndim == 0 + assert m.scalar_int().shape == () + assert m.scalar_int() == 42 + + +def test_wrap(): + def assert_references(a, b, base=None): + from distutils.version import LooseVersion + if base is None: + base = a + assert a is not b + assert a.__array_interface__['data'][0] == b.__array_interface__['data'][0] + assert a.shape == b.shape + assert a.strides == b.strides + assert a.flags.c_contiguous == b.flags.c_contiguous + assert a.flags.f_contiguous == b.flags.f_contiguous + assert a.flags.writeable == b.flags.writeable + assert a.flags.aligned == b.flags.aligned + if LooseVersion(np.__version__) >= LooseVersion("1.14.0"): + assert a.flags.writebackifcopy == b.flags.writebackifcopy + else: + assert a.flags.updateifcopy == b.flags.updateifcopy + assert np.all(a == b) + assert not b.flags.owndata + assert b.base is base + if a.flags.writeable and a.ndim == 2: + a[0, 0] = 1234 + assert b[0, 0] == 1234 + + a1 = np.array([1, 2], dtype=np.int16) + assert a1.flags.owndata and a1.base is None + a2 = m.wrap(a1) + assert_references(a1, a2) + + a1 = np.array([[1, 2], [3, 4]], dtype=np.float32, order='F') + assert a1.flags.owndata and a1.base is None + a2 = m.wrap(a1) + assert_references(a1, a2) + + a1 = np.array([[1, 2], [3, 4]], dtype=np.float32, order='C') + a1.flags.writeable = False + a2 = m.wrap(a1) + assert_references(a1, a2) + + a1 = np.random.random((4, 4, 4)) + a2 = m.wrap(a1) + assert_references(a1, a2) + + a1t = a1.transpose() + a2 = m.wrap(a1t) + assert_references(a1t, a2, a1) + + a1d = a1.diagonal() + a2 = m.wrap(a1d) + assert_references(a1d, a2, a1) + + a1m = a1[::-1, ::-1, ::-1] + a2 = m.wrap(a1m) + assert_references(a1m, a2, a1) + + +def test_numpy_view(capture): + with capture: + ac = m.ArrayClass() + ac_view_1 = ac.numpy_view() + ac_view_2 = ac.numpy_view() + assert np.all(ac_view_1 == np.array([1, 2], dtype=np.int32)) + del ac + pytest.gc_collect() + assert capture == """ + ArrayClass() + ArrayClass::numpy_view() + ArrayClass::numpy_view() + """ + ac_view_1[0] = 4 + ac_view_1[1] = 3 + assert ac_view_2[0] == 4 + assert ac_view_2[1] == 3 + with capture: + del ac_view_1 + del ac_view_2 + pytest.gc_collect() + pytest.gc_collect() + assert capture == """ + ~ArrayClass() + """ + + +@pytest.unsupported_on_pypy +def test_cast_numpy_int64_to_uint64(): + m.function_taking_uint64(123) + m.function_taking_uint64(np.uint64(123)) + + +def test_isinstance(): + assert m.isinstance_untyped(np.array([1, 2, 3]), "not an array") + assert m.isinstance_typed(np.array([1.0, 2.0, 3.0])) + + +def test_constructors(): + defaults = m.default_constructors() + for a in defaults.values(): + assert a.size == 0 + assert defaults["array"].dtype == np.array([]).dtype + assert defaults["array_t"].dtype == np.int32 + assert defaults["array_t"].dtype == np.float64 + + results = m.converting_constructors([1, 2, 3]) + for a in results.values(): + np.testing.assert_array_equal(a, [1, 2, 3]) + assert results["array"].dtype == np.int_ + assert results["array_t"].dtype == np.int32 + assert results["array_t"].dtype == np.float64 + + +def test_overload_resolution(msg): + # Exact overload matches: + assert m.overloaded(np.array([1], dtype='float64')) == 'double' + assert m.overloaded(np.array([1], dtype='float32')) == 'float' + assert m.overloaded(np.array([1], dtype='ushort')) == 'unsigned short' + assert m.overloaded(np.array([1], dtype='intc')) == 'int' + assert m.overloaded(np.array([1], dtype='longlong')) == 'long long' + assert m.overloaded(np.array([1], dtype='complex')) == 'double complex' + assert m.overloaded(np.array([1], dtype='csingle')) == 'float complex' + + # No exact match, should call first convertible version: + assert m.overloaded(np.array([1], dtype='uint8')) == 'double' + + with pytest.raises(TypeError) as excinfo: + m.overloaded("not an array") + assert msg(excinfo.value) == """ + overloaded(): incompatible function arguments. The following argument types are supported: + 1. (arg0: numpy.ndarray[float64]) -> str + 2. (arg0: numpy.ndarray[float32]) -> str + 3. (arg0: numpy.ndarray[int32]) -> str + 4. (arg0: numpy.ndarray[uint16]) -> str + 5. (arg0: numpy.ndarray[int64]) -> str + 6. (arg0: numpy.ndarray[complex128]) -> str + 7. (arg0: numpy.ndarray[complex64]) -> str + + Invoked with: 'not an array' + """ + + assert m.overloaded2(np.array([1], dtype='float64')) == 'double' + assert m.overloaded2(np.array([1], dtype='float32')) == 'float' + assert m.overloaded2(np.array([1], dtype='complex64')) == 'float complex' + assert m.overloaded2(np.array([1], dtype='complex128')) == 'double complex' + assert m.overloaded2(np.array([1], dtype='float32')) == 'float' + + assert m.overloaded3(np.array([1], dtype='float64')) == 'double' + assert m.overloaded3(np.array([1], dtype='intc')) == 'int' + expected_exc = """ + overloaded3(): incompatible function arguments. The following argument types are supported: + 1. (arg0: numpy.ndarray[int32]) -> str + 2. (arg0: numpy.ndarray[float64]) -> str + + Invoked with: """ + + with pytest.raises(TypeError) as excinfo: + m.overloaded3(np.array([1], dtype='uintc')) + assert msg(excinfo.value) == expected_exc + repr(np.array([1], dtype='uint32')) + with pytest.raises(TypeError) as excinfo: + m.overloaded3(np.array([1], dtype='float32')) + assert msg(excinfo.value) == expected_exc + repr(np.array([1.], dtype='float32')) + with pytest.raises(TypeError) as excinfo: + m.overloaded3(np.array([1], dtype='complex')) + assert msg(excinfo.value) == expected_exc + repr(np.array([1. + 0.j])) + + # Exact matches: + assert m.overloaded4(np.array([1], dtype='double')) == 'double' + assert m.overloaded4(np.array([1], dtype='longlong')) == 'long long' + # Non-exact matches requiring conversion. Since float to integer isn't a + # save conversion, it should go to the double overload, but short can go to + # either (and so should end up on the first-registered, the long long). + assert m.overloaded4(np.array([1], dtype='float32')) == 'double' + assert m.overloaded4(np.array([1], dtype='short')) == 'long long' + + assert m.overloaded5(np.array([1], dtype='double')) == 'double' + assert m.overloaded5(np.array([1], dtype='uintc')) == 'unsigned int' + assert m.overloaded5(np.array([1], dtype='float32')) == 'unsigned int' + + +def test_greedy_string_overload(): + """Tests fix for #685 - ndarray shouldn't go to std::string overload""" + + assert m.issue685("abc") == "string" + assert m.issue685(np.array([97, 98, 99], dtype='b')) == "array" + assert m.issue685(123) == "other" + + +def test_array_unchecked_fixed_dims(msg): + z1 = np.array([[1, 2], [3, 4]], dtype='float64') + m.proxy_add2(z1, 10) + assert np.all(z1 == [[11, 12], [13, 14]]) + + with pytest.raises(ValueError) as excinfo: + m.proxy_add2(np.array([1., 2, 3]), 5.0) + assert msg(excinfo.value) == "array has incorrect number of dimensions: 1; expected 2" + + expect_c = np.ndarray(shape=(3, 3, 3), buffer=np.array(range(3, 30)), dtype='int') + assert np.all(m.proxy_init3(3.0) == expect_c) + expect_f = np.transpose(expect_c) + assert np.all(m.proxy_init3F(3.0) == expect_f) + + assert m.proxy_squared_L2_norm(np.array(range(6))) == 55 + assert m.proxy_squared_L2_norm(np.array(range(6), dtype="float64")) == 55 + + assert m.proxy_auxiliaries2(z1) == [11, 11, True, 2, 8, 2, 2, 4, 32] + assert m.proxy_auxiliaries2(z1) == m.array_auxiliaries2(z1) + + +def test_array_unchecked_dyn_dims(msg): + z1 = np.array([[1, 2], [3, 4]], dtype='float64') + m.proxy_add2_dyn(z1, 10) + assert np.all(z1 == [[11, 12], [13, 14]]) + + expect_c = np.ndarray(shape=(3, 3, 3), buffer=np.array(range(3, 30)), dtype='int') + assert np.all(m.proxy_init3_dyn(3.0) == expect_c) + + assert m.proxy_auxiliaries2_dyn(z1) == [11, 11, True, 2, 8, 2, 2, 4, 32] + assert m.proxy_auxiliaries2_dyn(z1) == m.array_auxiliaries2(z1) + + +def test_array_failure(): + with pytest.raises(ValueError) as excinfo: + m.array_fail_test() + assert str(excinfo.value) == 'cannot create a pybind11::array from a nullptr' + + with pytest.raises(ValueError) as excinfo: + m.array_t_fail_test() + assert str(excinfo.value) == 'cannot create a pybind11::array_t from a nullptr' + + with pytest.raises(ValueError) as excinfo: + m.array_fail_test_negative_size() + assert str(excinfo.value) == 'negative dimensions are not allowed' + + +def test_initializer_list(): + assert m.array_initializer_list1().shape == (1,) + assert m.array_initializer_list2().shape == (1, 2) + assert m.array_initializer_list3().shape == (1, 2, 3) + assert m.array_initializer_list4().shape == (1, 2, 3, 4) + + +def test_array_resize(msg): + a = np.array([1, 2, 3, 4, 5, 6, 7, 8, 9], dtype='float64') + m.array_reshape2(a) + assert(a.size == 9) + assert(np.all(a == [[1, 2, 3], [4, 5, 6], [7, 8, 9]])) + + # total size change should succced with refcheck off + m.array_resize3(a, 4, False) + assert(a.size == 64) + # ... and fail with refcheck on + try: + m.array_resize3(a, 3, True) + except ValueError as e: + assert(str(e).startswith("cannot resize an array")) + # transposed array doesn't own data + b = a.transpose() + try: + m.array_resize3(b, 3, False) + except ValueError as e: + assert(str(e).startswith("cannot resize this array: it does not own its data")) + # ... but reshape should be fine + m.array_reshape2(b) + assert(b.shape == (8, 8)) + + +@pytest.unsupported_on_pypy +def test_array_create_and_resize(msg): + a = m.create_and_resize(2) + assert(a.size == 4) + assert(np.all(a == 42.)) + + +@pytest.unsupported_on_py2 +def test_index_using_ellipsis(): + a = m.index_using_ellipsis(np.zeros((5, 6, 7))) + assert a.shape == (6,) diff --git a/wrap/python/pybind11/tests/test_numpy_dtypes.cpp b/wrap/python/pybind11/tests/test_numpy_dtypes.cpp new file mode 100644 index 000000000..6e3dc6ba2 --- /dev/null +++ b/wrap/python/pybind11/tests/test_numpy_dtypes.cpp @@ -0,0 +1,466 @@ +/* + tests/test_numpy_dtypes.cpp -- Structured and compound NumPy dtypes + + Copyright (c) 2016 Ivan Smirnov + + All rights reserved. Use of this source code is governed by a + BSD-style license that can be found in the LICENSE file. +*/ + +#include "pybind11_tests.h" +#include + +#ifdef __GNUC__ +#define PYBIND11_PACKED(cls) cls __attribute__((__packed__)) +#else +#define PYBIND11_PACKED(cls) __pragma(pack(push, 1)) cls __pragma(pack(pop)) +#endif + +namespace py = pybind11; + +struct SimpleStruct { + bool bool_; + uint32_t uint_; + float float_; + long double ldbl_; +}; + +std::ostream& operator<<(std::ostream& os, const SimpleStruct& v) { + return os << "s:" << v.bool_ << "," << v.uint_ << "," << v.float_ << "," << v.ldbl_; +} + +PYBIND11_PACKED(struct PackedStruct { + bool bool_; + uint32_t uint_; + float float_; + long double ldbl_; +}); + +std::ostream& operator<<(std::ostream& os, const PackedStruct& v) { + return os << "p:" << v.bool_ << "," << v.uint_ << "," << v.float_ << "," << v.ldbl_; +} + +PYBIND11_PACKED(struct NestedStruct { + SimpleStruct a; + PackedStruct b; +}); + +std::ostream& operator<<(std::ostream& os, const NestedStruct& v) { + return os << "n:a=" << v.a << ";b=" << v.b; +} + +struct PartialStruct { + bool bool_; + uint32_t uint_; + float float_; + uint64_t dummy2; + long double ldbl_; +}; + +struct PartialNestedStruct { + uint64_t dummy1; + PartialStruct a; + uint64_t dummy2; +}; + +struct UnboundStruct { }; + +struct StringStruct { + char a[3]; + std::array b; +}; + +struct ComplexStruct { + std::complex cflt; + std::complex cdbl; +}; + +std::ostream& operator<<(std::ostream& os, const ComplexStruct& v) { + return os << "c:" << v.cflt << "," << v.cdbl; +} + +struct ArrayStruct { + char a[3][4]; + int32_t b[2]; + std::array c; + std::array d[4]; +}; + +PYBIND11_PACKED(struct StructWithUglyNames { + int8_t __x__; + uint64_t __y__; +}); + +enum class E1 : int64_t { A = -1, B = 1 }; +enum E2 : uint8_t { X = 1, Y = 2 }; + +PYBIND11_PACKED(struct EnumStruct { + E1 e1; + E2 e2; +}); + +std::ostream& operator<<(std::ostream& os, const StringStruct& v) { + os << "a='"; + for (size_t i = 0; i < 3 && v.a[i]; i++) os << v.a[i]; + os << "',b='"; + for (size_t i = 0; i < 3 && v.b[i]; i++) os << v.b[i]; + return os << "'"; +} + +std::ostream& operator<<(std::ostream& os, const ArrayStruct& v) { + os << "a={"; + for (int i = 0; i < 3; i++) { + if (i > 0) + os << ','; + os << '{'; + for (int j = 0; j < 3; j++) + os << v.a[i][j] << ','; + os << v.a[i][3] << '}'; + } + os << "},b={" << v.b[0] << ',' << v.b[1]; + os << "},c={" << int(v.c[0]) << ',' << int(v.c[1]) << ',' << int(v.c[2]); + os << "},d={"; + for (int i = 0; i < 4; i++) { + if (i > 0) + os << ','; + os << '{' << v.d[i][0] << ',' << v.d[i][1] << '}'; + } + return os << '}'; +} + +std::ostream& operator<<(std::ostream& os, const EnumStruct& v) { + return os << "e1=" << (v.e1 == E1::A ? "A" : "B") << ",e2=" << (v.e2 == E2::X ? "X" : "Y"); +} + +template +py::array mkarray_via_buffer(size_t n) { + return py::array(py::buffer_info(nullptr, sizeof(T), + py::format_descriptor::format(), + 1, { n }, { sizeof(T) })); +} + +#define SET_TEST_VALS(s, i) do { \ + s.bool_ = (i) % 2 != 0; \ + s.uint_ = (uint32_t) (i); \ + s.float_ = (float) (i) * 1.5f; \ + s.ldbl_ = (long double) (i) * -2.5L; } while (0) + +template +py::array_t create_recarray(size_t n) { + auto arr = mkarray_via_buffer(n); + auto req = arr.request(); + auto ptr = static_cast(req.ptr); + for (size_t i = 0; i < n; i++) { + SET_TEST_VALS(ptr[i], i); + } + return arr; +} + +template +py::list print_recarray(py::array_t arr) { + const auto req = arr.request(); + const auto ptr = static_cast(req.ptr); + auto l = py::list(); + for (ssize_t i = 0; i < req.size; i++) { + std::stringstream ss; + ss << ptr[i]; + l.append(py::str(ss.str())); + } + return l; +} + +py::array_t test_array_ctors(int i) { + using arr_t = py::array_t; + + std::vector data { 1, 2, 3, 4, 5, 6 }; + std::vector shape { 3, 2 }; + std::vector strides { 8, 4 }; + + auto ptr = data.data(); + auto vptr = (void *) ptr; + auto dtype = py::dtype("int32"); + + py::buffer_info buf_ndim1(vptr, 4, "i", 6); + py::buffer_info buf_ndim1_null(nullptr, 4, "i", 6); + py::buffer_info buf_ndim2(vptr, 4, "i", 2, shape, strides); + py::buffer_info buf_ndim2_null(nullptr, 4, "i", 2, shape, strides); + + auto fill = [](py::array arr) { + auto req = arr.request(); + for (int i = 0; i < 6; i++) ((int32_t *) req.ptr)[i] = i + 1; + return arr; + }; + + switch (i) { + // shape: (3, 2) + case 10: return arr_t(shape, strides, ptr); + case 11: return py::array(shape, strides, ptr); + case 12: return py::array(dtype, shape, strides, vptr); + case 13: return arr_t(shape, ptr); + case 14: return py::array(shape, ptr); + case 15: return py::array(dtype, shape, vptr); + case 16: return arr_t(buf_ndim2); + case 17: return py::array(buf_ndim2); + // shape: (3, 2) - post-fill + case 20: return fill(arr_t(shape, strides)); + case 21: return py::array(shape, strides, ptr); // can't have nullptr due to templated ctor + case 22: return fill(py::array(dtype, shape, strides)); + case 23: return fill(arr_t(shape)); + case 24: return py::array(shape, ptr); // can't have nullptr due to templated ctor + case 25: return fill(py::array(dtype, shape)); + case 26: return fill(arr_t(buf_ndim2_null)); + case 27: return fill(py::array(buf_ndim2_null)); + // shape: (6, ) + case 30: return arr_t(6, ptr); + case 31: return py::array(6, ptr); + case 32: return py::array(dtype, 6, vptr); + case 33: return arr_t(buf_ndim1); + case 34: return py::array(buf_ndim1); + // shape: (6, ) + case 40: return fill(arr_t(6)); + case 41: return py::array(6, ptr); // can't have nullptr due to templated ctor + case 42: return fill(py::array(dtype, 6)); + case 43: return fill(arr_t(buf_ndim1_null)); + case 44: return fill(py::array(buf_ndim1_null)); + } + return arr_t(); +} + +py::list test_dtype_ctors() { + py::list list; + list.append(py::dtype("int32")); + list.append(py::dtype(std::string("float64"))); + list.append(py::dtype::from_args(py::str("bool"))); + py::list names, offsets, formats; + py::dict dict; + names.append(py::str("a")); names.append(py::str("b")); dict["names"] = names; + offsets.append(py::int_(1)); offsets.append(py::int_(10)); dict["offsets"] = offsets; + formats.append(py::dtype("int32")); formats.append(py::dtype("float64")); dict["formats"] = formats; + dict["itemsize"] = py::int_(20); + list.append(py::dtype::from_args(dict)); + list.append(py::dtype(names, formats, offsets, 20)); + list.append(py::dtype(py::buffer_info((void *) 0, sizeof(unsigned int), "I", 1))); + list.append(py::dtype(py::buffer_info((void *) 0, 0, "T{i:a:f:b:}", 1))); + return list; +} + +struct A {}; +struct B {}; + +TEST_SUBMODULE(numpy_dtypes, m) { + try { py::module::import("numpy"); } + catch (...) { return; } + + // typeinfo may be registered before the dtype descriptor for scalar casts to work... + py::class_(m, "SimpleStruct"); + + PYBIND11_NUMPY_DTYPE(SimpleStruct, bool_, uint_, float_, ldbl_); + PYBIND11_NUMPY_DTYPE(PackedStruct, bool_, uint_, float_, ldbl_); + PYBIND11_NUMPY_DTYPE(NestedStruct, a, b); + PYBIND11_NUMPY_DTYPE(PartialStruct, bool_, uint_, float_, ldbl_); + PYBIND11_NUMPY_DTYPE(PartialNestedStruct, a); + PYBIND11_NUMPY_DTYPE(StringStruct, a, b); + PYBIND11_NUMPY_DTYPE(ArrayStruct, a, b, c, d); + PYBIND11_NUMPY_DTYPE(EnumStruct, e1, e2); + PYBIND11_NUMPY_DTYPE(ComplexStruct, cflt, cdbl); + + // ... or after + py::class_(m, "PackedStruct"); + + PYBIND11_NUMPY_DTYPE_EX(StructWithUglyNames, __x__, "x", __y__, "y"); + + // If uncommented, this should produce a static_assert failure telling the user that the struct + // is not a POD type +// struct NotPOD { std::string v; NotPOD() : v("hi") {}; }; +// PYBIND11_NUMPY_DTYPE(NotPOD, v); + + // Check that dtypes can be registered programmatically, both from + // initializer lists of field descriptors and from other containers. + py::detail::npy_format_descriptor::register_dtype( + {} + ); + py::detail::npy_format_descriptor::register_dtype( + std::vector{} + ); + + // test_recarray, test_scalar_conversion + m.def("create_rec_simple", &create_recarray); + m.def("create_rec_packed", &create_recarray); + m.def("create_rec_nested", [](size_t n) { // test_signature + py::array_t arr = mkarray_via_buffer(n); + auto req = arr.request(); + auto ptr = static_cast(req.ptr); + for (size_t i = 0; i < n; i++) { + SET_TEST_VALS(ptr[i].a, i); + SET_TEST_VALS(ptr[i].b, i + 1); + } + return arr; + }); + m.def("create_rec_partial", &create_recarray); + m.def("create_rec_partial_nested", [](size_t n) { + py::array_t arr = mkarray_via_buffer(n); + auto req = arr.request(); + auto ptr = static_cast(req.ptr); + for (size_t i = 0; i < n; i++) { + SET_TEST_VALS(ptr[i].a, i); + } + return arr; + }); + m.def("print_rec_simple", &print_recarray); + m.def("print_rec_packed", &print_recarray); + m.def("print_rec_nested", &print_recarray); + + // test_format_descriptors + m.def("get_format_unbound", []() { return py::format_descriptor::format(); }); + m.def("print_format_descriptors", []() { + py::list l; + for (const auto &fmt : { + py::format_descriptor::format(), + py::format_descriptor::format(), + py::format_descriptor::format(), + py::format_descriptor::format(), + py::format_descriptor::format(), + py::format_descriptor::format(), + py::format_descriptor::format(), + py::format_descriptor::format(), + py::format_descriptor::format() + }) { + l.append(py::cast(fmt)); + } + return l; + }); + + // test_dtype + m.def("print_dtypes", []() { + py::list l; + for (const py::handle &d : { + py::dtype::of(), + py::dtype::of(), + py::dtype::of(), + py::dtype::of(), + py::dtype::of(), + py::dtype::of(), + py::dtype::of(), + py::dtype::of(), + py::dtype::of(), + py::dtype::of() + }) + l.append(py::str(d)); + return l; + }); + m.def("test_dtype_ctors", &test_dtype_ctors); + m.def("test_dtype_methods", []() { + py::list list; + auto dt1 = py::dtype::of(); + auto dt2 = py::dtype::of(); + list.append(dt1); list.append(dt2); + list.append(py::bool_(dt1.has_fields())); list.append(py::bool_(dt2.has_fields())); + list.append(py::int_(dt1.itemsize())); list.append(py::int_(dt2.itemsize())); + return list; + }); + struct TrailingPaddingStruct { + int32_t a; + char b; + }; + PYBIND11_NUMPY_DTYPE(TrailingPaddingStruct, a, b); + m.def("trailing_padding_dtype", []() { return py::dtype::of(); }); + + // test_string_array + m.def("create_string_array", [](bool non_empty) { + py::array_t arr = mkarray_via_buffer(non_empty ? 4 : 0); + if (non_empty) { + auto req = arr.request(); + auto ptr = static_cast(req.ptr); + for (ssize_t i = 0; i < req.size * req.itemsize; i++) + static_cast(req.ptr)[i] = 0; + ptr[1].a[0] = 'a'; ptr[1].b[0] = 'a'; + ptr[2].a[0] = 'a'; ptr[2].b[0] = 'a'; + ptr[3].a[0] = 'a'; ptr[3].b[0] = 'a'; + + ptr[2].a[1] = 'b'; ptr[2].b[1] = 'b'; + ptr[3].a[1] = 'b'; ptr[3].b[1] = 'b'; + + ptr[3].a[2] = 'c'; ptr[3].b[2] = 'c'; + } + return arr; + }); + m.def("print_string_array", &print_recarray); + + // test_array_array + m.def("create_array_array", [](size_t n) { + py::array_t arr = mkarray_via_buffer(n); + auto ptr = (ArrayStruct *) arr.mutable_data(); + for (size_t i = 0; i < n; i++) { + for (size_t j = 0; j < 3; j++) + for (size_t k = 0; k < 4; k++) + ptr[i].a[j][k] = char('A' + (i * 100 + j * 10 + k) % 26); + for (size_t j = 0; j < 2; j++) + ptr[i].b[j] = int32_t(i * 1000 + j); + for (size_t j = 0; j < 3; j++) + ptr[i].c[j] = uint8_t(i * 10 + j); + for (size_t j = 0; j < 4; j++) + for (size_t k = 0; k < 2; k++) + ptr[i].d[j][k] = float(i) * 100.0f + float(j) * 10.0f + float(k); + } + return arr; + }); + m.def("print_array_array", &print_recarray); + + // test_enum_array + m.def("create_enum_array", [](size_t n) { + py::array_t arr = mkarray_via_buffer(n); + auto ptr = (EnumStruct *) arr.mutable_data(); + for (size_t i = 0; i < n; i++) { + ptr[i].e1 = static_cast(-1 + ((int) i % 2) * 2); + ptr[i].e2 = static_cast(1 + (i % 2)); + } + return arr; + }); + m.def("print_enum_array", &print_recarray); + + // test_complex_array + m.def("create_complex_array", [](size_t n) { + py::array_t arr = mkarray_via_buffer(n); + auto ptr = (ComplexStruct *) arr.mutable_data(); + for (size_t i = 0; i < n; i++) { + ptr[i].cflt.real(float(i)); + ptr[i].cflt.imag(float(i) + 0.25f); + ptr[i].cdbl.real(double(i) + 0.5); + ptr[i].cdbl.imag(double(i) + 0.75); + } + return arr; + }); + m.def("print_complex_array", &print_recarray); + + // test_array_constructors + m.def("test_array_ctors", &test_array_ctors); + + // test_compare_buffer_info + struct CompareStruct { + bool x; + uint32_t y; + float z; + }; + PYBIND11_NUMPY_DTYPE(CompareStruct, x, y, z); + m.def("compare_buffer_info", []() { + py::list list; + list.append(py::bool_(py::detail::compare_buffer_info::compare(py::buffer_info(nullptr, sizeof(float), "f", 1)))); + list.append(py::bool_(py::detail::compare_buffer_info::compare(py::buffer_info(nullptr, sizeof(int), "I", 1)))); + list.append(py::bool_(py::detail::compare_buffer_info::compare(py::buffer_info(nullptr, sizeof(long), "l", 1)))); + list.append(py::bool_(py::detail::compare_buffer_info::compare(py::buffer_info(nullptr, sizeof(long), sizeof(long) == sizeof(int) ? "i" : "q", 1)))); + list.append(py::bool_(py::detail::compare_buffer_info::compare(py::buffer_info(nullptr, sizeof(CompareStruct), "T{?:x:3xI:y:f:z:}", 1)))); + return list; + }); + m.def("buffer_to_dtype", [](py::buffer& buf) { return py::dtype(buf.request()); }); + + // test_scalar_conversion + m.def("f_simple", [](SimpleStruct s) { return s.uint_ * 10; }); + m.def("f_packed", [](PackedStruct s) { return s.uint_ * 10; }); + m.def("f_nested", [](NestedStruct s) { return s.a.uint_ * 10; }); + + // test_register_dtype + m.def("register_dtype", []() { PYBIND11_NUMPY_DTYPE(SimpleStruct, bool_, uint_, float_, ldbl_); }); + + // test_str_leak + m.def("dtype_wrapper", [](py::object d) { return py::dtype::from_args(std::move(d)); }); +} diff --git a/wrap/python/pybind11/tests/test_numpy_dtypes.py b/wrap/python/pybind11/tests/test_numpy_dtypes.py new file mode 100644 index 000000000..2e6388517 --- /dev/null +++ b/wrap/python/pybind11/tests/test_numpy_dtypes.py @@ -0,0 +1,310 @@ +import re +import pytest +from pybind11_tests import numpy_dtypes as m + +pytestmark = pytest.requires_numpy + +with pytest.suppress(ImportError): + import numpy as np + + +@pytest.fixture(scope='module') +def simple_dtype(): + ld = np.dtype('longdouble') + return np.dtype({'names': ['bool_', 'uint_', 'float_', 'ldbl_'], + 'formats': ['?', 'u4', 'f4', 'f{}'.format(ld.itemsize)], + 'offsets': [0, 4, 8, (16 if ld.alignment > 4 else 12)]}) + + +@pytest.fixture(scope='module') +def packed_dtype(): + return np.dtype([('bool_', '?'), ('uint_', 'u4'), ('float_', 'f4'), ('ldbl_', 'g')]) + + +def dt_fmt(): + from sys import byteorder + e = '<' if byteorder == 'little' else '>' + return ("{{'names':['bool_','uint_','float_','ldbl_']," + " 'formats':['?','" + e + "u4','" + e + "f4','" + e + "f{}']," + " 'offsets':[0,4,8,{}], 'itemsize':{}}}") + + +def simple_dtype_fmt(): + ld = np.dtype('longdouble') + simple_ld_off = 12 + 4 * (ld.alignment > 4) + return dt_fmt().format(ld.itemsize, simple_ld_off, simple_ld_off + ld.itemsize) + + +def packed_dtype_fmt(): + from sys import byteorder + return "[('bool_', '?'), ('uint_', '{e}u4'), ('float_', '{e}f4'), ('ldbl_', '{e}f{}')]".format( + np.dtype('longdouble').itemsize, e='<' if byteorder == 'little' else '>') + + +def partial_ld_offset(): + return 12 + 4 * (np.dtype('uint64').alignment > 4) + 8 + 8 * ( + np.dtype('longdouble').alignment > 8) + + +def partial_dtype_fmt(): + ld = np.dtype('longdouble') + partial_ld_off = partial_ld_offset() + return dt_fmt().format(ld.itemsize, partial_ld_off, partial_ld_off + ld.itemsize) + + +def partial_nested_fmt(): + ld = np.dtype('longdouble') + partial_nested_off = 8 + 8 * (ld.alignment > 8) + partial_ld_off = partial_ld_offset() + partial_nested_size = partial_nested_off * 2 + partial_ld_off + ld.itemsize + return "{{'names':['a'], 'formats':[{}], 'offsets':[{}], 'itemsize':{}}}".format( + partial_dtype_fmt(), partial_nested_off, partial_nested_size) + + +def assert_equal(actual, expected_data, expected_dtype): + np.testing.assert_equal(actual, np.array(expected_data, dtype=expected_dtype)) + + +def test_format_descriptors(): + with pytest.raises(RuntimeError) as excinfo: + m.get_format_unbound() + assert re.match('^NumPy type info missing for .*UnboundStruct.*$', str(excinfo.value)) + + ld = np.dtype('longdouble') + ldbl_fmt = ('4x' if ld.alignment > 4 else '') + ld.char + ss_fmt = "^T{?:bool_:3xI:uint_:f:float_:" + ldbl_fmt + ":ldbl_:}" + dbl = np.dtype('double') + partial_fmt = ("^T{?:bool_:3xI:uint_:f:float_:" + + str(4 * (dbl.alignment > 4) + dbl.itemsize + 8 * (ld.alignment > 8)) + + "xg:ldbl_:}") + nested_extra = str(max(8, ld.alignment)) + assert m.print_format_descriptors() == [ + ss_fmt, + "^T{?:bool_:I:uint_:f:float_:g:ldbl_:}", + "^T{" + ss_fmt + ":a:^T{?:bool_:I:uint_:f:float_:g:ldbl_:}:b:}", + partial_fmt, + "^T{" + nested_extra + "x" + partial_fmt + ":a:" + nested_extra + "x}", + "^T{3s:a:3s:b:}", + "^T{(3)4s:a:(2)i:b:(3)B:c:1x(4, 2)f:d:}", + '^T{q:e1:B:e2:}', + '^T{Zf:cflt:Zd:cdbl:}' + ] + + +def test_dtype(simple_dtype): + from sys import byteorder + e = '<' if byteorder == 'little' else '>' + + assert m.print_dtypes() == [ + simple_dtype_fmt(), + packed_dtype_fmt(), + "[('a', {}), ('b', {})]".format(simple_dtype_fmt(), packed_dtype_fmt()), + partial_dtype_fmt(), + partial_nested_fmt(), + "[('a', 'S3'), ('b', 'S3')]", + ("{{'names':['a','b','c','d'], " + + "'formats':[('S4', (3,)),('" + e + "i4', (2,)),('u1', (3,)),('" + e + "f4', (4, 2))], " + + "'offsets':[0,12,20,24], 'itemsize':56}}").format(e=e), + "[('e1', '" + e + "i8'), ('e2', 'u1')]", + "[('x', 'i1'), ('y', '" + e + "u8')]", + "[('cflt', '" + e + "c8'), ('cdbl', '" + e + "c16')]" + ] + + d1 = np.dtype({'names': ['a', 'b'], 'formats': ['int32', 'float64'], + 'offsets': [1, 10], 'itemsize': 20}) + d2 = np.dtype([('a', 'i4'), ('b', 'f4')]) + assert m.test_dtype_ctors() == [np.dtype('int32'), np.dtype('float64'), + np.dtype('bool'), d1, d1, np.dtype('uint32'), d2] + + assert m.test_dtype_methods() == [np.dtype('int32'), simple_dtype, False, True, + np.dtype('int32').itemsize, simple_dtype.itemsize] + + assert m.trailing_padding_dtype() == m.buffer_to_dtype(np.zeros(1, m.trailing_padding_dtype())) + + +def test_recarray(simple_dtype, packed_dtype): + elements = [(False, 0, 0.0, -0.0), (True, 1, 1.5, -2.5), (False, 2, 3.0, -5.0)] + + for func, dtype in [(m.create_rec_simple, simple_dtype), (m.create_rec_packed, packed_dtype)]: + arr = func(0) + assert arr.dtype == dtype + assert_equal(arr, [], simple_dtype) + assert_equal(arr, [], packed_dtype) + + arr = func(3) + assert arr.dtype == dtype + assert_equal(arr, elements, simple_dtype) + assert_equal(arr, elements, packed_dtype) + + if dtype == simple_dtype: + assert m.print_rec_simple(arr) == [ + "s:0,0,0,-0", + "s:1,1,1.5,-2.5", + "s:0,2,3,-5" + ] + else: + assert m.print_rec_packed(arr) == [ + "p:0,0,0,-0", + "p:1,1,1.5,-2.5", + "p:0,2,3,-5" + ] + + nested_dtype = np.dtype([('a', simple_dtype), ('b', packed_dtype)]) + + arr = m.create_rec_nested(0) + assert arr.dtype == nested_dtype + assert_equal(arr, [], nested_dtype) + + arr = m.create_rec_nested(3) + assert arr.dtype == nested_dtype + assert_equal(arr, [((False, 0, 0.0, -0.0), (True, 1, 1.5, -2.5)), + ((True, 1, 1.5, -2.5), (False, 2, 3.0, -5.0)), + ((False, 2, 3.0, -5.0), (True, 3, 4.5, -7.5))], nested_dtype) + assert m.print_rec_nested(arr) == [ + "n:a=s:0,0,0,-0;b=p:1,1,1.5,-2.5", + "n:a=s:1,1,1.5,-2.5;b=p:0,2,3,-5", + "n:a=s:0,2,3,-5;b=p:1,3,4.5,-7.5" + ] + + arr = m.create_rec_partial(3) + assert str(arr.dtype) == partial_dtype_fmt() + partial_dtype = arr.dtype + assert '' not in arr.dtype.fields + assert partial_dtype.itemsize > simple_dtype.itemsize + assert_equal(arr, elements, simple_dtype) + assert_equal(arr, elements, packed_dtype) + + arr = m.create_rec_partial_nested(3) + assert str(arr.dtype) == partial_nested_fmt() + assert '' not in arr.dtype.fields + assert '' not in arr.dtype.fields['a'][0].fields + assert arr.dtype.itemsize > partial_dtype.itemsize + np.testing.assert_equal(arr['a'], m.create_rec_partial(3)) + + +def test_array_constructors(): + data = np.arange(1, 7, dtype='int32') + for i in range(8): + np.testing.assert_array_equal(m.test_array_ctors(10 + i), data.reshape((3, 2))) + np.testing.assert_array_equal(m.test_array_ctors(20 + i), data.reshape((3, 2))) + for i in range(5): + np.testing.assert_array_equal(m.test_array_ctors(30 + i), data) + np.testing.assert_array_equal(m.test_array_ctors(40 + i), data) + + +def test_string_array(): + arr = m.create_string_array(True) + assert str(arr.dtype) == "[('a', 'S3'), ('b', 'S3')]" + assert m.print_string_array(arr) == [ + "a='',b=''", + "a='a',b='a'", + "a='ab',b='ab'", + "a='abc',b='abc'" + ] + dtype = arr.dtype + assert arr['a'].tolist() == [b'', b'a', b'ab', b'abc'] + assert arr['b'].tolist() == [b'', b'a', b'ab', b'abc'] + arr = m.create_string_array(False) + assert dtype == arr.dtype + + +def test_array_array(): + from sys import byteorder + e = '<' if byteorder == 'little' else '>' + + arr = m.create_array_array(3) + assert str(arr.dtype) == ( + "{{'names':['a','b','c','d'], " + + "'formats':[('S4', (3,)),('" + e + "i4', (2,)),('u1', (3,)),('{e}f4', (4, 2))], " + + "'offsets':[0,12,20,24], 'itemsize':56}}").format(e=e) + assert m.print_array_array(arr) == [ + "a={{A,B,C,D},{K,L,M,N},{U,V,W,X}},b={0,1}," + + "c={0,1,2},d={{0,1},{10,11},{20,21},{30,31}}", + "a={{W,X,Y,Z},{G,H,I,J},{Q,R,S,T}},b={1000,1001}," + + "c={10,11,12},d={{100,101},{110,111},{120,121},{130,131}}", + "a={{S,T,U,V},{C,D,E,F},{M,N,O,P}},b={2000,2001}," + + "c={20,21,22},d={{200,201},{210,211},{220,221},{230,231}}", + ] + assert arr['a'].tolist() == [[b'ABCD', b'KLMN', b'UVWX'], + [b'WXYZ', b'GHIJ', b'QRST'], + [b'STUV', b'CDEF', b'MNOP']] + assert arr['b'].tolist() == [[0, 1], [1000, 1001], [2000, 2001]] + assert m.create_array_array(0).dtype == arr.dtype + + +def test_enum_array(): + from sys import byteorder + e = '<' if byteorder == 'little' else '>' + + arr = m.create_enum_array(3) + dtype = arr.dtype + assert dtype == np.dtype([('e1', e + 'i8'), ('e2', 'u1')]) + assert m.print_enum_array(arr) == [ + "e1=A,e2=X", + "e1=B,e2=Y", + "e1=A,e2=X" + ] + assert arr['e1'].tolist() == [-1, 1, -1] + assert arr['e2'].tolist() == [1, 2, 1] + assert m.create_enum_array(0).dtype == dtype + + +def test_complex_array(): + from sys import byteorder + e = '<' if byteorder == 'little' else '>' + + arr = m.create_complex_array(3) + dtype = arr.dtype + assert dtype == np.dtype([('cflt', e + 'c8'), ('cdbl', e + 'c16')]) + assert m.print_complex_array(arr) == [ + "c:(0,0.25),(0.5,0.75)", + "c:(1,1.25),(1.5,1.75)", + "c:(2,2.25),(2.5,2.75)" + ] + assert arr['cflt'].tolist() == [0.0 + 0.25j, 1.0 + 1.25j, 2.0 + 2.25j] + assert arr['cdbl'].tolist() == [0.5 + 0.75j, 1.5 + 1.75j, 2.5 + 2.75j] + assert m.create_complex_array(0).dtype == dtype + + +def test_signature(doc): + assert doc(m.create_rec_nested) == \ + "create_rec_nested(arg0: int) -> numpy.ndarray[NestedStruct]" + + +def test_scalar_conversion(): + n = 3 + arrays = [m.create_rec_simple(n), m.create_rec_packed(n), + m.create_rec_nested(n), m.create_enum_array(n)] + funcs = [m.f_simple, m.f_packed, m.f_nested] + + for i, func in enumerate(funcs): + for j, arr in enumerate(arrays): + if i == j and i < 2: + assert [func(arr[k]) for k in range(n)] == [k * 10 for k in range(n)] + else: + with pytest.raises(TypeError) as excinfo: + func(arr[0]) + assert 'incompatible function arguments' in str(excinfo.value) + + +def test_register_dtype(): + with pytest.raises(RuntimeError) as excinfo: + m.register_dtype() + assert 'dtype is already registered' in str(excinfo.value) + + +@pytest.unsupported_on_pypy +def test_str_leak(): + from sys import getrefcount + fmt = "f4" + pytest.gc_collect() + start = getrefcount(fmt) + d = m.dtype_wrapper(fmt) + assert d is np.dtype("f4") + del d + pytest.gc_collect() + assert getrefcount(fmt) == start + + +def test_compare_buffer_info(): + assert all(m.compare_buffer_info()) diff --git a/wrap/python/pybind11/tests/test_numpy_vectorize.cpp b/wrap/python/pybind11/tests/test_numpy_vectorize.cpp new file mode 100644 index 000000000..a875a74b9 --- /dev/null +++ b/wrap/python/pybind11/tests/test_numpy_vectorize.cpp @@ -0,0 +1,89 @@ +/* + tests/test_numpy_vectorize.cpp -- auto-vectorize functions over NumPy array + arguments + + Copyright (c) 2016 Wenzel Jakob + + All rights reserved. Use of this source code is governed by a + BSD-style license that can be found in the LICENSE file. +*/ + +#include "pybind11_tests.h" +#include + +double my_func(int x, float y, double z) { + py::print("my_func(x:int={}, y:float={:.0f}, z:float={:.0f})"_s.format(x, y, z)); + return (float) x*y*z; +} + +TEST_SUBMODULE(numpy_vectorize, m) { + try { py::module::import("numpy"); } + catch (...) { return; } + + // test_vectorize, test_docs, test_array_collapse + // Vectorize all arguments of a function (though non-vector arguments are also allowed) + m.def("vectorized_func", py::vectorize(my_func)); + + // Vectorize a lambda function with a capture object (e.g. to exclude some arguments from the vectorization) + m.def("vectorized_func2", + [](py::array_t x, py::array_t y, float z) { + return py::vectorize([z](int x, float y) { return my_func(x, y, z); })(x, y); + } + ); + + // Vectorize a complex-valued function + m.def("vectorized_func3", py::vectorize( + [](std::complex c) { return c * std::complex(2.f); } + )); + + // test_type_selection + // Numpy function which only accepts specific data types + m.def("selective_func", [](py::array_t) { return "Int branch taken."; }); + m.def("selective_func", [](py::array_t) { return "Float branch taken."; }); + m.def("selective_func", [](py::array_t, py::array::c_style>) { return "Complex float branch taken."; }); + + + // test_passthrough_arguments + // Passthrough test: references and non-pod types should be automatically passed through (in the + // function definition below, only `b`, `d`, and `g` are vectorized): + struct NonPODClass { + NonPODClass(int v) : value{v} {} + int value; + }; + py::class_(m, "NonPODClass").def(py::init()); + m.def("vec_passthrough", py::vectorize( + [](double *a, double b, py::array_t c, const int &d, int &e, NonPODClass f, const double g) { + return *a + b + c.at(0) + d + e + f.value + g; + } + )); + + // test_method_vectorization + struct VectorizeTestClass { + VectorizeTestClass(int v) : value{v} {}; + float method(int x, float y) { return y + (float) (x + value); } + int value = 0; + }; + py::class_ vtc(m, "VectorizeTestClass"); + vtc .def(py::init()) + .def_readwrite("value", &VectorizeTestClass::value); + + // Automatic vectorizing of methods + vtc.def("method", py::vectorize(&VectorizeTestClass::method)); + + // test_trivial_broadcasting + // Internal optimization test for whether the input is trivially broadcastable: + py::enum_(m, "trivial") + .value("f_trivial", py::detail::broadcast_trivial::f_trivial) + .value("c_trivial", py::detail::broadcast_trivial::c_trivial) + .value("non_trivial", py::detail::broadcast_trivial::non_trivial); + m.def("vectorized_is_trivial", []( + py::array_t arg1, + py::array_t arg2, + py::array_t arg3 + ) { + ssize_t ndim; + std::vector shape; + std::array buffers {{ arg1.request(), arg2.request(), arg3.request() }}; + return py::detail::broadcast(buffers, ndim, shape); + }); +} diff --git a/wrap/python/pybind11/tests/test_numpy_vectorize.py b/wrap/python/pybind11/tests/test_numpy_vectorize.py new file mode 100644 index 000000000..0e9c88397 --- /dev/null +++ b/wrap/python/pybind11/tests/test_numpy_vectorize.py @@ -0,0 +1,196 @@ +import pytest +from pybind11_tests import numpy_vectorize as m + +pytestmark = pytest.requires_numpy + +with pytest.suppress(ImportError): + import numpy as np + + +def test_vectorize(capture): + assert np.isclose(m.vectorized_func3(np.array(3 + 7j)), [6 + 14j]) + + for f in [m.vectorized_func, m.vectorized_func2]: + with capture: + assert np.isclose(f(1, 2, 3), 6) + assert capture == "my_func(x:int=1, y:float=2, z:float=3)" + with capture: + assert np.isclose(f(np.array(1), np.array(2), 3), 6) + assert capture == "my_func(x:int=1, y:float=2, z:float=3)" + with capture: + assert np.allclose(f(np.array([1, 3]), np.array([2, 4]), 3), [6, 36]) + assert capture == """ + my_func(x:int=1, y:float=2, z:float=3) + my_func(x:int=3, y:float=4, z:float=3) + """ + with capture: + a = np.array([[1, 2], [3, 4]], order='F') + b = np.array([[10, 20], [30, 40]], order='F') + c = 3 + result = f(a, b, c) + assert np.allclose(result, a * b * c) + assert result.flags.f_contiguous + # All inputs are F order and full or singletons, so we the result is in col-major order: + assert capture == """ + my_func(x:int=1, y:float=10, z:float=3) + my_func(x:int=3, y:float=30, z:float=3) + my_func(x:int=2, y:float=20, z:float=3) + my_func(x:int=4, y:float=40, z:float=3) + """ + with capture: + a, b, c = np.array([[1, 3, 5], [7, 9, 11]]), np.array([[2, 4, 6], [8, 10, 12]]), 3 + assert np.allclose(f(a, b, c), a * b * c) + assert capture == """ + my_func(x:int=1, y:float=2, z:float=3) + my_func(x:int=3, y:float=4, z:float=3) + my_func(x:int=5, y:float=6, z:float=3) + my_func(x:int=7, y:float=8, z:float=3) + my_func(x:int=9, y:float=10, z:float=3) + my_func(x:int=11, y:float=12, z:float=3) + """ + with capture: + a, b, c = np.array([[1, 2, 3], [4, 5, 6]]), np.array([2, 3, 4]), 2 + assert np.allclose(f(a, b, c), a * b * c) + assert capture == """ + my_func(x:int=1, y:float=2, z:float=2) + my_func(x:int=2, y:float=3, z:float=2) + my_func(x:int=3, y:float=4, z:float=2) + my_func(x:int=4, y:float=2, z:float=2) + my_func(x:int=5, y:float=3, z:float=2) + my_func(x:int=6, y:float=4, z:float=2) + """ + with capture: + a, b, c = np.array([[1, 2, 3], [4, 5, 6]]), np.array([[2], [3]]), 2 + assert np.allclose(f(a, b, c), a * b * c) + assert capture == """ + my_func(x:int=1, y:float=2, z:float=2) + my_func(x:int=2, y:float=2, z:float=2) + my_func(x:int=3, y:float=2, z:float=2) + my_func(x:int=4, y:float=3, z:float=2) + my_func(x:int=5, y:float=3, z:float=2) + my_func(x:int=6, y:float=3, z:float=2) + """ + with capture: + a, b, c = np.array([[1, 2, 3], [4, 5, 6]], order='F'), np.array([[2], [3]]), 2 + assert np.allclose(f(a, b, c), a * b * c) + assert capture == """ + my_func(x:int=1, y:float=2, z:float=2) + my_func(x:int=2, y:float=2, z:float=2) + my_func(x:int=3, y:float=2, z:float=2) + my_func(x:int=4, y:float=3, z:float=2) + my_func(x:int=5, y:float=3, z:float=2) + my_func(x:int=6, y:float=3, z:float=2) + """ + with capture: + a, b, c = np.array([[1, 2, 3], [4, 5, 6]])[::, ::2], np.array([[2], [3]]), 2 + assert np.allclose(f(a, b, c), a * b * c) + assert capture == """ + my_func(x:int=1, y:float=2, z:float=2) + my_func(x:int=3, y:float=2, z:float=2) + my_func(x:int=4, y:float=3, z:float=2) + my_func(x:int=6, y:float=3, z:float=2) + """ + with capture: + a, b, c = np.array([[1, 2, 3], [4, 5, 6]], order='F')[::, ::2], np.array([[2], [3]]), 2 + assert np.allclose(f(a, b, c), a * b * c) + assert capture == """ + my_func(x:int=1, y:float=2, z:float=2) + my_func(x:int=3, y:float=2, z:float=2) + my_func(x:int=4, y:float=3, z:float=2) + my_func(x:int=6, y:float=3, z:float=2) + """ + + +def test_type_selection(): + assert m.selective_func(np.array([1], dtype=np.int32)) == "Int branch taken." + assert m.selective_func(np.array([1.0], dtype=np.float32)) == "Float branch taken." + assert m.selective_func(np.array([1.0j], dtype=np.complex64)) == "Complex float branch taken." + + +def test_docs(doc): + assert doc(m.vectorized_func) == """ + vectorized_func(arg0: numpy.ndarray[int32], arg1: numpy.ndarray[float32], arg2: numpy.ndarray[float64]) -> object + """ # noqa: E501 line too long + + +def test_trivial_broadcasting(): + trivial, vectorized_is_trivial = m.trivial, m.vectorized_is_trivial + + assert vectorized_is_trivial(1, 2, 3) == trivial.c_trivial + assert vectorized_is_trivial(np.array(1), np.array(2), 3) == trivial.c_trivial + assert vectorized_is_trivial(np.array([1, 3]), np.array([2, 4]), 3) == trivial.c_trivial + assert trivial.c_trivial == vectorized_is_trivial( + np.array([[1, 3, 5], [7, 9, 11]]), np.array([[2, 4, 6], [8, 10, 12]]), 3) + assert vectorized_is_trivial( + np.array([[1, 2, 3], [4, 5, 6]]), np.array([2, 3, 4]), 2) == trivial.non_trivial + assert vectorized_is_trivial( + np.array([[1, 2, 3], [4, 5, 6]]), np.array([[2], [3]]), 2) == trivial.non_trivial + z1 = np.array([[1, 2, 3, 4], [5, 6, 7, 8]], dtype='int32') + z2 = np.array(z1, dtype='float32') + z3 = np.array(z1, dtype='float64') + assert vectorized_is_trivial(z1, z2, z3) == trivial.c_trivial + assert vectorized_is_trivial(1, z2, z3) == trivial.c_trivial + assert vectorized_is_trivial(z1, 1, z3) == trivial.c_trivial + assert vectorized_is_trivial(z1, z2, 1) == trivial.c_trivial + assert vectorized_is_trivial(z1[::2, ::2], 1, 1) == trivial.non_trivial + assert vectorized_is_trivial(1, 1, z1[::2, ::2]) == trivial.c_trivial + assert vectorized_is_trivial(1, 1, z3[::2, ::2]) == trivial.non_trivial + assert vectorized_is_trivial(z1, 1, z3[1::4, 1::4]) == trivial.c_trivial + + y1 = np.array(z1, order='F') + y2 = np.array(y1) + y3 = np.array(y1) + assert vectorized_is_trivial(y1, y2, y3) == trivial.f_trivial + assert vectorized_is_trivial(y1, 1, 1) == trivial.f_trivial + assert vectorized_is_trivial(1, y2, 1) == trivial.f_trivial + assert vectorized_is_trivial(1, 1, y3) == trivial.f_trivial + assert vectorized_is_trivial(y1, z2, 1) == trivial.non_trivial + assert vectorized_is_trivial(z1[1::4, 1::4], y2, 1) == trivial.f_trivial + assert vectorized_is_trivial(y1[1::4, 1::4], z2, 1) == trivial.c_trivial + + assert m.vectorized_func(z1, z2, z3).flags.c_contiguous + assert m.vectorized_func(y1, y2, y3).flags.f_contiguous + assert m.vectorized_func(z1, 1, 1).flags.c_contiguous + assert m.vectorized_func(1, y2, 1).flags.f_contiguous + assert m.vectorized_func(z1[1::4, 1::4], y2, 1).flags.f_contiguous + assert m.vectorized_func(y1[1::4, 1::4], z2, 1).flags.c_contiguous + + +def test_passthrough_arguments(doc): + assert doc(m.vec_passthrough) == ( + "vec_passthrough(" + ", ".join([ + "arg0: float", + "arg1: numpy.ndarray[float64]", + "arg2: numpy.ndarray[float64]", + "arg3: numpy.ndarray[int32]", + "arg4: int", + "arg5: m.numpy_vectorize.NonPODClass", + "arg6: numpy.ndarray[float64]"]) + ") -> object") + + b = np.array([[10, 20, 30]], dtype='float64') + c = np.array([100, 200]) # NOT a vectorized argument + d = np.array([[1000], [2000], [3000]], dtype='int') + g = np.array([[1000000, 2000000, 3000000]], dtype='int') # requires casting + assert np.all( + m.vec_passthrough(1, b, c, d, 10000, m.NonPODClass(100000), g) == + np.array([[1111111, 2111121, 3111131], + [1112111, 2112121, 3112131], + [1113111, 2113121, 3113131]])) + + +def test_method_vectorization(): + o = m.VectorizeTestClass(3) + x = np.array([1, 2], dtype='int') + y = np.array([[10], [20]], dtype='float32') + assert np.all(o.method(x, y) == [[14, 15], [24, 25]]) + + +def test_array_collapse(): + assert not isinstance(m.vectorized_func(1, 2, 3), np.ndarray) + assert not isinstance(m.vectorized_func(np.array(1), 2, 3), np.ndarray) + z = m.vectorized_func([1], 2, 3) + assert isinstance(z, np.ndarray) + assert z.shape == (1, ) + z = m.vectorized_func(1, [[[2]]], 3) + assert isinstance(z, np.ndarray) + assert z.shape == (1, 1, 1) diff --git a/wrap/python/pybind11/tests/test_opaque_types.cpp b/wrap/python/pybind11/tests/test_opaque_types.cpp new file mode 100644 index 000000000..0d20d9a01 --- /dev/null +++ b/wrap/python/pybind11/tests/test_opaque_types.cpp @@ -0,0 +1,67 @@ +/* + tests/test_opaque_types.cpp -- opaque types, passing void pointers + + Copyright (c) 2016 Wenzel Jakob + + All rights reserved. Use of this source code is governed by a + BSD-style license that can be found in the LICENSE file. +*/ + +#include "pybind11_tests.h" +#include +#include + +// IMPORTANT: Disable internal pybind11 translation mechanisms for STL data structures +// +// This also deliberately doesn't use the below StringList type alias to test +// that MAKE_OPAQUE can handle a type containing a `,`. (The `std::allocator` +// bit is just the default `std::vector` allocator). +PYBIND11_MAKE_OPAQUE(std::vector>); + +using StringList = std::vector>; + +TEST_SUBMODULE(opaque_types, m) { + // test_string_list + py::class_(m, "StringList") + .def(py::init<>()) + .def("pop_back", &StringList::pop_back) + /* There are multiple versions of push_back(), etc. Select the right ones. */ + .def("push_back", (void (StringList::*)(const std::string &)) &StringList::push_back) + .def("back", (std::string &(StringList::*)()) &StringList::back) + .def("__len__", [](const StringList &v) { return v.size(); }) + .def("__iter__", [](StringList &v) { + return py::make_iterator(v.begin(), v.end()); + }, py::keep_alive<0, 1>()); + + class ClassWithSTLVecProperty { + public: + StringList stringList; + }; + py::class_(m, "ClassWithSTLVecProperty") + .def(py::init<>()) + .def_readwrite("stringList", &ClassWithSTLVecProperty::stringList); + + m.def("print_opaque_list", [](const StringList &l) { + std::string ret = "Opaque list: ["; + bool first = true; + for (auto entry : l) { + if (!first) + ret += ", "; + ret += entry; + first = false; + } + return ret + "]"; + }); + + // test_pointers + m.def("return_void_ptr", []() { return (void *) 0x1234; }); + m.def("get_void_ptr_value", [](void *ptr) { return reinterpret_cast(ptr); }); + m.def("return_null_str", []() { return (char *) nullptr; }); + m.def("get_null_str_value", [](char *ptr) { return reinterpret_cast(ptr); }); + + m.def("return_unique_ptr", []() -> std::unique_ptr { + StringList *result = new StringList(); + result->push_back("some value"); + return std::unique_ptr(result); + }); +} diff --git a/wrap/python/pybind11/tests/test_opaque_types.py b/wrap/python/pybind11/tests/test_opaque_types.py new file mode 100644 index 000000000..6b3802fdb --- /dev/null +++ b/wrap/python/pybind11/tests/test_opaque_types.py @@ -0,0 +1,46 @@ +import pytest +from pybind11_tests import opaque_types as m +from pybind11_tests import ConstructorStats, UserType + + +def test_string_list(): + lst = m.StringList() + lst.push_back("Element 1") + lst.push_back("Element 2") + assert m.print_opaque_list(lst) == "Opaque list: [Element 1, Element 2]" + assert lst.back() == "Element 2" + + for i, k in enumerate(lst, start=1): + assert k == "Element {}".format(i) + lst.pop_back() + assert m.print_opaque_list(lst) == "Opaque list: [Element 1]" + + cvp = m.ClassWithSTLVecProperty() + assert m.print_opaque_list(cvp.stringList) == "Opaque list: []" + + cvp.stringList = lst + cvp.stringList.push_back("Element 3") + assert m.print_opaque_list(cvp.stringList) == "Opaque list: [Element 1, Element 3]" + + +def test_pointers(msg): + living_before = ConstructorStats.get(UserType).alive() + assert m.get_void_ptr_value(m.return_void_ptr()) == 0x1234 + assert m.get_void_ptr_value(UserType()) # Should also work for other C++ types + assert ConstructorStats.get(UserType).alive() == living_before + + with pytest.raises(TypeError) as excinfo: + m.get_void_ptr_value([1, 2, 3]) # This should not work + assert msg(excinfo.value) == """ + get_void_ptr_value(): incompatible function arguments. The following argument types are supported: + 1. (arg0: capsule) -> int + + Invoked with: [1, 2, 3] + """ # noqa: E501 line too long + + assert m.return_null_str() is None + assert m.get_null_str_value(m.return_null_str()) is not None + + ptr = m.return_unique_ptr() + assert "StringList" in repr(ptr) + assert m.print_opaque_list(ptr) == "Opaque list: [some value]" diff --git a/wrap/python/pybind11/tests/test_operator_overloading.cpp b/wrap/python/pybind11/tests/test_operator_overloading.cpp new file mode 100644 index 000000000..8ca7d8bcf --- /dev/null +++ b/wrap/python/pybind11/tests/test_operator_overloading.cpp @@ -0,0 +1,169 @@ +/* + tests/test_operator_overloading.cpp -- operator overloading + + Copyright (c) 2016 Wenzel Jakob + + All rights reserved. Use of this source code is governed by a + BSD-style license that can be found in the LICENSE file. +*/ + +#include "pybind11_tests.h" +#include "constructor_stats.h" +#include +#include + +class Vector2 { +public: + Vector2(float x, float y) : x(x), y(y) { print_created(this, toString()); } + Vector2(const Vector2 &v) : x(v.x), y(v.y) { print_copy_created(this); } + Vector2(Vector2 &&v) : x(v.x), y(v.y) { print_move_created(this); v.x = v.y = 0; } + Vector2 &operator=(const Vector2 &v) { x = v.x; y = v.y; print_copy_assigned(this); return *this; } + Vector2 &operator=(Vector2 &&v) { x = v.x; y = v.y; v.x = v.y = 0; print_move_assigned(this); return *this; } + ~Vector2() { print_destroyed(this); } + + std::string toString() const { return "[" + std::to_string(x) + ", " + std::to_string(y) + "]"; } + + Vector2 operator+(const Vector2 &v) const { return Vector2(x + v.x, y + v.y); } + Vector2 operator-(const Vector2 &v) const { return Vector2(x - v.x, y - v.y); } + Vector2 operator-(float value) const { return Vector2(x - value, y - value); } + Vector2 operator+(float value) const { return Vector2(x + value, y + value); } + Vector2 operator*(float value) const { return Vector2(x * value, y * value); } + Vector2 operator/(float value) const { return Vector2(x / value, y / value); } + Vector2 operator*(const Vector2 &v) const { return Vector2(x * v.x, y * v.y); } + Vector2 operator/(const Vector2 &v) const { return Vector2(x / v.x, y / v.y); } + Vector2& operator+=(const Vector2 &v) { x += v.x; y += v.y; return *this; } + Vector2& operator-=(const Vector2 &v) { x -= v.x; y -= v.y; return *this; } + Vector2& operator*=(float v) { x *= v; y *= v; return *this; } + Vector2& operator/=(float v) { x /= v; y /= v; return *this; } + Vector2& operator*=(const Vector2 &v) { x *= v.x; y *= v.y; return *this; } + Vector2& operator/=(const Vector2 &v) { x /= v.x; y /= v.y; return *this; } + + friend Vector2 operator+(float f, const Vector2 &v) { return Vector2(f + v.x, f + v.y); } + friend Vector2 operator-(float f, const Vector2 &v) { return Vector2(f - v.x, f - v.y); } + friend Vector2 operator*(float f, const Vector2 &v) { return Vector2(f * v.x, f * v.y); } + friend Vector2 operator/(float f, const Vector2 &v) { return Vector2(f / v.x, f / v.y); } +private: + float x, y; +}; + +class C1 { }; +class C2 { }; + +int operator+(const C1 &, const C1 &) { return 11; } +int operator+(const C2 &, const C2 &) { return 22; } +int operator+(const C2 &, const C1 &) { return 21; } +int operator+(const C1 &, const C2 &) { return 12; } + +namespace std { + template<> + struct hash { + // Not a good hash function, but easy to test + size_t operator()(const Vector2 &) { return 4; } + }; +} + +// MSVC warns about unknown pragmas, and warnings are errors. +#ifndef _MSC_VER + #pragma GCC diagnostic push + // clang 7.0.0 and Apple LLVM 10.0.1 introduce `-Wself-assign-overloaded` to + // `-Wall`, which is used here for overloading (e.g. `py::self += py::self `). + // Here, we suppress the warning using `#pragma diagnostic`. + // Taken from: https://github.com/RobotLocomotion/drake/commit/aaf84b46 + // TODO(eric): This could be resolved using a function / functor (e.g. `py::self()`). + #if (__APPLE__) && (__clang__) + #if (__clang_major__ >= 10) && (__clang_minor__ >= 0) && (__clang_patchlevel__ >= 1) + #pragma GCC diagnostic ignored "-Wself-assign-overloaded" + #endif + #elif (__clang__) + #if (__clang_major__ >= 7) + #pragma GCC diagnostic ignored "-Wself-assign-overloaded" + #endif + #endif +#endif + +TEST_SUBMODULE(operators, m) { + + // test_operator_overloading + py::class_(m, "Vector2") + .def(py::init()) + .def(py::self + py::self) + .def(py::self + float()) + .def(py::self - py::self) + .def(py::self - float()) + .def(py::self * float()) + .def(py::self / float()) + .def(py::self * py::self) + .def(py::self / py::self) + .def(py::self += py::self) + .def(py::self -= py::self) + .def(py::self *= float()) + .def(py::self /= float()) + .def(py::self *= py::self) + .def(py::self /= py::self) + .def(float() + py::self) + .def(float() - py::self) + .def(float() * py::self) + .def(float() / py::self) + .def("__str__", &Vector2::toString) + .def(hash(py::self)) + ; + + m.attr("Vector") = m.attr("Vector2"); + + // test_operators_notimplemented + // #393: need to return NotSupported to ensure correct arithmetic operator behavior + py::class_(m, "C1") + .def(py::init<>()) + .def(py::self + py::self); + + py::class_(m, "C2") + .def(py::init<>()) + .def(py::self + py::self) + .def("__add__", [](const C2& c2, const C1& c1) { return c2 + c1; }) + .def("__radd__", [](const C2& c2, const C1& c1) { return c1 + c2; }); + + // test_nested + // #328: first member in a class can't be used in operators + struct NestABase { int value = -2; }; + py::class_(m, "NestABase") + .def(py::init<>()) + .def_readwrite("value", &NestABase::value); + + struct NestA : NestABase { + int value = 3; + NestA& operator+=(int i) { value += i; return *this; } + }; + py::class_(m, "NestA") + .def(py::init<>()) + .def(py::self += int()) + .def("as_base", [](NestA &a) -> NestABase& { + return (NestABase&) a; + }, py::return_value_policy::reference_internal); + m.def("get_NestA", [](const NestA &a) { return a.value; }); + + struct NestB { + NestA a; + int value = 4; + NestB& operator-=(int i) { value -= i; return *this; } + }; + py::class_(m, "NestB") + .def(py::init<>()) + .def(py::self -= int()) + .def_readwrite("a", &NestB::a); + m.def("get_NestB", [](const NestB &b) { return b.value; }); + + struct NestC { + NestB b; + int value = 5; + NestC& operator*=(int i) { value *= i; return *this; } + }; + py::class_(m, "NestC") + .def(py::init<>()) + .def(py::self *= int()) + .def_readwrite("b", &NestC::b); + m.def("get_NestC", [](const NestC &c) { return c.value; }); +} + +#ifndef _MSC_VER + #pragma GCC diagnostic pop +#endif diff --git a/wrap/python/pybind11/tests/test_operator_overloading.py b/wrap/python/pybind11/tests/test_operator_overloading.py new file mode 100644 index 000000000..86827d2ba --- /dev/null +++ b/wrap/python/pybind11/tests/test_operator_overloading.py @@ -0,0 +1,106 @@ +import pytest +from pybind11_tests import operators as m +from pybind11_tests import ConstructorStats + + +def test_operator_overloading(): + v1 = m.Vector2(1, 2) + v2 = m.Vector(3, -1) + assert str(v1) == "[1.000000, 2.000000]" + assert str(v2) == "[3.000000, -1.000000]" + + assert str(v1 + v2) == "[4.000000, 1.000000]" + assert str(v1 - v2) == "[-2.000000, 3.000000]" + assert str(v1 - 8) == "[-7.000000, -6.000000]" + assert str(v1 + 8) == "[9.000000, 10.000000]" + assert str(v1 * 8) == "[8.000000, 16.000000]" + assert str(v1 / 8) == "[0.125000, 0.250000]" + assert str(8 - v1) == "[7.000000, 6.000000]" + assert str(8 + v1) == "[9.000000, 10.000000]" + assert str(8 * v1) == "[8.000000, 16.000000]" + assert str(8 / v1) == "[8.000000, 4.000000]" + assert str(v1 * v2) == "[3.000000, -2.000000]" + assert str(v2 / v1) == "[3.000000, -0.500000]" + + v1 += 2 * v2 + assert str(v1) == "[7.000000, 0.000000]" + v1 -= v2 + assert str(v1) == "[4.000000, 1.000000]" + v1 *= 2 + assert str(v1) == "[8.000000, 2.000000]" + v1 /= 16 + assert str(v1) == "[0.500000, 0.125000]" + v1 *= v2 + assert str(v1) == "[1.500000, -0.125000]" + v2 /= v1 + assert str(v2) == "[2.000000, 8.000000]" + + assert hash(v1) == 4 + + cstats = ConstructorStats.get(m.Vector2) + assert cstats.alive() == 2 + del v1 + assert cstats.alive() == 1 + del v2 + assert cstats.alive() == 0 + assert cstats.values() == ['[1.000000, 2.000000]', '[3.000000, -1.000000]', + '[4.000000, 1.000000]', '[-2.000000, 3.000000]', + '[-7.000000, -6.000000]', '[9.000000, 10.000000]', + '[8.000000, 16.000000]', '[0.125000, 0.250000]', + '[7.000000, 6.000000]', '[9.000000, 10.000000]', + '[8.000000, 16.000000]', '[8.000000, 4.000000]', + '[3.000000, -2.000000]', '[3.000000, -0.500000]', + '[6.000000, -2.000000]'] + assert cstats.default_constructions == 0 + assert cstats.copy_constructions == 0 + assert cstats.move_constructions >= 10 + assert cstats.copy_assignments == 0 + assert cstats.move_assignments == 0 + + +def test_operators_notimplemented(): + """#393: need to return NotSupported to ensure correct arithmetic operator behavior""" + + c1, c2 = m.C1(), m.C2() + assert c1 + c1 == 11 + assert c2 + c2 == 22 + assert c2 + c1 == 21 + assert c1 + c2 == 12 + + +def test_nested(): + """#328: first member in a class can't be used in operators""" + + a = m.NestA() + b = m.NestB() + c = m.NestC() + + a += 10 + assert m.get_NestA(a) == 13 + b.a += 100 + assert m.get_NestA(b.a) == 103 + c.b.a += 1000 + assert m.get_NestA(c.b.a) == 1003 + b -= 1 + assert m.get_NestB(b) == 3 + c.b -= 3 + assert m.get_NestB(c.b) == 1 + c *= 7 + assert m.get_NestC(c) == 35 + + abase = a.as_base() + assert abase.value == -2 + a.as_base().value += 44 + assert abase.value == 42 + assert c.b.a.as_base().value == -2 + c.b.a.as_base().value += 44 + assert c.b.a.as_base().value == 42 + + del c + pytest.gc_collect() + del a # Shouldn't delete while abase is still alive + pytest.gc_collect() + + assert abase.value == 42 + del abase, b + pytest.gc_collect() diff --git a/wrap/python/pybind11/tests/test_pickling.cpp b/wrap/python/pybind11/tests/test_pickling.cpp new file mode 100644 index 000000000..9dc63bda3 --- /dev/null +++ b/wrap/python/pybind11/tests/test_pickling.cpp @@ -0,0 +1,130 @@ +/* + tests/test_pickling.cpp -- pickle support + + Copyright (c) 2016 Wenzel Jakob + + All rights reserved. Use of this source code is governed by a + BSD-style license that can be found in the LICENSE file. +*/ + +#include "pybind11_tests.h" + +TEST_SUBMODULE(pickling, m) { + // test_roundtrip + class Pickleable { + public: + Pickleable(const std::string &value) : m_value(value) { } + const std::string &value() const { return m_value; } + + void setExtra1(int extra1) { m_extra1 = extra1; } + void setExtra2(int extra2) { m_extra2 = extra2; } + int extra1() const { return m_extra1; } + int extra2() const { return m_extra2; } + private: + std::string m_value; + int m_extra1 = 0; + int m_extra2 = 0; + }; + + class PickleableNew : public Pickleable { + public: + using Pickleable::Pickleable; + }; + + py::class_(m, "Pickleable") + .def(py::init()) + .def("value", &Pickleable::value) + .def("extra1", &Pickleable::extra1) + .def("extra2", &Pickleable::extra2) + .def("setExtra1", &Pickleable::setExtra1) + .def("setExtra2", &Pickleable::setExtra2) + // For details on the methods below, refer to + // http://docs.python.org/3/library/pickle.html#pickling-class-instances + .def("__getstate__", [](const Pickleable &p) { + /* Return a tuple that fully encodes the state of the object */ + return py::make_tuple(p.value(), p.extra1(), p.extra2()); + }) + .def("__setstate__", [](Pickleable &p, py::tuple t) { + if (t.size() != 3) + throw std::runtime_error("Invalid state!"); + /* Invoke the constructor (need to use in-place version) */ + new (&p) Pickleable(t[0].cast()); + + /* Assign any additional state */ + p.setExtra1(t[1].cast()); + p.setExtra2(t[2].cast()); + }); + + py::class_(m, "PickleableNew") + .def(py::init()) + .def(py::pickle( + [](const PickleableNew &p) { + return py::make_tuple(p.value(), p.extra1(), p.extra2()); + }, + [](py::tuple t) { + if (t.size() != 3) + throw std::runtime_error("Invalid state!"); + auto p = PickleableNew(t[0].cast()); + + p.setExtra1(t[1].cast()); + p.setExtra2(t[2].cast()); + return p; + } + )); + +#if !defined(PYPY_VERSION) + // test_roundtrip_with_dict + class PickleableWithDict { + public: + PickleableWithDict(const std::string &value) : value(value) { } + + std::string value; + int extra; + }; + + class PickleableWithDictNew : public PickleableWithDict { + public: + using PickleableWithDict::PickleableWithDict; + }; + + py::class_(m, "PickleableWithDict", py::dynamic_attr()) + .def(py::init()) + .def_readwrite("value", &PickleableWithDict::value) + .def_readwrite("extra", &PickleableWithDict::extra) + .def("__getstate__", [](py::object self) { + /* Also include __dict__ in state */ + return py::make_tuple(self.attr("value"), self.attr("extra"), self.attr("__dict__")); + }) + .def("__setstate__", [](py::object self, py::tuple t) { + if (t.size() != 3) + throw std::runtime_error("Invalid state!"); + /* Cast and construct */ + auto& p = self.cast(); + new (&p) PickleableWithDict(t[0].cast()); + + /* Assign C++ state */ + p.extra = t[1].cast(); + + /* Assign Python state */ + self.attr("__dict__") = t[2]; + }); + + py::class_(m, "PickleableWithDictNew") + .def(py::init()) + .def(py::pickle( + [](py::object self) { + return py::make_tuple(self.attr("value"), self.attr("extra"), self.attr("__dict__")); + }, + [](const py::tuple &t) { + if (t.size() != 3) + throw std::runtime_error("Invalid state!"); + + auto cpp_state = PickleableWithDictNew(t[0].cast()); + cpp_state.extra = t[1].cast(); + + auto py_state = t[2].cast(); + return std::make_pair(cpp_state, py_state); + } + )); +#endif +} diff --git a/wrap/python/pybind11/tests/test_pickling.py b/wrap/python/pybind11/tests/test_pickling.py new file mode 100644 index 000000000..5ae05aaa0 --- /dev/null +++ b/wrap/python/pybind11/tests/test_pickling.py @@ -0,0 +1,42 @@ +import pytest +from pybind11_tests import pickling as m + +try: + import cPickle as pickle # Use cPickle on Python 2.7 +except ImportError: + import pickle + + +@pytest.mark.parametrize("cls_name", ["Pickleable", "PickleableNew"]) +def test_roundtrip(cls_name): + cls = getattr(m, cls_name) + p = cls("test_value") + p.setExtra1(15) + p.setExtra2(48) + + data = pickle.dumps(p, 2) # Must use pickle protocol >= 2 + p2 = pickle.loads(data) + assert p2.value() == p.value() + assert p2.extra1() == p.extra1() + assert p2.extra2() == p.extra2() + + +@pytest.unsupported_on_pypy +@pytest.mark.parametrize("cls_name", ["PickleableWithDict", "PickleableWithDictNew"]) +def test_roundtrip_with_dict(cls_name): + cls = getattr(m, cls_name) + p = cls("test_value") + p.extra = 15 + p.dynamic = "Attribute" + + data = pickle.dumps(p, pickle.HIGHEST_PROTOCOL) + p2 = pickle.loads(data) + assert p2.value == p.value + assert p2.extra == p.extra + assert p2.dynamic == p.dynamic + + +def test_enum_pickle(): + from pybind11_tests import enums as e + data = pickle.dumps(e.EOne, 2) + assert e.EOne == pickle.loads(data) diff --git a/wrap/python/pybind11/tests/test_pytypes.cpp b/wrap/python/pybind11/tests/test_pytypes.cpp new file mode 100644 index 000000000..e6c955ff9 --- /dev/null +++ b/wrap/python/pybind11/tests/test_pytypes.cpp @@ -0,0 +1,296 @@ +/* + tests/test_pytypes.cpp -- Python type casters + + Copyright (c) 2017 Wenzel Jakob + + All rights reserved. Use of this source code is governed by a + BSD-style license that can be found in the LICENSE file. +*/ + +#include "pybind11_tests.h" + + +TEST_SUBMODULE(pytypes, m) { + // test_list + m.def("get_list", []() { + py::list list; + list.append("value"); + py::print("Entry at position 0:", list[0]); + list[0] = py::str("overwritten"); + return list; + }); + m.def("print_list", [](py::list list) { + int index = 0; + for (auto item : list) + py::print("list item {}: {}"_s.format(index++, item)); + }); + + // test_set + m.def("get_set", []() { + py::set set; + set.add(py::str("key1")); + set.add("key2"); + set.add(std::string("key3")); + return set; + }); + m.def("print_set", [](py::set set) { + for (auto item : set) + py::print("key:", item); + }); + + // test_dict + m.def("get_dict", []() { return py::dict("key"_a="value"); }); + m.def("print_dict", [](py::dict dict) { + for (auto item : dict) + py::print("key: {}, value={}"_s.format(item.first, item.second)); + }); + m.def("dict_keyword_constructor", []() { + auto d1 = py::dict("x"_a=1, "y"_a=2); + auto d2 = py::dict("z"_a=3, **d1); + return d2; + }); + + // test_str + m.def("str_from_string", []() { return py::str(std::string("baz")); }); + m.def("str_from_bytes", []() { return py::str(py::bytes("boo", 3)); }); + m.def("str_from_object", [](const py::object& obj) { return py::str(obj); }); + m.def("repr_from_object", [](const py::object& obj) { return py::repr(obj); }); + + m.def("str_format", []() { + auto s1 = "{} + {} = {}"_s.format(1, 2, 3); + auto s2 = "{a} + {b} = {c}"_s.format("a"_a=1, "b"_a=2, "c"_a=3); + return py::make_tuple(s1, s2); + }); + + // test_bytes + m.def("bytes_from_string", []() { return py::bytes(std::string("foo")); }); + m.def("bytes_from_str", []() { return py::bytes(py::str("bar", 3)); }); + + // test_capsule + m.def("return_capsule_with_destructor", []() { + py::print("creating capsule"); + return py::capsule([]() { + py::print("destructing capsule"); + }); + }); + + m.def("return_capsule_with_destructor_2", []() { + py::print("creating capsule"); + return py::capsule((void *) 1234, [](void *ptr) { + py::print("destructing capsule: {}"_s.format((size_t) ptr)); + }); + }); + + m.def("return_capsule_with_name_and_destructor", []() { + auto capsule = py::capsule((void *) 1234, "pointer type description", [](PyObject *ptr) { + if (ptr) { + auto name = PyCapsule_GetName(ptr); + py::print("destructing capsule ({}, '{}')"_s.format( + (size_t) PyCapsule_GetPointer(ptr, name), name + )); + } + }); + void *contents = capsule; + py::print("created capsule ({}, '{}')"_s.format((size_t) contents, capsule.name())); + return capsule; + }); + + // test_accessors + m.def("accessor_api", [](py::object o) { + auto d = py::dict(); + + d["basic_attr"] = o.attr("basic_attr"); + + auto l = py::list(); + for (const auto &item : o.attr("begin_end")) { + l.append(item); + } + d["begin_end"] = l; + + d["operator[object]"] = o.attr("d")["operator[object]"_s]; + d["operator[char *]"] = o.attr("d")["operator[char *]"]; + + d["attr(object)"] = o.attr("sub").attr("attr_obj"); + d["attr(char *)"] = o.attr("sub").attr("attr_char"); + try { + o.attr("sub").attr("missing").ptr(); + } catch (const py::error_already_set &) { + d["missing_attr_ptr"] = "raised"_s; + } + try { + o.attr("missing").attr("doesn't matter"); + } catch (const py::error_already_set &) { + d["missing_attr_chain"] = "raised"_s; + } + + d["is_none"] = o.attr("basic_attr").is_none(); + + d["operator()"] = o.attr("func")(1); + d["operator*"] = o.attr("func")(*o.attr("begin_end")); + + // Test implicit conversion + py::list implicit_list = o.attr("begin_end"); + d["implicit_list"] = implicit_list; + py::dict implicit_dict = o.attr("__dict__"); + d["implicit_dict"] = implicit_dict; + + return d; + }); + + m.def("tuple_accessor", [](py::tuple existing_t) { + try { + existing_t[0] = 1; + } catch (const py::error_already_set &) { + // --> Python system error + // Only new tuples (refcount == 1) are mutable + auto new_t = py::tuple(3); + for (size_t i = 0; i < new_t.size(); ++i) { + new_t[i] = i; + } + return new_t; + } + return py::tuple(); + }); + + m.def("accessor_assignment", []() { + auto l = py::list(1); + l[0] = 0; + + auto d = py::dict(); + d["get"] = l[0]; + auto var = l[0]; + d["deferred_get"] = var; + l[0] = 1; + d["set"] = l[0]; + var = 99; // this assignment should not overwrite l[0] + d["deferred_set"] = l[0]; + d["var"] = var; + + return d; + }); + + // test_constructors + m.def("default_constructors", []() { + return py::dict( + "str"_a=py::str(), + "bool"_a=py::bool_(), + "int"_a=py::int_(), + "float"_a=py::float_(), + "tuple"_a=py::tuple(), + "list"_a=py::list(), + "dict"_a=py::dict(), + "set"_a=py::set() + ); + }); + + m.def("converting_constructors", [](py::dict d) { + return py::dict( + "str"_a=py::str(d["str"]), + "bool"_a=py::bool_(d["bool"]), + "int"_a=py::int_(d["int"]), + "float"_a=py::float_(d["float"]), + "tuple"_a=py::tuple(d["tuple"]), + "list"_a=py::list(d["list"]), + "dict"_a=py::dict(d["dict"]), + "set"_a=py::set(d["set"]), + "memoryview"_a=py::memoryview(d["memoryview"]) + ); + }); + + m.def("cast_functions", [](py::dict d) { + // When converting between Python types, obj.cast() should be the same as T(obj) + return py::dict( + "str"_a=d["str"].cast(), + "bool"_a=d["bool"].cast(), + "int"_a=d["int"].cast(), + "float"_a=d["float"].cast(), + "tuple"_a=d["tuple"].cast(), + "list"_a=d["list"].cast(), + "dict"_a=d["dict"].cast(), + "set"_a=d["set"].cast(), + "memoryview"_a=d["memoryview"].cast() + ); + }); + + m.def("get_implicit_casting", []() { + py::dict d; + d["char*_i1"] = "abc"; + const char *c2 = "abc"; + d["char*_i2"] = c2; + d["char*_e"] = py::cast(c2); + d["char*_p"] = py::str(c2); + + d["int_i1"] = 42; + int i = 42; + d["int_i2"] = i; + i++; + d["int_e"] = py::cast(i); + i++; + d["int_p"] = py::int_(i); + + d["str_i1"] = std::string("str"); + std::string s2("str1"); + d["str_i2"] = s2; + s2[3] = '2'; + d["str_e"] = py::cast(s2); + s2[3] = '3'; + d["str_p"] = py::str(s2); + + py::list l(2); + l[0] = 3; + l[1] = py::cast(6); + l.append(9); + l.append(py::cast(12)); + l.append(py::int_(15)); + + return py::dict( + "d"_a=d, + "l"_a=l + ); + }); + + // test_print + m.def("print_function", []() { + py::print("Hello, World!"); + py::print(1, 2.0, "three", true, std::string("-- multiple args")); + auto args = py::make_tuple("and", "a", "custom", "separator"); + py::print("*args", *args, "sep"_a="-"); + py::print("no new line here", "end"_a=" -- "); + py::print("next print"); + + auto py_stderr = py::module::import("sys").attr("stderr"); + py::print("this goes to stderr", "file"_a=py_stderr); + + py::print("flush", "flush"_a=true); + + py::print("{a} + {b} = {c}"_s.format("a"_a="py::print", "b"_a="str.format", "c"_a="this")); + }); + + m.def("print_failure", []() { py::print(42, UnregisteredType()); }); + + m.def("hash_function", [](py::object obj) { return py::hash(obj); }); + + m.def("test_number_protocol", [](py::object a, py::object b) { + py::list l; + l.append(a.equal(b)); + l.append(a.not_equal(b)); + l.append(a < b); + l.append(a <= b); + l.append(a > b); + l.append(a >= b); + l.append(a + b); + l.append(a - b); + l.append(a * b); + l.append(a / b); + l.append(a | b); + l.append(a & b); + l.append(a ^ b); + l.append(a >> b); + l.append(a << b); + return l; + }); + + m.def("test_list_slicing", [](py::list a) { + return a[py::slice(0, -1, 2)]; + }); +} diff --git a/wrap/python/pybind11/tests/test_pytypes.py b/wrap/python/pybind11/tests/test_pytypes.py new file mode 100644 index 000000000..0116d4ef2 --- /dev/null +++ b/wrap/python/pybind11/tests/test_pytypes.py @@ -0,0 +1,253 @@ +from __future__ import division +import pytest +import sys + +from pybind11_tests import pytypes as m +from pybind11_tests import debug_enabled + + +def test_list(capture, doc): + with capture: + lst = m.get_list() + assert lst == ["overwritten"] + + lst.append("value2") + m.print_list(lst) + assert capture.unordered == """ + Entry at position 0: value + list item 0: overwritten + list item 1: value2 + """ + + assert doc(m.get_list) == "get_list() -> list" + assert doc(m.print_list) == "print_list(arg0: list) -> None" + + +def test_set(capture, doc): + s = m.get_set() + assert s == {"key1", "key2", "key3"} + + with capture: + s.add("key4") + m.print_set(s) + assert capture.unordered == """ + key: key1 + key: key2 + key: key3 + key: key4 + """ + + assert doc(m.get_list) == "get_list() -> list" + assert doc(m.print_list) == "print_list(arg0: list) -> None" + + +def test_dict(capture, doc): + d = m.get_dict() + assert d == {"key": "value"} + + with capture: + d["key2"] = "value2" + m.print_dict(d) + assert capture.unordered == """ + key: key, value=value + key: key2, value=value2 + """ + + assert doc(m.get_dict) == "get_dict() -> dict" + assert doc(m.print_dict) == "print_dict(arg0: dict) -> None" + + assert m.dict_keyword_constructor() == {"x": 1, "y": 2, "z": 3} + + +def test_str(doc): + assert m.str_from_string().encode().decode() == "baz" + assert m.str_from_bytes().encode().decode() == "boo" + + assert doc(m.str_from_bytes) == "str_from_bytes() -> str" + + class A(object): + def __str__(self): + return "this is a str" + + def __repr__(self): + return "this is a repr" + + assert m.str_from_object(A()) == "this is a str" + assert m.repr_from_object(A()) == "this is a repr" + + s1, s2 = m.str_format() + assert s1 == "1 + 2 = 3" + assert s1 == s2 + + +def test_bytes(doc): + assert m.bytes_from_string().decode() == "foo" + assert m.bytes_from_str().decode() == "bar" + + assert doc(m.bytes_from_str) == "bytes_from_str() -> {}".format( + "bytes" if sys.version_info[0] == 3 else "str" + ) + + +def test_capsule(capture): + pytest.gc_collect() + with capture: + a = m.return_capsule_with_destructor() + del a + pytest.gc_collect() + assert capture.unordered == """ + creating capsule + destructing capsule + """ + + with capture: + a = m.return_capsule_with_destructor_2() + del a + pytest.gc_collect() + assert capture.unordered == """ + creating capsule + destructing capsule: 1234 + """ + + with capture: + a = m.return_capsule_with_name_and_destructor() + del a + pytest.gc_collect() + assert capture.unordered == """ + created capsule (1234, 'pointer type description') + destructing capsule (1234, 'pointer type description') + """ + + +def test_accessors(): + class SubTestObject: + attr_obj = 1 + attr_char = 2 + + class TestObject: + basic_attr = 1 + begin_end = [1, 2, 3] + d = {"operator[object]": 1, "operator[char *]": 2} + sub = SubTestObject() + + def func(self, x, *args): + return self.basic_attr + x + sum(args) + + d = m.accessor_api(TestObject()) + assert d["basic_attr"] == 1 + assert d["begin_end"] == [1, 2, 3] + assert d["operator[object]"] == 1 + assert d["operator[char *]"] == 2 + assert d["attr(object)"] == 1 + assert d["attr(char *)"] == 2 + assert d["missing_attr_ptr"] == "raised" + assert d["missing_attr_chain"] == "raised" + assert d["is_none"] is False + assert d["operator()"] == 2 + assert d["operator*"] == 7 + assert d["implicit_list"] == [1, 2, 3] + assert all(x in TestObject.__dict__ for x in d["implicit_dict"]) + + assert m.tuple_accessor(tuple()) == (0, 1, 2) + + d = m.accessor_assignment() + assert d["get"] == 0 + assert d["deferred_get"] == 0 + assert d["set"] == 1 + assert d["deferred_set"] == 1 + assert d["var"] == 99 + + +def test_constructors(): + """C++ default and converting constructors are equivalent to type calls in Python""" + types = [str, bool, int, float, tuple, list, dict, set] + expected = {t.__name__: t() for t in types} + assert m.default_constructors() == expected + + data = { + str: 42, + bool: "Not empty", + int: "42", + float: "+1e3", + tuple: range(3), + list: range(3), + dict: [("two", 2), ("one", 1), ("three", 3)], + set: [4, 4, 5, 6, 6, 6], + memoryview: b'abc' + } + inputs = {k.__name__: v for k, v in data.items()} + expected = {k.__name__: k(v) for k, v in data.items()} + + assert m.converting_constructors(inputs) == expected + assert m.cast_functions(inputs) == expected + + # Converting constructors and cast functions should just reference rather + # than copy when no conversion is needed: + noconv1 = m.converting_constructors(expected) + for k in noconv1: + assert noconv1[k] is expected[k] + + noconv2 = m.cast_functions(expected) + for k in noconv2: + assert noconv2[k] is expected[k] + + +def test_implicit_casting(): + """Tests implicit casting when assigning or appending to dicts and lists.""" + z = m.get_implicit_casting() + assert z['d'] == { + 'char*_i1': 'abc', 'char*_i2': 'abc', 'char*_e': 'abc', 'char*_p': 'abc', + 'str_i1': 'str', 'str_i2': 'str1', 'str_e': 'str2', 'str_p': 'str3', + 'int_i1': 42, 'int_i2': 42, 'int_e': 43, 'int_p': 44 + } + assert z['l'] == [3, 6, 9, 12, 15] + + +def test_print(capture): + with capture: + m.print_function() + assert capture == """ + Hello, World! + 1 2.0 three True -- multiple args + *args-and-a-custom-separator + no new line here -- next print + flush + py::print + str.format = this + """ + assert capture.stderr == "this goes to stderr" + + with pytest.raises(RuntimeError) as excinfo: + m.print_failure() + assert str(excinfo.value) == "make_tuple(): unable to convert " + ( + "argument of type 'UnregisteredType' to Python object" + if debug_enabled else + "arguments to Python object (compile in debug mode for details)" + ) + + +def test_hash(): + class Hashable(object): + def __init__(self, value): + self.value = value + + def __hash__(self): + return self.value + + class Unhashable(object): + __hash__ = None + + assert m.hash_function(Hashable(42)) == 42 + with pytest.raises(TypeError): + m.hash_function(Unhashable()) + + +def test_number_protocol(): + for a, b in [(1, 1), (3, 5)]: + li = [a == b, a != b, a < b, a <= b, a > b, a >= b, a + b, + a - b, a * b, a / b, a | b, a & b, a ^ b, a >> b, a << b] + assert m.test_number_protocol(a, b) == li + + +def test_list_slicing(): + li = list(range(100)) + assert li[::2] == m.test_list_slicing(li) diff --git a/wrap/python/pybind11/tests/test_sequences_and_iterators.cpp b/wrap/python/pybind11/tests/test_sequences_and_iterators.cpp new file mode 100644 index 000000000..87ccf99d6 --- /dev/null +++ b/wrap/python/pybind11/tests/test_sequences_and_iterators.cpp @@ -0,0 +1,353 @@ +/* + tests/test_sequences_and_iterators.cpp -- supporting Pythons' sequence protocol, iterators, + etc. + + Copyright (c) 2016 Wenzel Jakob + + All rights reserved. Use of this source code is governed by a + BSD-style license that can be found in the LICENSE file. +*/ + +#include "pybind11_tests.h" +#include "constructor_stats.h" +#include +#include + +template +class NonZeroIterator { + const T* ptr_; +public: + NonZeroIterator(const T* ptr) : ptr_(ptr) {} + const T& operator*() const { return *ptr_; } + NonZeroIterator& operator++() { ++ptr_; return *this; } +}; + +class NonZeroSentinel {}; + +template +bool operator==(const NonZeroIterator>& it, const NonZeroSentinel&) { + return !(*it).first || !(*it).second; +} + +template +py::list test_random_access_iterator(PythonType x) { + if (x.size() < 5) + throw py::value_error("Please provide at least 5 elements for testing."); + + auto checks = py::list(); + auto assert_equal = [&checks](py::handle a, py::handle b) { + auto result = PyObject_RichCompareBool(a.ptr(), b.ptr(), Py_EQ); + if (result == -1) { throw py::error_already_set(); } + checks.append(result != 0); + }; + + auto it = x.begin(); + assert_equal(x[0], *it); + assert_equal(x[0], it[0]); + assert_equal(x[1], it[1]); + + assert_equal(x[1], *(++it)); + assert_equal(x[1], *(it++)); + assert_equal(x[2], *it); + assert_equal(x[3], *(it += 1)); + assert_equal(x[2], *(--it)); + assert_equal(x[2], *(it--)); + assert_equal(x[1], *it); + assert_equal(x[0], *(it -= 1)); + + assert_equal(it->attr("real"), x[0].attr("real")); + assert_equal((it + 1)->attr("real"), x[1].attr("real")); + + assert_equal(x[1], *(it + 1)); + assert_equal(x[1], *(1 + it)); + it += 3; + assert_equal(x[1], *(it - 2)); + + checks.append(static_cast(x.end() - x.begin()) == x.size()); + checks.append((x.begin() + static_cast(x.size())) == x.end()); + checks.append(x.begin() < x.end()); + + return checks; +} + +TEST_SUBMODULE(sequences_and_iterators, m) { + // test_sliceable + class Sliceable{ + public: + Sliceable(int n): size(n) {} + int start,stop,step; + int size; + }; + py::class_(m,"Sliceable") + .def(py::init()) + .def("__getitem__",[](const Sliceable &s, py::slice slice) { + ssize_t start, stop, step, slicelength; + if (!slice.compute(s.size, &start, &stop, &step, &slicelength)) + throw py::error_already_set(); + int istart = static_cast(start); + int istop = static_cast(stop); + int istep = static_cast(step); + return std::make_tuple(istart,istop,istep); + }) + ; + + // test_sequence + class Sequence { + public: + Sequence(size_t size) : m_size(size) { + print_created(this, "of size", m_size); + m_data = new float[size]; + memset(m_data, 0, sizeof(float) * size); + } + Sequence(const std::vector &value) : m_size(value.size()) { + print_created(this, "of size", m_size, "from std::vector"); + m_data = new float[m_size]; + memcpy(m_data, &value[0], sizeof(float) * m_size); + } + Sequence(const Sequence &s) : m_size(s.m_size) { + print_copy_created(this); + m_data = new float[m_size]; + memcpy(m_data, s.m_data, sizeof(float)*m_size); + } + Sequence(Sequence &&s) : m_size(s.m_size), m_data(s.m_data) { + print_move_created(this); + s.m_size = 0; + s.m_data = nullptr; + } + + ~Sequence() { print_destroyed(this); delete[] m_data; } + + Sequence &operator=(const Sequence &s) { + if (&s != this) { + delete[] m_data; + m_size = s.m_size; + m_data = new float[m_size]; + memcpy(m_data, s.m_data, sizeof(float)*m_size); + } + print_copy_assigned(this); + return *this; + } + + Sequence &operator=(Sequence &&s) { + if (&s != this) { + delete[] m_data; + m_size = s.m_size; + m_data = s.m_data; + s.m_size = 0; + s.m_data = nullptr; + } + print_move_assigned(this); + return *this; + } + + bool operator==(const Sequence &s) const { + if (m_size != s.size()) return false; + for (size_t i = 0; i < m_size; ++i) + if (m_data[i] != s[i]) + return false; + return true; + } + bool operator!=(const Sequence &s) const { return !operator==(s); } + + float operator[](size_t index) const { return m_data[index]; } + float &operator[](size_t index) { return m_data[index]; } + + bool contains(float v) const { + for (size_t i = 0; i < m_size; ++i) + if (v == m_data[i]) + return true; + return false; + } + + Sequence reversed() const { + Sequence result(m_size); + for (size_t i = 0; i < m_size; ++i) + result[m_size - i - 1] = m_data[i]; + return result; + } + + size_t size() const { return m_size; } + + const float *begin() const { return m_data; } + const float *end() const { return m_data+m_size; } + + private: + size_t m_size; + float *m_data; + }; + py::class_(m, "Sequence") + .def(py::init()) + .def(py::init&>()) + /// Bare bones interface + .def("__getitem__", [](const Sequence &s, size_t i) { + if (i >= s.size()) throw py::index_error(); + return s[i]; + }) + .def("__setitem__", [](Sequence &s, size_t i, float v) { + if (i >= s.size()) throw py::index_error(); + s[i] = v; + }) + .def("__len__", &Sequence::size) + /// Optional sequence protocol operations + .def("__iter__", [](const Sequence &s) { return py::make_iterator(s.begin(), s.end()); }, + py::keep_alive<0, 1>() /* Essential: keep object alive while iterator exists */) + .def("__contains__", [](const Sequence &s, float v) { return s.contains(v); }) + .def("__reversed__", [](const Sequence &s) -> Sequence { return s.reversed(); }) + /// Slicing protocol (optional) + .def("__getitem__", [](const Sequence &s, py::slice slice) -> Sequence* { + size_t start, stop, step, slicelength; + if (!slice.compute(s.size(), &start, &stop, &step, &slicelength)) + throw py::error_already_set(); + Sequence *seq = new Sequence(slicelength); + for (size_t i = 0; i < slicelength; ++i) { + (*seq)[i] = s[start]; start += step; + } + return seq; + }) + .def("__setitem__", [](Sequence &s, py::slice slice, const Sequence &value) { + size_t start, stop, step, slicelength; + if (!slice.compute(s.size(), &start, &stop, &step, &slicelength)) + throw py::error_already_set(); + if (slicelength != value.size()) + throw std::runtime_error("Left and right hand size of slice assignment have different sizes!"); + for (size_t i = 0; i < slicelength; ++i) { + s[start] = value[i]; start += step; + } + }) + /// Comparisons + .def(py::self == py::self) + .def(py::self != py::self) + // Could also define py::self + py::self for concatenation, etc. + ; + + // test_map_iterator + // Interface of a map-like object that isn't (directly) an unordered_map, but provides some basic + // map-like functionality. + class StringMap { + public: + StringMap() = default; + StringMap(std::unordered_map init) + : map(std::move(init)) {} + + void set(std::string key, std::string val) { map[key] = val; } + std::string get(std::string key) const { return map.at(key); } + size_t size() const { return map.size(); } + private: + std::unordered_map map; + public: + decltype(map.cbegin()) begin() const { return map.cbegin(); } + decltype(map.cend()) end() const { return map.cend(); } + }; + py::class_(m, "StringMap") + .def(py::init<>()) + .def(py::init>()) + .def("__getitem__", [](const StringMap &map, std::string key) { + try { return map.get(key); } + catch (const std::out_of_range&) { + throw py::key_error("key '" + key + "' does not exist"); + } + }) + .def("__setitem__", &StringMap::set) + .def("__len__", &StringMap::size) + .def("__iter__", [](const StringMap &map) { return py::make_key_iterator(map.begin(), map.end()); }, + py::keep_alive<0, 1>()) + .def("items", [](const StringMap &map) { return py::make_iterator(map.begin(), map.end()); }, + py::keep_alive<0, 1>()) + ; + + // test_generalized_iterators + class IntPairs { + public: + IntPairs(std::vector> data) : data_(std::move(data)) {} + const std::pair* begin() const { return data_.data(); } + private: + std::vector> data_; + }; + py::class_(m, "IntPairs") + .def(py::init>>()) + .def("nonzero", [](const IntPairs& s) { + return py::make_iterator(NonZeroIterator>(s.begin()), NonZeroSentinel()); + }, py::keep_alive<0, 1>()) + .def("nonzero_keys", [](const IntPairs& s) { + return py::make_key_iterator(NonZeroIterator>(s.begin()), NonZeroSentinel()); + }, py::keep_alive<0, 1>()) + ; + + +#if 0 + // Obsolete: special data structure for exposing custom iterator types to python + // kept here for illustrative purposes because there might be some use cases which + // are not covered by the much simpler py::make_iterator + + struct PySequenceIterator { + PySequenceIterator(const Sequence &seq, py::object ref) : seq(seq), ref(ref) { } + + float next() { + if (index == seq.size()) + throw py::stop_iteration(); + return seq[index++]; + } + + const Sequence &seq; + py::object ref; // keep a reference + size_t index = 0; + }; + + py::class_(seq, "Iterator") + .def("__iter__", [](PySequenceIterator &it) -> PySequenceIterator& { return it; }) + .def("__next__", &PySequenceIterator::next); + + On the actual Sequence object, the iterator would be constructed as follows: + .def("__iter__", [](py::object s) { return PySequenceIterator(s.cast(), s); }) +#endif + + // test_python_iterator_in_cpp + m.def("object_to_list", [](py::object o) { + auto l = py::list(); + for (auto item : o) { + l.append(item); + } + return l; + }); + + m.def("iterator_to_list", [](py::iterator it) { + auto l = py::list(); + while (it != py::iterator::sentinel()) { + l.append(*it); + ++it; + } + return l; + }); + + // Make sure that py::iterator works with std algorithms + m.def("count_none", [](py::object o) { + return std::count_if(o.begin(), o.end(), [](py::handle h) { return h.is_none(); }); + }); + + m.def("find_none", [](py::object o) { + auto it = std::find_if(o.begin(), o.end(), [](py::handle h) { return h.is_none(); }); + return it->is_none(); + }); + + m.def("count_nonzeros", [](py::dict d) { + return std::count_if(d.begin(), d.end(), [](std::pair p) { + return p.second.cast() != 0; + }); + }); + + m.def("tuple_iterator", &test_random_access_iterator); + m.def("list_iterator", &test_random_access_iterator); + m.def("sequence_iterator", &test_random_access_iterator); + + // test_iterator_passthrough + // #181: iterator passthrough did not compile + m.def("iterator_passthrough", [](py::iterator s) -> py::iterator { + return py::make_iterator(std::begin(s), std::end(s)); + }); + + // test_iterator_rvp + // #388: Can't make iterators via make_iterator() with different r/v policies + static std::vector list = { 1, 2, 3 }; + m.def("make_iterator_1", []() { return py::make_iterator(list); }); + m.def("make_iterator_2", []() { return py::make_iterator(list); }); +} diff --git a/wrap/python/pybind11/tests/test_sequences_and_iterators.py b/wrap/python/pybind11/tests/test_sequences_and_iterators.py new file mode 100644 index 000000000..6bd160640 --- /dev/null +++ b/wrap/python/pybind11/tests/test_sequences_and_iterators.py @@ -0,0 +1,171 @@ +import pytest +from pybind11_tests import sequences_and_iterators as m +from pybind11_tests import ConstructorStats + + +def isclose(a, b, rel_tol=1e-05, abs_tol=0.0): + """Like math.isclose() from Python 3.5""" + return abs(a - b) <= max(rel_tol * max(abs(a), abs(b)), abs_tol) + + +def allclose(a_list, b_list, rel_tol=1e-05, abs_tol=0.0): + return all(isclose(a, b, rel_tol=rel_tol, abs_tol=abs_tol) for a, b in zip(a_list, b_list)) + + +def test_generalized_iterators(): + assert list(m.IntPairs([(1, 2), (3, 4), (0, 5)]).nonzero()) == [(1, 2), (3, 4)] + assert list(m.IntPairs([(1, 2), (2, 0), (0, 3), (4, 5)]).nonzero()) == [(1, 2)] + assert list(m.IntPairs([(0, 3), (1, 2), (3, 4)]).nonzero()) == [] + + assert list(m.IntPairs([(1, 2), (3, 4), (0, 5)]).nonzero_keys()) == [1, 3] + assert list(m.IntPairs([(1, 2), (2, 0), (0, 3), (4, 5)]).nonzero_keys()) == [1] + assert list(m.IntPairs([(0, 3), (1, 2), (3, 4)]).nonzero_keys()) == [] + + # __next__ must continue to raise StopIteration + it = m.IntPairs([(0, 0)]).nonzero() + for _ in range(3): + with pytest.raises(StopIteration): + next(it) + + it = m.IntPairs([(0, 0)]).nonzero_keys() + for _ in range(3): + with pytest.raises(StopIteration): + next(it) + + +def test_sliceable(): + sliceable = m.Sliceable(100) + assert sliceable[::] == (0, 100, 1) + assert sliceable[10::] == (10, 100, 1) + assert sliceable[:10:] == (0, 10, 1) + assert sliceable[::10] == (0, 100, 10) + assert sliceable[-10::] == (90, 100, 1) + assert sliceable[:-10:] == (0, 90, 1) + assert sliceable[::-10] == (99, -1, -10) + assert sliceable[50:60:1] == (50, 60, 1) + assert sliceable[50:60:-1] == (50, 60, -1) + + +def test_sequence(): + cstats = ConstructorStats.get(m.Sequence) + + s = m.Sequence(5) + assert cstats.values() == ['of size', '5'] + + assert "Sequence" in repr(s) + assert len(s) == 5 + assert s[0] == 0 and s[3] == 0 + assert 12.34 not in s + s[0], s[3] = 12.34, 56.78 + assert 12.34 in s + assert isclose(s[0], 12.34) and isclose(s[3], 56.78) + + rev = reversed(s) + assert cstats.values() == ['of size', '5'] + + rev2 = s[::-1] + assert cstats.values() == ['of size', '5'] + + it = iter(m.Sequence(0)) + for _ in range(3): # __next__ must continue to raise StopIteration + with pytest.raises(StopIteration): + next(it) + assert cstats.values() == ['of size', '0'] + + expected = [0, 56.78, 0, 0, 12.34] + assert allclose(rev, expected) + assert allclose(rev2, expected) + assert rev == rev2 + + rev[0::2] = m.Sequence([2.0, 2.0, 2.0]) + assert cstats.values() == ['of size', '3', 'from std::vector'] + + assert allclose(rev, [2, 56.78, 2, 0, 2]) + + assert cstats.alive() == 4 + del it + assert cstats.alive() == 3 + del s + assert cstats.alive() == 2 + del rev + assert cstats.alive() == 1 + del rev2 + assert cstats.alive() == 0 + + assert cstats.values() == [] + assert cstats.default_constructions == 0 + assert cstats.copy_constructions == 0 + assert cstats.move_constructions >= 1 + assert cstats.copy_assignments == 0 + assert cstats.move_assignments == 0 + + +def test_map_iterator(): + sm = m.StringMap({'hi': 'bye', 'black': 'white'}) + assert sm['hi'] == 'bye' + assert len(sm) == 2 + assert sm['black'] == 'white' + + with pytest.raises(KeyError): + assert sm['orange'] + sm['orange'] = 'banana' + assert sm['orange'] == 'banana' + + expected = {'hi': 'bye', 'black': 'white', 'orange': 'banana'} + for k in sm: + assert sm[k] == expected[k] + for k, v in sm.items(): + assert v == expected[k] + + it = iter(m.StringMap({})) + for _ in range(3): # __next__ must continue to raise StopIteration + with pytest.raises(StopIteration): + next(it) + + +def test_python_iterator_in_cpp(): + t = (1, 2, 3) + assert m.object_to_list(t) == [1, 2, 3] + assert m.object_to_list(iter(t)) == [1, 2, 3] + assert m.iterator_to_list(iter(t)) == [1, 2, 3] + + with pytest.raises(TypeError) as excinfo: + m.object_to_list(1) + assert "object is not iterable" in str(excinfo.value) + + with pytest.raises(TypeError) as excinfo: + m.iterator_to_list(1) + assert "incompatible function arguments" in str(excinfo.value) + + def bad_next_call(): + raise RuntimeError("py::iterator::advance() should propagate errors") + + with pytest.raises(RuntimeError) as excinfo: + m.iterator_to_list(iter(bad_next_call, None)) + assert str(excinfo.value) == "py::iterator::advance() should propagate errors" + + lst = [1, None, 0, None] + assert m.count_none(lst) == 2 + assert m.find_none(lst) is True + assert m.count_nonzeros({"a": 0, "b": 1, "c": 2}) == 2 + + r = range(5) + assert all(m.tuple_iterator(tuple(r))) + assert all(m.list_iterator(list(r))) + assert all(m.sequence_iterator(r)) + + +def test_iterator_passthrough(): + """#181: iterator passthrough did not compile""" + from pybind11_tests.sequences_and_iterators import iterator_passthrough + + assert list(iterator_passthrough(iter([3, 5, 7, 9, 11, 13, 15]))) == [3, 5, 7, 9, 11, 13, 15] + + +def test_iterator_rvp(): + """#388: Can't make iterators via make_iterator() with different r/v policies """ + import pybind11_tests.sequences_and_iterators as m + + assert list(m.make_iterator_1()) == [1, 2, 3] + assert list(m.make_iterator_2()) == [1, 2, 3] + assert not isinstance(m.make_iterator_1(), type(m.make_iterator_2())) diff --git a/wrap/python/pybind11/tests/test_smart_ptr.cpp b/wrap/python/pybind11/tests/test_smart_ptr.cpp new file mode 100644 index 000000000..87c9be8c2 --- /dev/null +++ b/wrap/python/pybind11/tests/test_smart_ptr.cpp @@ -0,0 +1,366 @@ +/* + tests/test_smart_ptr.cpp -- binding classes with custom reference counting, + implicit conversions between types + + Copyright (c) 2016 Wenzel Jakob + + All rights reserved. Use of this source code is governed by a + BSD-style license that can be found in the LICENSE file. +*/ + +#if defined(_MSC_VER) && _MSC_VER < 1910 +# pragma warning(disable: 4702) // unreachable code in system header +#endif + +#include "pybind11_tests.h" +#include "object.h" + +// Make pybind aware of the ref-counted wrapper type (s): + +// ref is a wrapper for 'Object' which uses intrusive reference counting +// It is always possible to construct a ref from an Object* pointer without +// possible inconsistencies, hence the 'true' argument at the end. +PYBIND11_DECLARE_HOLDER_TYPE(T, ref, true); +// Make pybind11 aware of the non-standard getter member function +namespace pybind11 { namespace detail { + template + struct holder_helper> { + static const T *get(const ref &p) { return p.get_ptr(); } + }; +}} + +// The following is not required anymore for std::shared_ptr, but it should compile without error: +PYBIND11_DECLARE_HOLDER_TYPE(T, std::shared_ptr); + +// This is just a wrapper around unique_ptr, but with extra fields to deliberately bloat up the +// holder size to trigger the non-simple-layout internal instance layout for single inheritance with +// large holder type: +template class huge_unique_ptr { + std::unique_ptr ptr; + uint64_t padding[10]; +public: + huge_unique_ptr(T *p) : ptr(p) {}; + T *get() { return ptr.get(); } +}; +PYBIND11_DECLARE_HOLDER_TYPE(T, huge_unique_ptr); + +// Simple custom holder that works like unique_ptr +template +class custom_unique_ptr { + std::unique_ptr impl; +public: + custom_unique_ptr(T* p) : impl(p) { } + T* get() const { return impl.get(); } + T* release_ptr() { return impl.release(); } +}; +PYBIND11_DECLARE_HOLDER_TYPE(T, custom_unique_ptr); + +// Simple custom holder that works like shared_ptr and has operator& overload +// To obtain address of an instance of this holder pybind should use std::addressof +// Attempt to get address via operator& may leads to segmentation fault +template +class shared_ptr_with_addressof_operator { + std::shared_ptr impl; +public: + shared_ptr_with_addressof_operator( ) = default; + shared_ptr_with_addressof_operator(T* p) : impl(p) { } + T* get() const { return impl.get(); } + T** operator&() { throw std::logic_error("Call of overloaded operator& is not expected"); } +}; +PYBIND11_DECLARE_HOLDER_TYPE(T, shared_ptr_with_addressof_operator); + +// Simple custom holder that works like unique_ptr and has operator& overload +// To obtain address of an instance of this holder pybind should use std::addressof +// Attempt to get address via operator& may leads to segmentation fault +template +class unique_ptr_with_addressof_operator { + std::unique_ptr impl; +public: + unique_ptr_with_addressof_operator() = default; + unique_ptr_with_addressof_operator(T* p) : impl(p) { } + T* get() const { return impl.get(); } + T* release_ptr() { return impl.release(); } + T** operator&() { throw std::logic_error("Call of overloaded operator& is not expected"); } +}; +PYBIND11_DECLARE_HOLDER_TYPE(T, unique_ptr_with_addressof_operator); + + +TEST_SUBMODULE(smart_ptr, m) { + + // test_smart_ptr + + // Object implementation in `object.h` + py::class_> obj(m, "Object"); + obj.def("getRefCount", &Object::getRefCount); + + // Custom object with builtin reference counting (see 'object.h' for the implementation) + class MyObject1 : public Object { + public: + MyObject1(int value) : value(value) { print_created(this, toString()); } + std::string toString() const { return "MyObject1[" + std::to_string(value) + "]"; } + protected: + virtual ~MyObject1() { print_destroyed(this); } + private: + int value; + }; + py::class_>(m, "MyObject1", obj) + .def(py::init()); + py::implicitly_convertible(); + + m.def("make_object_1", []() -> Object * { return new MyObject1(1); }); + m.def("make_object_2", []() -> ref { return new MyObject1(2); }); + m.def("make_myobject1_1", []() -> MyObject1 * { return new MyObject1(4); }); + m.def("make_myobject1_2", []() -> ref { return new MyObject1(5); }); + m.def("print_object_1", [](const Object *obj) { py::print(obj->toString()); }); + m.def("print_object_2", [](ref obj) { py::print(obj->toString()); }); + m.def("print_object_3", [](const ref &obj) { py::print(obj->toString()); }); + m.def("print_object_4", [](const ref *obj) { py::print((*obj)->toString()); }); + m.def("print_myobject1_1", [](const MyObject1 *obj) { py::print(obj->toString()); }); + m.def("print_myobject1_2", [](ref obj) { py::print(obj->toString()); }); + m.def("print_myobject1_3", [](const ref &obj) { py::print(obj->toString()); }); + m.def("print_myobject1_4", [](const ref *obj) { py::print((*obj)->toString()); }); + + // Expose constructor stats for the ref type + m.def("cstats_ref", &ConstructorStats::get); + + + // Object managed by a std::shared_ptr<> + class MyObject2 { + public: + MyObject2(const MyObject2 &) = default; + MyObject2(int value) : value(value) { print_created(this, toString()); } + std::string toString() const { return "MyObject2[" + std::to_string(value) + "]"; } + virtual ~MyObject2() { print_destroyed(this); } + private: + int value; + }; + py::class_>(m, "MyObject2") + .def(py::init()); + m.def("make_myobject2_1", []() { return new MyObject2(6); }); + m.def("make_myobject2_2", []() { return std::make_shared(7); }); + m.def("print_myobject2_1", [](const MyObject2 *obj) { py::print(obj->toString()); }); + m.def("print_myobject2_2", [](std::shared_ptr obj) { py::print(obj->toString()); }); + m.def("print_myobject2_3", [](const std::shared_ptr &obj) { py::print(obj->toString()); }); + m.def("print_myobject2_4", [](const std::shared_ptr *obj) { py::print((*obj)->toString()); }); + + // Object managed by a std::shared_ptr<>, additionally derives from std::enable_shared_from_this<> + class MyObject3 : public std::enable_shared_from_this { + public: + MyObject3(const MyObject3 &) = default; + MyObject3(int value) : value(value) { print_created(this, toString()); } + std::string toString() const { return "MyObject3[" + std::to_string(value) + "]"; } + virtual ~MyObject3() { print_destroyed(this); } + private: + int value; + }; + py::class_>(m, "MyObject3") + .def(py::init()); + m.def("make_myobject3_1", []() { return new MyObject3(8); }); + m.def("make_myobject3_2", []() { return std::make_shared(9); }); + m.def("print_myobject3_1", [](const MyObject3 *obj) { py::print(obj->toString()); }); + m.def("print_myobject3_2", [](std::shared_ptr obj) { py::print(obj->toString()); }); + m.def("print_myobject3_3", [](const std::shared_ptr &obj) { py::print(obj->toString()); }); + m.def("print_myobject3_4", [](const std::shared_ptr *obj) { py::print((*obj)->toString()); }); + + // test_smart_ptr_refcounting + m.def("test_object1_refcounting", []() { + ref o = new MyObject1(0); + bool good = o->getRefCount() == 1; + py::object o2 = py::cast(o, py::return_value_policy::reference); + // always request (partial) ownership for objects with intrusive + // reference counting even when using the 'reference' RVP + good &= o->getRefCount() == 2; + return good; + }); + + // test_unique_nodelete + // Object with a private destructor + class MyObject4 { + public: + MyObject4(int value) : value{value} { print_created(this); } + int value; + private: + ~MyObject4() { print_destroyed(this); } + }; + py::class_>(m, "MyObject4") + .def(py::init()) + .def_readwrite("value", &MyObject4::value); + + // test_unique_deleter + // Object with std::unique_ptr where D is not matching the base class + // Object with a protected destructor + class MyObject4a { + public: + MyObject4a(int i) { + value = i; + print_created(this); + }; + int value; + protected: + virtual ~MyObject4a() { print_destroyed(this); } + }; + py::class_>(m, "MyObject4a") + .def(py::init()) + .def_readwrite("value", &MyObject4a::value); + + // Object derived but with public destructor and no Deleter in default holder + class MyObject4b : public MyObject4a { + public: + MyObject4b(int i) : MyObject4a(i) { print_created(this); } + ~MyObject4b() { print_destroyed(this); } + }; + py::class_(m, "MyObject4b") + .def(py::init()); + + // test_large_holder + class MyObject5 { // managed by huge_unique_ptr + public: + MyObject5(int value) : value{value} { print_created(this); } + ~MyObject5() { print_destroyed(this); } + int value; + }; + py::class_>(m, "MyObject5") + .def(py::init()) + .def_readwrite("value", &MyObject5::value); + + // test_shared_ptr_and_references + struct SharedPtrRef { + struct A { + A() { print_created(this); } + A(const A &) { print_copy_created(this); } + A(A &&) { print_move_created(this); } + ~A() { print_destroyed(this); } + }; + + A value = {}; + std::shared_ptr shared = std::make_shared(); + }; + using A = SharedPtrRef::A; + py::class_>(m, "A"); + py::class_(m, "SharedPtrRef") + .def(py::init<>()) + .def_readonly("ref", &SharedPtrRef::value) + .def_property_readonly("copy", [](const SharedPtrRef &s) { return s.value; }, + py::return_value_policy::copy) + .def_readonly("holder_ref", &SharedPtrRef::shared) + .def_property_readonly("holder_copy", [](const SharedPtrRef &s) { return s.shared; }, + py::return_value_policy::copy) + .def("set_ref", [](SharedPtrRef &, const A &) { return true; }) + .def("set_holder", [](SharedPtrRef &, std::shared_ptr) { return true; }); + + // test_shared_ptr_from_this_and_references + struct SharedFromThisRef { + struct B : std::enable_shared_from_this { + B() { print_created(this); } + B(const B &) : std::enable_shared_from_this() { print_copy_created(this); } + B(B &&) : std::enable_shared_from_this() { print_move_created(this); } + ~B() { print_destroyed(this); } + }; + + B value = {}; + std::shared_ptr shared = std::make_shared(); + }; + using B = SharedFromThisRef::B; + py::class_>(m, "B"); + py::class_(m, "SharedFromThisRef") + .def(py::init<>()) + .def_readonly("bad_wp", &SharedFromThisRef::value) + .def_property_readonly("ref", [](const SharedFromThisRef &s) -> const B & { return *s.shared; }) + .def_property_readonly("copy", [](const SharedFromThisRef &s) { return s.value; }, + py::return_value_policy::copy) + .def_readonly("holder_ref", &SharedFromThisRef::shared) + .def_property_readonly("holder_copy", [](const SharedFromThisRef &s) { return s.shared; }, + py::return_value_policy::copy) + .def("set_ref", [](SharedFromThisRef &, const B &) { return true; }) + .def("set_holder", [](SharedFromThisRef &, std::shared_ptr) { return true; }); + + // Issue #865: shared_from_this doesn't work with virtual inheritance + struct SharedFromThisVBase : std::enable_shared_from_this { + SharedFromThisVBase() = default; + SharedFromThisVBase(const SharedFromThisVBase &) = default; + virtual ~SharedFromThisVBase() = default; + }; + struct SharedFromThisVirt : virtual SharedFromThisVBase {}; + static std::shared_ptr sft(new SharedFromThisVirt()); + py::class_>(m, "SharedFromThisVirt") + .def_static("get", []() { return sft.get(); }); + + // test_move_only_holder + struct C { + C() { print_created(this); } + ~C() { print_destroyed(this); } + }; + py::class_>(m, "TypeWithMoveOnlyHolder") + .def_static("make", []() { return custom_unique_ptr(new C); }); + + // test_holder_with_addressof_operator + struct TypeForHolderWithAddressOf { + TypeForHolderWithAddressOf() { print_created(this); } + TypeForHolderWithAddressOf(const TypeForHolderWithAddressOf &) { print_copy_created(this); } + TypeForHolderWithAddressOf(TypeForHolderWithAddressOf &&) { print_move_created(this); } + ~TypeForHolderWithAddressOf() { print_destroyed(this); } + std::string toString() const { + return "TypeForHolderWithAddressOf[" + std::to_string(value) + "]"; + } + int value = 42; + }; + using HolderWithAddressOf = shared_ptr_with_addressof_operator; + py::class_(m, "TypeForHolderWithAddressOf") + .def_static("make", []() { return HolderWithAddressOf(new TypeForHolderWithAddressOf); }) + .def("get", [](const HolderWithAddressOf &self) { return self.get(); }) + .def("print_object_1", [](const TypeForHolderWithAddressOf *obj) { py::print(obj->toString()); }) + .def("print_object_2", [](HolderWithAddressOf obj) { py::print(obj.get()->toString()); }) + .def("print_object_3", [](const HolderWithAddressOf &obj) { py::print(obj.get()->toString()); }) + .def("print_object_4", [](const HolderWithAddressOf *obj) { py::print((*obj).get()->toString()); }); + + // test_move_only_holder_with_addressof_operator + struct TypeForMoveOnlyHolderWithAddressOf { + TypeForMoveOnlyHolderWithAddressOf(int value) : value{value} { print_created(this); } + ~TypeForMoveOnlyHolderWithAddressOf() { print_destroyed(this); } + std::string toString() const { + return "MoveOnlyHolderWithAddressOf[" + std::to_string(value) + "]"; + } + int value; + }; + using MoveOnlyHolderWithAddressOf = unique_ptr_with_addressof_operator; + py::class_(m, "TypeForMoveOnlyHolderWithAddressOf") + .def_static("make", []() { return MoveOnlyHolderWithAddressOf(new TypeForMoveOnlyHolderWithAddressOf(0)); }) + .def_readwrite("value", &TypeForMoveOnlyHolderWithAddressOf::value) + .def("print_object", [](const TypeForMoveOnlyHolderWithAddressOf *obj) { py::print(obj->toString()); }); + + // test_smart_ptr_from_default + struct HeldByDefaultHolder { }; + py::class_(m, "HeldByDefaultHolder") + .def(py::init<>()) + .def_static("load_shared_ptr", [](std::shared_ptr) {}); + + // test_shared_ptr_gc + // #187: issue involving std::shared_ptr<> return value policy & garbage collection + struct ElementBase { + virtual ~ElementBase() { } /* Force creation of virtual table */ + }; + py::class_>(m, "ElementBase"); + + struct ElementA : ElementBase { + ElementA(int v) : v(v) { } + int value() { return v; } + int v; + }; + py::class_>(m, "ElementA") + .def(py::init()) + .def("value", &ElementA::value); + + struct ElementList { + void add(std::shared_ptr e) { l.push_back(e); } + std::vector> l; + }; + py::class_>(m, "ElementList") + .def(py::init<>()) + .def("add", &ElementList::add) + .def("get", [](ElementList &el) { + py::list list; + for (auto &e : el.l) + list.append(py::cast(e)); + return list; + }); +} diff --git a/wrap/python/pybind11/tests/test_smart_ptr.py b/wrap/python/pybind11/tests/test_smart_ptr.py new file mode 100644 index 000000000..0a3bb58ee --- /dev/null +++ b/wrap/python/pybind11/tests/test_smart_ptr.py @@ -0,0 +1,285 @@ +import pytest +from pybind11_tests import smart_ptr as m +from pybind11_tests import ConstructorStats + + +def test_smart_ptr(capture): + # Object1 + for i, o in enumerate([m.make_object_1(), m.make_object_2(), m.MyObject1(3)], start=1): + assert o.getRefCount() == 1 + with capture: + m.print_object_1(o) + m.print_object_2(o) + m.print_object_3(o) + m.print_object_4(o) + assert capture == "MyObject1[{i}]\n".format(i=i) * 4 + + for i, o in enumerate([m.make_myobject1_1(), m.make_myobject1_2(), m.MyObject1(6), 7], + start=4): + print(o) + with capture: + if not isinstance(o, int): + m.print_object_1(o) + m.print_object_2(o) + m.print_object_3(o) + m.print_object_4(o) + m.print_myobject1_1(o) + m.print_myobject1_2(o) + m.print_myobject1_3(o) + m.print_myobject1_4(o) + assert capture == "MyObject1[{i}]\n".format(i=i) * (4 if isinstance(o, int) else 8) + + cstats = ConstructorStats.get(m.MyObject1) + assert cstats.alive() == 0 + expected_values = ['MyObject1[{}]'.format(i) for i in range(1, 7)] + ['MyObject1[7]'] * 4 + assert cstats.values() == expected_values + assert cstats.default_constructions == 0 + assert cstats.copy_constructions == 0 + # assert cstats.move_constructions >= 0 # Doesn't invoke any + assert cstats.copy_assignments == 0 + assert cstats.move_assignments == 0 + + # Object2 + for i, o in zip([8, 6, 7], [m.MyObject2(8), m.make_myobject2_1(), m.make_myobject2_2()]): + print(o) + with capture: + m.print_myobject2_1(o) + m.print_myobject2_2(o) + m.print_myobject2_3(o) + m.print_myobject2_4(o) + assert capture == "MyObject2[{i}]\n".format(i=i) * 4 + + cstats = ConstructorStats.get(m.MyObject2) + assert cstats.alive() == 1 + o = None + assert cstats.alive() == 0 + assert cstats.values() == ['MyObject2[8]', 'MyObject2[6]', 'MyObject2[7]'] + assert cstats.default_constructions == 0 + assert cstats.copy_constructions == 0 + # assert cstats.move_constructions >= 0 # Doesn't invoke any + assert cstats.copy_assignments == 0 + assert cstats.move_assignments == 0 + + # Object3 + for i, o in zip([9, 8, 9], [m.MyObject3(9), m.make_myobject3_1(), m.make_myobject3_2()]): + print(o) + with capture: + m.print_myobject3_1(o) + m.print_myobject3_2(o) + m.print_myobject3_3(o) + m.print_myobject3_4(o) + assert capture == "MyObject3[{i}]\n".format(i=i) * 4 + + cstats = ConstructorStats.get(m.MyObject3) + assert cstats.alive() == 1 + o = None + assert cstats.alive() == 0 + assert cstats.values() == ['MyObject3[9]', 'MyObject3[8]', 'MyObject3[9]'] + assert cstats.default_constructions == 0 + assert cstats.copy_constructions == 0 + # assert cstats.move_constructions >= 0 # Doesn't invoke any + assert cstats.copy_assignments == 0 + assert cstats.move_assignments == 0 + + # Object + cstats = ConstructorStats.get(m.Object) + assert cstats.alive() == 0 + assert cstats.values() == [] + assert cstats.default_constructions == 10 + assert cstats.copy_constructions == 0 + # assert cstats.move_constructions >= 0 # Doesn't invoke any + assert cstats.copy_assignments == 0 + assert cstats.move_assignments == 0 + + # ref<> + cstats = m.cstats_ref() + assert cstats.alive() == 0 + assert cstats.values() == ['from pointer'] * 10 + assert cstats.default_constructions == 30 + assert cstats.copy_constructions == 12 + # assert cstats.move_constructions >= 0 # Doesn't invoke any + assert cstats.copy_assignments == 30 + assert cstats.move_assignments == 0 + + +def test_smart_ptr_refcounting(): + assert m.test_object1_refcounting() + + +def test_unique_nodelete(): + o = m.MyObject4(23) + assert o.value == 23 + cstats = ConstructorStats.get(m.MyObject4) + assert cstats.alive() == 1 + del o + assert cstats.alive() == 1 # Leak, but that's intentional + + +def test_unique_nodelete4a(): + o = m.MyObject4a(23) + assert o.value == 23 + cstats = ConstructorStats.get(m.MyObject4a) + assert cstats.alive() == 1 + del o + assert cstats.alive() == 1 # Leak, but that's intentional + + +def test_unique_deleter(): + o = m.MyObject4b(23) + assert o.value == 23 + cstats4a = ConstructorStats.get(m.MyObject4a) + assert cstats4a.alive() == 2 # Two because of previous test + cstats4b = ConstructorStats.get(m.MyObject4b) + assert cstats4b.alive() == 1 + del o + assert cstats4a.alive() == 1 # Should now only be one leftover from previous test + assert cstats4b.alive() == 0 # Should be deleted + + +def test_large_holder(): + o = m.MyObject5(5) + assert o.value == 5 + cstats = ConstructorStats.get(m.MyObject5) + assert cstats.alive() == 1 + del o + assert cstats.alive() == 0 + + +def test_shared_ptr_and_references(): + s = m.SharedPtrRef() + stats = ConstructorStats.get(m.A) + assert stats.alive() == 2 + + ref = s.ref # init_holder_helper(holder_ptr=false, owned=false) + assert stats.alive() == 2 + assert s.set_ref(ref) + with pytest.raises(RuntimeError) as excinfo: + assert s.set_holder(ref) + assert "Unable to cast from non-held to held instance" in str(excinfo.value) + + copy = s.copy # init_holder_helper(holder_ptr=false, owned=true) + assert stats.alive() == 3 + assert s.set_ref(copy) + assert s.set_holder(copy) + + holder_ref = s.holder_ref # init_holder_helper(holder_ptr=true, owned=false) + assert stats.alive() == 3 + assert s.set_ref(holder_ref) + assert s.set_holder(holder_ref) + + holder_copy = s.holder_copy # init_holder_helper(holder_ptr=true, owned=true) + assert stats.alive() == 3 + assert s.set_ref(holder_copy) + assert s.set_holder(holder_copy) + + del ref, copy, holder_ref, holder_copy, s + assert stats.alive() == 0 + + +def test_shared_ptr_from_this_and_references(): + s = m.SharedFromThisRef() + stats = ConstructorStats.get(m.B) + assert stats.alive() == 2 + + ref = s.ref # init_holder_helper(holder_ptr=false, owned=false, bad_wp=false) + assert stats.alive() == 2 + assert s.set_ref(ref) + assert s.set_holder(ref) # std::enable_shared_from_this can create a holder from a reference + + bad_wp = s.bad_wp # init_holder_helper(holder_ptr=false, owned=false, bad_wp=true) + assert stats.alive() == 2 + assert s.set_ref(bad_wp) + with pytest.raises(RuntimeError) as excinfo: + assert s.set_holder(bad_wp) + assert "Unable to cast from non-held to held instance" in str(excinfo.value) + + copy = s.copy # init_holder_helper(holder_ptr=false, owned=true, bad_wp=false) + assert stats.alive() == 3 + assert s.set_ref(copy) + assert s.set_holder(copy) + + holder_ref = s.holder_ref # init_holder_helper(holder_ptr=true, owned=false, bad_wp=false) + assert stats.alive() == 3 + assert s.set_ref(holder_ref) + assert s.set_holder(holder_ref) + + holder_copy = s.holder_copy # init_holder_helper(holder_ptr=true, owned=true, bad_wp=false) + assert stats.alive() == 3 + assert s.set_ref(holder_copy) + assert s.set_holder(holder_copy) + + del ref, bad_wp, copy, holder_ref, holder_copy, s + assert stats.alive() == 0 + + z = m.SharedFromThisVirt.get() + y = m.SharedFromThisVirt.get() + assert y is z + + +def test_move_only_holder(): + a = m.TypeWithMoveOnlyHolder.make() + stats = ConstructorStats.get(m.TypeWithMoveOnlyHolder) + assert stats.alive() == 1 + del a + assert stats.alive() == 0 + + +def test_holder_with_addressof_operator(): + # this test must not throw exception from c++ + a = m.TypeForHolderWithAddressOf.make() + a.print_object_1() + a.print_object_2() + a.print_object_3() + a.print_object_4() + + stats = ConstructorStats.get(m.TypeForHolderWithAddressOf) + assert stats.alive() == 1 + + np = m.TypeForHolderWithAddressOf.make() + assert stats.alive() == 2 + del a + assert stats.alive() == 1 + del np + assert stats.alive() == 0 + + b = m.TypeForHolderWithAddressOf.make() + c = b + assert b.get() is c.get() + assert stats.alive() == 1 + + del b + assert stats.alive() == 1 + + del c + assert stats.alive() == 0 + + +def test_move_only_holder_with_addressof_operator(): + a = m.TypeForMoveOnlyHolderWithAddressOf.make() + a.print_object() + + stats = ConstructorStats.get(m.TypeForMoveOnlyHolderWithAddressOf) + assert stats.alive() == 1 + + a.value = 42 + assert a.value == 42 + + del a + assert stats.alive() == 0 + + +def test_smart_ptr_from_default(): + instance = m.HeldByDefaultHolder() + with pytest.raises(RuntimeError) as excinfo: + m.HeldByDefaultHolder.load_shared_ptr(instance) + assert "Unable to load a custom holder type from a default-holder instance" in str(excinfo) + + +def test_shared_ptr_gc(): + """#187: issue involving std::shared_ptr<> return value policy & garbage collection""" + el = m.ElementList() + for i in range(10): + el.add(m.ElementA(i)) + pytest.gc_collect() + for i, v in enumerate(el.get()): + assert i == v.value() diff --git a/wrap/python/pybind11/tests/test_stl.cpp b/wrap/python/pybind11/tests/test_stl.cpp new file mode 100644 index 000000000..207c9fb2b --- /dev/null +++ b/wrap/python/pybind11/tests/test_stl.cpp @@ -0,0 +1,284 @@ +/* + tests/test_stl.cpp -- STL type casters + + Copyright (c) 2017 Wenzel Jakob + + All rights reserved. Use of this source code is governed by a + BSD-style license that can be found in the LICENSE file. +*/ + +#include "pybind11_tests.h" +#include "constructor_stats.h" +#include + +#include +#include + +// Test with `std::variant` in C++17 mode, or with `boost::variant` in C++11/14 +#if PYBIND11_HAS_VARIANT +using std::variant; +#elif defined(PYBIND11_TEST_BOOST) && (!defined(_MSC_VER) || _MSC_VER >= 1910) +# include +# define PYBIND11_HAS_VARIANT 1 +using boost::variant; + +namespace pybind11 { namespace detail { +template +struct type_caster> : variant_caster> {}; + +template <> +struct visit_helper { + template + static auto call(Args &&...args) -> decltype(boost::apply_visitor(args...)) { + return boost::apply_visitor(args...); + } +}; +}} // namespace pybind11::detail +#endif + +PYBIND11_MAKE_OPAQUE(std::vector>); + +/// Issue #528: templated constructor +struct TplCtorClass { + template TplCtorClass(const T &) { } + bool operator==(const TplCtorClass &) const { return true; } +}; + +namespace std { + template <> + struct hash { size_t operator()(const TplCtorClass &) const { return 0; } }; +} + + +TEST_SUBMODULE(stl, m) { + // test_vector + m.def("cast_vector", []() { return std::vector{1}; }); + m.def("load_vector", [](const std::vector &v) { return v.at(0) == 1 && v.at(1) == 2; }); + // `std::vector` is special because it returns proxy objects instead of references + m.def("cast_bool_vector", []() { return std::vector{true, false}; }); + m.def("load_bool_vector", [](const std::vector &v) { + return v.at(0) == true && v.at(1) == false; + }); + // Unnumbered regression (caused by #936): pointers to stl containers aren't castable + static std::vector lvv{2}; + m.def("cast_ptr_vector", []() { return &lvv; }); + + // test_deque + m.def("cast_deque", []() { return std::deque{1}; }); + m.def("load_deque", [](const std::deque &v) { return v.at(0) == 1 && v.at(1) == 2; }); + + // test_array + m.def("cast_array", []() { return std::array {{1 , 2}}; }); + m.def("load_array", [](const std::array &a) { return a[0] == 1 && a[1] == 2; }); + + // test_valarray + m.def("cast_valarray", []() { return std::valarray{1, 4, 9}; }); + m.def("load_valarray", [](const std::valarray& v) { + return v.size() == 3 && v[0] == 1 && v[1] == 4 && v[2] == 9; + }); + + // test_map + m.def("cast_map", []() { return std::map{{"key", "value"}}; }); + m.def("load_map", [](const std::map &map) { + return map.at("key") == "value" && map.at("key2") == "value2"; + }); + + // test_set + m.def("cast_set", []() { return std::set{"key1", "key2"}; }); + m.def("load_set", [](const std::set &set) { + return set.count("key1") && set.count("key2") && set.count("key3"); + }); + + // test_recursive_casting + m.def("cast_rv_vector", []() { return std::vector{2}; }); + m.def("cast_rv_array", []() { return std::array(); }); + // NB: map and set keys are `const`, so while we technically do move them (as `const Type &&`), + // casters don't typically do anything with that, which means they fall to the `const Type &` + // caster. + m.def("cast_rv_map", []() { return std::unordered_map{{"a", RValueCaster{}}}; }); + m.def("cast_rv_nested", []() { + std::vector>, 2>> v; + v.emplace_back(); // add an array + v.back()[0].emplace_back(); // add a map to the array + v.back()[0].back().emplace("b", RValueCaster{}); + v.back()[0].back().emplace("c", RValueCaster{}); + v.back()[1].emplace_back(); // add a map to the array + v.back()[1].back().emplace("a", RValueCaster{}); + return v; + }); + static std::array lva; + static std::unordered_map lvm{{"a", RValueCaster{}}, {"b", RValueCaster{}}}; + static std::unordered_map>>> lvn; + lvn["a"].emplace_back(); // add a list + lvn["a"].back().emplace_back(); // add an array + lvn["a"].emplace_back(); // another list + lvn["a"].back().emplace_back(); // add an array + lvn["b"].emplace_back(); // add a list + lvn["b"].back().emplace_back(); // add an array + lvn["b"].back().emplace_back(); // add another array + m.def("cast_lv_vector", []() -> const decltype(lvv) & { return lvv; }); + m.def("cast_lv_array", []() -> const decltype(lva) & { return lva; }); + m.def("cast_lv_map", []() -> const decltype(lvm) & { return lvm; }); + m.def("cast_lv_nested", []() -> const decltype(lvn) & { return lvn; }); + // #853: + m.def("cast_unique_ptr_vector", []() { + std::vector> v; + v.emplace_back(new UserType{7}); + v.emplace_back(new UserType{42}); + return v; + }); + + // test_move_out_container + struct MoveOutContainer { + struct Value { int value; }; + std::list move_list() const { return {{0}, {1}, {2}}; } + }; + py::class_(m, "MoveOutContainerValue") + .def_readonly("value", &MoveOutContainer::Value::value); + py::class_(m, "MoveOutContainer") + .def(py::init<>()) + .def_property_readonly("move_list", &MoveOutContainer::move_list); + + // Class that can be move- and copy-constructed, but not assigned + struct NoAssign { + int value; + + explicit NoAssign(int value = 0) : value(value) { } + NoAssign(const NoAssign &) = default; + NoAssign(NoAssign &&) = default; + + NoAssign &operator=(const NoAssign &) = delete; + NoAssign &operator=(NoAssign &&) = delete; + }; + py::class_(m, "NoAssign", "Class with no C++ assignment operators") + .def(py::init<>()) + .def(py::init()); + +#ifdef PYBIND11_HAS_OPTIONAL + // test_optional + m.attr("has_optional") = true; + + using opt_int = std::optional; + using opt_no_assign = std::optional; + m.def("double_or_zero", [](const opt_int& x) -> int { + return x.value_or(0) * 2; + }); + m.def("half_or_none", [](int x) -> opt_int { + return x ? opt_int(x / 2) : opt_int(); + }); + m.def("test_nullopt", [](opt_int x) { + return x.value_or(42); + }, py::arg_v("x", std::nullopt, "None")); + m.def("test_no_assign", [](const opt_no_assign &x) { + return x ? x->value : 42; + }, py::arg_v("x", std::nullopt, "None")); + + m.def("nodefer_none_optional", [](std::optional) { return true; }); + m.def("nodefer_none_optional", [](py::none) { return false; }); +#endif + +#ifdef PYBIND11_HAS_EXP_OPTIONAL + // test_exp_optional + m.attr("has_exp_optional") = true; + + using exp_opt_int = std::experimental::optional; + using exp_opt_no_assign = std::experimental::optional; + m.def("double_or_zero_exp", [](const exp_opt_int& x) -> int { + return x.value_or(0) * 2; + }); + m.def("half_or_none_exp", [](int x) -> exp_opt_int { + return x ? exp_opt_int(x / 2) : exp_opt_int(); + }); + m.def("test_nullopt_exp", [](exp_opt_int x) { + return x.value_or(42); + }, py::arg_v("x", std::experimental::nullopt, "None")); + m.def("test_no_assign_exp", [](const exp_opt_no_assign &x) { + return x ? x->value : 42; + }, py::arg_v("x", std::experimental::nullopt, "None")); +#endif + +#ifdef PYBIND11_HAS_VARIANT + static_assert(std::is_same::value, + "visitor::result_type is required by boost::variant in C++11 mode"); + + struct visitor { + using result_type = const char *; + + result_type operator()(int) { return "int"; } + result_type operator()(std::string) { return "std::string"; } + result_type operator()(double) { return "double"; } + result_type operator()(std::nullptr_t) { return "std::nullptr_t"; } + }; + + // test_variant + m.def("load_variant", [](variant v) { + return py::detail::visit_helper::call(visitor(), v); + }); + m.def("load_variant_2pass", [](variant v) { + return py::detail::visit_helper::call(visitor(), v); + }); + m.def("cast_variant", []() { + using V = variant; + return py::make_tuple(V(5), V("Hello")); + }); +#endif + + // #528: templated constructor + // (no python tests: the test here is that this compiles) + m.def("tpl_ctor_vector", [](std::vector &) {}); + m.def("tpl_ctor_map", [](std::unordered_map &) {}); + m.def("tpl_ctor_set", [](std::unordered_set &) {}); +#if defined(PYBIND11_HAS_OPTIONAL) + m.def("tpl_constr_optional", [](std::optional &) {}); +#elif defined(PYBIND11_HAS_EXP_OPTIONAL) + m.def("tpl_constr_optional", [](std::experimental::optional &) {}); +#endif + + // test_vec_of_reference_wrapper + // #171: Can't return STL structures containing reference wrapper + m.def("return_vec_of_reference_wrapper", [](std::reference_wrapper p4) { + static UserType p1{1}, p2{2}, p3{3}; + return std::vector> { + std::ref(p1), std::ref(p2), std::ref(p3), p4 + }; + }); + + // test_stl_pass_by_pointer + m.def("stl_pass_by_pointer", [](std::vector* v) { return *v; }, "v"_a=nullptr); + + // #1258: pybind11/stl.h converts string to vector + m.def("func_with_string_or_vector_string_arg_overload", [](std::vector) { return 1; }); + m.def("func_with_string_or_vector_string_arg_overload", [](std::list) { return 2; }); + m.def("func_with_string_or_vector_string_arg_overload", [](std::string) { return 3; }); + + class Placeholder { + public: + Placeholder() { print_created(this); } + Placeholder(const Placeholder &) = delete; + ~Placeholder() { print_destroyed(this); } + }; + py::class_(m, "Placeholder"); + + /// test_stl_vector_ownership + m.def("test_stl_ownership", + []() { + std::vector result; + result.push_back(new Placeholder()); + return result; + }, + py::return_value_policy::take_ownership); + + m.def("array_cast_sequence", [](std::array x) { return x; }); + + /// test_issue_1561 + struct Issue1561Inner { std::string data; }; + struct Issue1561Outer { std::vector list; }; + + py::class_(m, "Issue1561Inner") + .def(py::init()) + .def_readwrite("data", &Issue1561Inner::data); + + py::class_(m, "Issue1561Outer") + .def(py::init<>()) + .def_readwrite("list", &Issue1561Outer::list); +} diff --git a/wrap/python/pybind11/tests/test_stl.py b/wrap/python/pybind11/tests/test_stl.py new file mode 100644 index 000000000..2335cb9fd --- /dev/null +++ b/wrap/python/pybind11/tests/test_stl.py @@ -0,0 +1,241 @@ +import pytest + +from pybind11_tests import stl as m +from pybind11_tests import UserType +from pybind11_tests import ConstructorStats + + +def test_vector(doc): + """std::vector <-> list""" + lst = m.cast_vector() + assert lst == [1] + lst.append(2) + assert m.load_vector(lst) + assert m.load_vector(tuple(lst)) + + assert m.cast_bool_vector() == [True, False] + assert m.load_bool_vector([True, False]) + + assert doc(m.cast_vector) == "cast_vector() -> List[int]" + assert doc(m.load_vector) == "load_vector(arg0: List[int]) -> bool" + + # Test regression caused by 936: pointers to stl containers weren't castable + assert m.cast_ptr_vector() == ["lvalue", "lvalue"] + + +def test_deque(doc): + """std::deque <-> list""" + lst = m.cast_deque() + assert lst == [1] + lst.append(2) + assert m.load_deque(lst) + assert m.load_deque(tuple(lst)) + + +def test_array(doc): + """std::array <-> list""" + lst = m.cast_array() + assert lst == [1, 2] + assert m.load_array(lst) + + assert doc(m.cast_array) == "cast_array() -> List[int[2]]" + assert doc(m.load_array) == "load_array(arg0: List[int[2]]) -> bool" + + +def test_valarray(doc): + """std::valarray <-> list""" + lst = m.cast_valarray() + assert lst == [1, 4, 9] + assert m.load_valarray(lst) + + assert doc(m.cast_valarray) == "cast_valarray() -> List[int]" + assert doc(m.load_valarray) == "load_valarray(arg0: List[int]) -> bool" + + +def test_map(doc): + """std::map <-> dict""" + d = m.cast_map() + assert d == {"key": "value"} + assert "key" in d + d["key2"] = "value2" + assert "key2" in d + assert m.load_map(d) + + assert doc(m.cast_map) == "cast_map() -> Dict[str, str]" + assert doc(m.load_map) == "load_map(arg0: Dict[str, str]) -> bool" + + +def test_set(doc): + """std::set <-> set""" + s = m.cast_set() + assert s == {"key1", "key2"} + s.add("key3") + assert m.load_set(s) + + assert doc(m.cast_set) == "cast_set() -> Set[str]" + assert doc(m.load_set) == "load_set(arg0: Set[str]) -> bool" + + +def test_recursive_casting(): + """Tests that stl casters preserve lvalue/rvalue context for container values""" + assert m.cast_rv_vector() == ["rvalue", "rvalue"] + assert m.cast_lv_vector() == ["lvalue", "lvalue"] + assert m.cast_rv_array() == ["rvalue", "rvalue", "rvalue"] + assert m.cast_lv_array() == ["lvalue", "lvalue"] + assert m.cast_rv_map() == {"a": "rvalue"} + assert m.cast_lv_map() == {"a": "lvalue", "b": "lvalue"} + assert m.cast_rv_nested() == [[[{"b": "rvalue", "c": "rvalue"}], [{"a": "rvalue"}]]] + assert m.cast_lv_nested() == { + "a": [[["lvalue", "lvalue"]], [["lvalue", "lvalue"]]], + "b": [[["lvalue", "lvalue"], ["lvalue", "lvalue"]]] + } + + # Issue #853 test case: + z = m.cast_unique_ptr_vector() + assert z[0].value == 7 and z[1].value == 42 + + +def test_move_out_container(): + """Properties use the `reference_internal` policy by default. If the underlying function + returns an rvalue, the policy is automatically changed to `move` to avoid referencing + a temporary. In case the return value is a container of user-defined types, the policy + also needs to be applied to the elements, not just the container.""" + c = m.MoveOutContainer() + moved_out_list = c.move_list + assert [x.value for x in moved_out_list] == [0, 1, 2] + + +@pytest.mark.skipif(not hasattr(m, "has_optional"), reason='no ') +def test_optional(): + assert m.double_or_zero(None) == 0 + assert m.double_or_zero(42) == 84 + pytest.raises(TypeError, m.double_or_zero, 'foo') + + assert m.half_or_none(0) is None + assert m.half_or_none(42) == 21 + pytest.raises(TypeError, m.half_or_none, 'foo') + + assert m.test_nullopt() == 42 + assert m.test_nullopt(None) == 42 + assert m.test_nullopt(42) == 42 + assert m.test_nullopt(43) == 43 + + assert m.test_no_assign() == 42 + assert m.test_no_assign(None) == 42 + assert m.test_no_assign(m.NoAssign(43)) == 43 + pytest.raises(TypeError, m.test_no_assign, 43) + + assert m.nodefer_none_optional(None) + + +@pytest.mark.skipif(not hasattr(m, "has_exp_optional"), reason='no ') +def test_exp_optional(): + assert m.double_or_zero_exp(None) == 0 + assert m.double_or_zero_exp(42) == 84 + pytest.raises(TypeError, m.double_or_zero_exp, 'foo') + + assert m.half_or_none_exp(0) is None + assert m.half_or_none_exp(42) == 21 + pytest.raises(TypeError, m.half_or_none_exp, 'foo') + + assert m.test_nullopt_exp() == 42 + assert m.test_nullopt_exp(None) == 42 + assert m.test_nullopt_exp(42) == 42 + assert m.test_nullopt_exp(43) == 43 + + assert m.test_no_assign_exp() == 42 + assert m.test_no_assign_exp(None) == 42 + assert m.test_no_assign_exp(m.NoAssign(43)) == 43 + pytest.raises(TypeError, m.test_no_assign_exp, 43) + + +@pytest.mark.skipif(not hasattr(m, "load_variant"), reason='no ') +def test_variant(doc): + assert m.load_variant(1) == "int" + assert m.load_variant("1") == "std::string" + assert m.load_variant(1.0) == "double" + assert m.load_variant(None) == "std::nullptr_t" + + assert m.load_variant_2pass(1) == "int" + assert m.load_variant_2pass(1.0) == "double" + + assert m.cast_variant() == (5, "Hello") + + assert doc(m.load_variant) == "load_variant(arg0: Union[int, str, float, None]) -> str" + + +def test_vec_of_reference_wrapper(): + """#171: Can't return reference wrappers (or STL structures containing them)""" + assert str(m.return_vec_of_reference_wrapper(UserType(4))) == \ + "[UserType(1), UserType(2), UserType(3), UserType(4)]" + + +def test_stl_pass_by_pointer(msg): + """Passing nullptr or None to an STL container pointer is not expected to work""" + with pytest.raises(TypeError) as excinfo: + m.stl_pass_by_pointer() # default value is `nullptr` + assert msg(excinfo.value) == """ + stl_pass_by_pointer(): incompatible function arguments. The following argument types are supported: + 1. (v: List[int] = None) -> List[int] + + Invoked with: + """ # noqa: E501 line too long + + with pytest.raises(TypeError) as excinfo: + m.stl_pass_by_pointer(None) + assert msg(excinfo.value) == """ + stl_pass_by_pointer(): incompatible function arguments. The following argument types are supported: + 1. (v: List[int] = None) -> List[int] + + Invoked with: None + """ # noqa: E501 line too long + + assert m.stl_pass_by_pointer([1, 2, 3]) == [1, 2, 3] + + +def test_missing_header_message(): + """Trying convert `list` to a `std::vector`, or vice versa, without including + should result in a helpful suggestion in the error message""" + import pybind11_cross_module_tests as cm + + expected_message = ("Did you forget to `#include `? Or ,\n" + ", , etc. Some automatic\n" + "conversions are optional and require extra headers to be included\n" + "when compiling your pybind11 module.") + + with pytest.raises(TypeError) as excinfo: + cm.missing_header_arg([1.0, 2.0, 3.0]) + assert expected_message in str(excinfo.value) + + with pytest.raises(TypeError) as excinfo: + cm.missing_header_return() + assert expected_message in str(excinfo.value) + + +def test_function_with_string_and_vector_string_arg(): + """Check if a string is NOT implicitly converted to a list, which was the + behavior before fix of issue #1258""" + assert m.func_with_string_or_vector_string_arg_overload(('A', 'B', )) == 2 + assert m.func_with_string_or_vector_string_arg_overload(['A', 'B']) == 2 + assert m.func_with_string_or_vector_string_arg_overload('A') == 3 + + +def test_stl_ownership(): + cstats = ConstructorStats.get(m.Placeholder) + assert cstats.alive() == 0 + r = m.test_stl_ownership() + assert len(r) == 1 + del r + assert cstats.alive() == 0 + + +def test_array_cast_sequence(): + assert m.array_cast_sequence((1, 2, 3)) == [1, 2, 3] + + +def test_issue_1561(): + """ check fix for issue #1561 """ + bar = m.Issue1561Outer() + bar.list = [m.Issue1561Inner('bar')] + bar.list + assert bar.list[0].data == 'bar' diff --git a/wrap/python/pybind11/tests/test_stl_binders.cpp b/wrap/python/pybind11/tests/test_stl_binders.cpp new file mode 100644 index 000000000..a88b589e1 --- /dev/null +++ b/wrap/python/pybind11/tests/test_stl_binders.cpp @@ -0,0 +1,107 @@ +/* + tests/test_stl_binders.cpp -- Usage of stl_binders functions + + Copyright (c) 2016 Sergey Lyskov + + All rights reserved. Use of this source code is governed by a + BSD-style license that can be found in the LICENSE file. +*/ + +#include "pybind11_tests.h" + +#include +#include +#include +#include +#include + +class El { +public: + El() = delete; + El(int v) : a(v) { } + + int a; +}; + +std::ostream & operator<<(std::ostream &s, El const&v) { + s << "El{" << v.a << '}'; + return s; +} + +/// Issue #487: binding std::vector with E non-copyable +class E_nc { +public: + explicit E_nc(int i) : value{i} {} + E_nc(const E_nc &) = delete; + E_nc &operator=(const E_nc &) = delete; + E_nc(E_nc &&) = default; + E_nc &operator=(E_nc &&) = default; + + int value; +}; + +template Container *one_to_n(int n) { + auto v = new Container(); + for (int i = 1; i <= n; i++) + v->emplace_back(i); + return v; +} + +template Map *times_ten(int n) { + auto m = new Map(); + for (int i = 1; i <= n; i++) + m->emplace(int(i), E_nc(10*i)); + return m; +} + +TEST_SUBMODULE(stl_binders, m) { + // test_vector_int + py::bind_vector>(m, "VectorInt", py::buffer_protocol()); + + // test_vector_custom + py::class_(m, "El") + .def(py::init()); + py::bind_vector>(m, "VectorEl"); + py::bind_vector>>(m, "VectorVectorEl"); + + // test_map_string_double + py::bind_map>(m, "MapStringDouble"); + py::bind_map>(m, "UnorderedMapStringDouble"); + + // test_map_string_double_const + py::bind_map>(m, "MapStringDoubleConst"); + py::bind_map>(m, "UnorderedMapStringDoubleConst"); + + py::class_(m, "ENC") + .def(py::init()) + .def_readwrite("value", &E_nc::value); + + // test_noncopyable_containers + py::bind_vector>(m, "VectorENC"); + m.def("get_vnc", &one_to_n>, py::return_value_policy::reference); + py::bind_vector>(m, "DequeENC"); + m.def("get_dnc", &one_to_n>, py::return_value_policy::reference); + py::bind_map>(m, "MapENC"); + m.def("get_mnc", ×_ten>, py::return_value_policy::reference); + py::bind_map>(m, "UmapENC"); + m.def("get_umnc", ×_ten>, py::return_value_policy::reference); + + // test_vector_buffer + py::bind_vector>(m, "VectorUChar", py::buffer_protocol()); + // no dtype declared for this version: + struct VUndeclStruct { bool w; uint32_t x; double y; bool z; }; + m.def("create_undeclstruct", [m] () mutable { + py::bind_vector>(m, "VectorUndeclStruct", py::buffer_protocol()); + }); + + // The rest depends on numpy: + try { py::module::import("numpy"); } + catch (...) { return; } + + // test_vector_buffer_numpy + struct VStruct { bool w; uint32_t x; double y; bool z; }; + PYBIND11_NUMPY_DTYPE(VStruct, w, x, y, z); + py::class_(m, "VStruct").def_readwrite("x", &VStruct::x); + py::bind_vector>(m, "VectorStruct", py::buffer_protocol()); + m.def("get_vectorstruct", [] {return std::vector {{0, 5, 3.0, 1}, {1, 30, -1e4, 0}};}); +} diff --git a/wrap/python/pybind11/tests/test_stl_binders.py b/wrap/python/pybind11/tests/test_stl_binders.py new file mode 100644 index 000000000..52c8ac0c4 --- /dev/null +++ b/wrap/python/pybind11/tests/test_stl_binders.py @@ -0,0 +1,225 @@ +import pytest +import sys +from pybind11_tests import stl_binders as m + +with pytest.suppress(ImportError): + import numpy as np + + +def test_vector_int(): + v_int = m.VectorInt([0, 0]) + assert len(v_int) == 2 + assert bool(v_int) is True + + # test construction from a generator + v_int1 = m.VectorInt(x for x in range(5)) + assert v_int1 == m.VectorInt([0, 1, 2, 3, 4]) + + v_int2 = m.VectorInt([0, 0]) + assert v_int == v_int2 + v_int2[1] = 1 + assert v_int != v_int2 + + v_int2.append(2) + v_int2.insert(0, 1) + v_int2.insert(0, 2) + v_int2.insert(0, 3) + v_int2.insert(6, 3) + assert str(v_int2) == "VectorInt[3, 2, 1, 0, 1, 2, 3]" + with pytest.raises(IndexError): + v_int2.insert(8, 4) + + v_int.append(99) + v_int2[2:-2] = v_int + assert v_int2 == m.VectorInt([3, 2, 0, 0, 99, 2, 3]) + del v_int2[1:3] + assert v_int2 == m.VectorInt([3, 0, 99, 2, 3]) + del v_int2[0] + assert v_int2 == m.VectorInt([0, 99, 2, 3]) + + v_int2.extend(m.VectorInt([4, 5])) + assert v_int2 == m.VectorInt([0, 99, 2, 3, 4, 5]) + + v_int2.extend([6, 7]) + assert v_int2 == m.VectorInt([0, 99, 2, 3, 4, 5, 6, 7]) + + # test error handling, and that the vector is unchanged + with pytest.raises(RuntimeError): + v_int2.extend([8, 'a']) + + assert v_int2 == m.VectorInt([0, 99, 2, 3, 4, 5, 6, 7]) + + # test extending from a generator + v_int2.extend(x for x in range(5)) + assert v_int2 == m.VectorInt([0, 99, 2, 3, 4, 5, 6, 7, 0, 1, 2, 3, 4]) + + +# related to the PyPy's buffer protocol. +@pytest.unsupported_on_pypy +def test_vector_buffer(): + b = bytearray([1, 2, 3, 4]) + v = m.VectorUChar(b) + assert v[1] == 2 + v[2] = 5 + mv = memoryview(v) # We expose the buffer interface + if sys.version_info.major > 2: + assert mv[2] == 5 + mv[2] = 6 + else: + assert mv[2] == '\x05' + mv[2] = '\x06' + assert v[2] == 6 + + with pytest.raises(RuntimeError) as excinfo: + m.create_undeclstruct() # Undeclared struct contents, no buffer interface + assert "NumPy type info missing for " in str(excinfo.value) + + +@pytest.unsupported_on_pypy +@pytest.requires_numpy +def test_vector_buffer_numpy(): + a = np.array([1, 2, 3, 4], dtype=np.int32) + with pytest.raises(TypeError): + m.VectorInt(a) + + a = np.array([[1, 2, 3, 4], [5, 6, 7, 8], [9, 10, 11, 12]], dtype=np.uintc) + v = m.VectorInt(a[0, :]) + assert len(v) == 4 + assert v[2] == 3 + ma = np.asarray(v) + ma[2] = 5 + assert v[2] == 5 + + v = m.VectorInt(a[:, 1]) + assert len(v) == 3 + assert v[2] == 10 + + v = m.get_vectorstruct() + assert v[0].x == 5 + ma = np.asarray(v) + ma[1]['x'] = 99 + assert v[1].x == 99 + + v = m.VectorStruct(np.zeros(3, dtype=np.dtype([('w', 'bool'), ('x', 'I'), + ('y', 'float64'), ('z', 'bool')], align=True))) + assert len(v) == 3 + + +def test_vector_bool(): + import pybind11_cross_module_tests as cm + + vv_c = cm.VectorBool() + for i in range(10): + vv_c.append(i % 2 == 0) + for i in range(10): + assert vv_c[i] == (i % 2 == 0) + assert str(vv_c) == "VectorBool[1, 0, 1, 0, 1, 0, 1, 0, 1, 0]" + + +def test_vector_custom(): + v_a = m.VectorEl() + v_a.append(m.El(1)) + v_a.append(m.El(2)) + assert str(v_a) == "VectorEl[El{1}, El{2}]" + + vv_a = m.VectorVectorEl() + vv_a.append(v_a) + vv_b = vv_a[0] + assert str(vv_b) == "VectorEl[El{1}, El{2}]" + + +def test_map_string_double(): + mm = m.MapStringDouble() + mm['a'] = 1 + mm['b'] = 2.5 + + assert list(mm) == ['a', 'b'] + assert list(mm.items()) == [('a', 1), ('b', 2.5)] + assert str(mm) == "MapStringDouble{a: 1, b: 2.5}" + + um = m.UnorderedMapStringDouble() + um['ua'] = 1.1 + um['ub'] = 2.6 + + assert sorted(list(um)) == ['ua', 'ub'] + assert sorted(list(um.items())) == [('ua', 1.1), ('ub', 2.6)] + assert "UnorderedMapStringDouble" in str(um) + + +def test_map_string_double_const(): + mc = m.MapStringDoubleConst() + mc['a'] = 10 + mc['b'] = 20.5 + assert str(mc) == "MapStringDoubleConst{a: 10, b: 20.5}" + + umc = m.UnorderedMapStringDoubleConst() + umc['a'] = 11 + umc['b'] = 21.5 + + str(umc) + + +def test_noncopyable_containers(): + # std::vector + vnc = m.get_vnc(5) + for i in range(0, 5): + assert vnc[i].value == i + 1 + + for i, j in enumerate(vnc, start=1): + assert j.value == i + + # std::deque + dnc = m.get_dnc(5) + for i in range(0, 5): + assert dnc[i].value == i + 1 + + i = 1 + for j in dnc: + assert(j.value == i) + i += 1 + + # std::map + mnc = m.get_mnc(5) + for i in range(1, 6): + assert mnc[i].value == 10 * i + + vsum = 0 + for k, v in mnc.items(): + assert v.value == 10 * k + vsum += v.value + + assert vsum == 150 + + # std::unordered_map + mnc = m.get_umnc(5) + for i in range(1, 6): + assert mnc[i].value == 10 * i + + vsum = 0 + for k, v in mnc.items(): + assert v.value == 10 * k + vsum += v.value + + assert vsum == 150 + + +def test_map_delitem(): + mm = m.MapStringDouble() + mm['a'] = 1 + mm['b'] = 2.5 + + assert list(mm) == ['a', 'b'] + assert list(mm.items()) == [('a', 1), ('b', 2.5)] + del mm['a'] + assert list(mm) == ['b'] + assert list(mm.items()) == [('b', 2.5)] + + um = m.UnorderedMapStringDouble() + um['ua'] = 1.1 + um['ub'] = 2.6 + + assert sorted(list(um)) == ['ua', 'ub'] + assert sorted(list(um.items())) == [('ua', 1.1), ('ub', 2.6)] + del um['ua'] + assert sorted(list(um)) == ['ub'] + assert sorted(list(um.items())) == [('ub', 2.6)] diff --git a/wrap/python/pybind11/tests/test_tagbased_polymorphic.cpp b/wrap/python/pybind11/tests/test_tagbased_polymorphic.cpp new file mode 100644 index 000000000..272e460c9 --- /dev/null +++ b/wrap/python/pybind11/tests/test_tagbased_polymorphic.cpp @@ -0,0 +1,136 @@ +/* + tests/test_tagbased_polymorphic.cpp -- test of polymorphic_type_hook + + Copyright (c) 2018 Hudson River Trading LLC + + All rights reserved. Use of this source code is governed by a + BSD-style license that can be found in the LICENSE file. +*/ + +#include "pybind11_tests.h" +#include + +struct Animal +{ + enum class Kind { + Unknown = 0, + Dog = 100, Labrador, Chihuahua, LastDog = 199, + Cat = 200, Panther, LastCat = 299 + }; + static const std::type_info* type_of_kind(Kind kind); + static std::string name_of_kind(Kind kind); + + const Kind kind; + const std::string name; + + protected: + Animal(const std::string& _name, Kind _kind) + : kind(_kind), name(_name) + {} +}; + +struct Dog : Animal +{ + Dog(const std::string& _name, Kind _kind = Kind::Dog) : Animal(_name, _kind) {} + std::string bark() const { return name_of_kind(kind) + " " + name + " goes " + sound; } + std::string sound = "WOOF!"; +}; + +struct Labrador : Dog +{ + Labrador(const std::string& _name, int _excitement = 9001) + : Dog(_name, Kind::Labrador), excitement(_excitement) {} + int excitement; +}; + +struct Chihuahua : Dog +{ + Chihuahua(const std::string& _name) : Dog(_name, Kind::Chihuahua) { sound = "iyiyiyiyiyi"; } + std::string bark() const { return Dog::bark() + " and runs in circles"; } +}; + +struct Cat : Animal +{ + Cat(const std::string& _name, Kind _kind = Kind::Cat) : Animal(_name, _kind) {} + std::string purr() const { return "mrowr"; } +}; + +struct Panther : Cat +{ + Panther(const std::string& _name) : Cat(_name, Kind::Panther) {} + std::string purr() const { return "mrrrRRRRRR"; } +}; + +std::vector> create_zoo() +{ + std::vector> ret; + ret.emplace_back(new Labrador("Fido", 15000)); + + // simulate some new type of Dog that the Python bindings + // haven't been updated for; it should still be considered + // a Dog, not just an Animal. + ret.emplace_back(new Dog("Ginger", Dog::Kind(150))); + + ret.emplace_back(new Chihuahua("Hertzl")); + ret.emplace_back(new Cat("Tiger", Cat::Kind::Cat)); + ret.emplace_back(new Panther("Leo")); + return ret; +} + +const std::type_info* Animal::type_of_kind(Kind kind) +{ + switch (kind) { + case Kind::Unknown: break; + + case Kind::Dog: break; + case Kind::Labrador: return &typeid(Labrador); + case Kind::Chihuahua: return &typeid(Chihuahua); + case Kind::LastDog: break; + + case Kind::Cat: break; + case Kind::Panther: return &typeid(Panther); + case Kind::LastCat: break; + } + + if (kind >= Kind::Dog && kind <= Kind::LastDog) return &typeid(Dog); + if (kind >= Kind::Cat && kind <= Kind::LastCat) return &typeid(Cat); + return nullptr; +} + +std::string Animal::name_of_kind(Kind kind) +{ + std::string raw_name = type_of_kind(kind)->name(); + py::detail::clean_type_id(raw_name); + return raw_name; +} + +namespace pybind11 { + template + struct polymorphic_type_hook::value>> + { + static const void *get(const itype *src, const std::type_info*& type) + { type = src ? Animal::type_of_kind(src->kind) : nullptr; return src; } + }; +} + +TEST_SUBMODULE(tagbased_polymorphic, m) { + py::class_(m, "Animal") + .def_readonly("name", &Animal::name); + py::class_(m, "Dog") + .def(py::init()) + .def_readwrite("sound", &Dog::sound) + .def("bark", &Dog::bark); + py::class_(m, "Labrador") + .def(py::init(), "name"_a, "excitement"_a = 9001) + .def_readwrite("excitement", &Labrador::excitement); + py::class_(m, "Chihuahua") + .def(py::init()) + .def("bark", &Chihuahua::bark); + py::class_(m, "Cat") + .def(py::init()) + .def("purr", &Cat::purr); + py::class_(m, "Panther") + .def(py::init()) + .def("purr", &Panther::purr); + m.def("create_zoo", &create_zoo); +}; diff --git a/wrap/python/pybind11/tests/test_tagbased_polymorphic.py b/wrap/python/pybind11/tests/test_tagbased_polymorphic.py new file mode 100644 index 000000000..2574d7de7 --- /dev/null +++ b/wrap/python/pybind11/tests/test_tagbased_polymorphic.py @@ -0,0 +1,20 @@ +from pybind11_tests import tagbased_polymorphic as m + + +def test_downcast(): + zoo = m.create_zoo() + assert [type(animal) for animal in zoo] == [ + m.Labrador, m.Dog, m.Chihuahua, m.Cat, m.Panther + ] + assert [animal.name for animal in zoo] == [ + "Fido", "Ginger", "Hertzl", "Tiger", "Leo" + ] + zoo[1].sound = "woooooo" + assert [dog.bark() for dog in zoo[:3]] == [ + "Labrador Fido goes WOOF!", + "Dog Ginger goes woooooo", + "Chihuahua Hertzl goes iyiyiyiyiyi and runs in circles" + ] + assert [cat.purr() for cat in zoo[3:]] == ["mrowr", "mrrrRRRRRR"] + zoo[0].excitement -= 1000 + assert zoo[0].excitement == 14000 diff --git a/wrap/python/pybind11/tests/test_union.cpp b/wrap/python/pybind11/tests/test_union.cpp new file mode 100644 index 000000000..7b98ea216 --- /dev/null +++ b/wrap/python/pybind11/tests/test_union.cpp @@ -0,0 +1,22 @@ +/* + tests/test_class.cpp -- test py::class_ definitions and basic functionality + + Copyright (c) 2019 Roland Dreier + + All rights reserved. Use of this source code is governed by a + BSD-style license that can be found in the LICENSE file. +*/ + +#include "pybind11_tests.h" + +TEST_SUBMODULE(union_, m) { + union TestUnion { + int value_int; + unsigned value_uint; + }; + + py::class_(m, "TestUnion") + .def(py::init<>()) + .def_readonly("as_int", &TestUnion::value_int) + .def_readwrite("as_uint", &TestUnion::value_uint); +} diff --git a/wrap/python/pybind11/tests/test_union.py b/wrap/python/pybind11/tests/test_union.py new file mode 100644 index 000000000..e1866e701 --- /dev/null +++ b/wrap/python/pybind11/tests/test_union.py @@ -0,0 +1,8 @@ +from pybind11_tests import union_ as m + + +def test_union(): + instance = m.TestUnion() + + instance.as_uint = 10 + assert instance.as_int == 10 diff --git a/wrap/python/pybind11/tests/test_virtual_functions.cpp b/wrap/python/pybind11/tests/test_virtual_functions.cpp new file mode 100644 index 000000000..ccf018d99 --- /dev/null +++ b/wrap/python/pybind11/tests/test_virtual_functions.cpp @@ -0,0 +1,479 @@ +/* + tests/test_virtual_functions.cpp -- overriding virtual functions from Python + + Copyright (c) 2016 Wenzel Jakob + + All rights reserved. Use of this source code is governed by a + BSD-style license that can be found in the LICENSE file. +*/ + +#include "pybind11_tests.h" +#include "constructor_stats.h" +#include +#include + +/* This is an example class that we'll want to be able to extend from Python */ +class ExampleVirt { +public: + ExampleVirt(int state) : state(state) { print_created(this, state); } + ExampleVirt(const ExampleVirt &e) : state(e.state) { print_copy_created(this); } + ExampleVirt(ExampleVirt &&e) : state(e.state) { print_move_created(this); e.state = 0; } + virtual ~ExampleVirt() { print_destroyed(this); } + + virtual int run(int value) { + py::print("Original implementation of " + "ExampleVirt::run(state={}, value={}, str1={}, str2={})"_s.format(state, value, get_string1(), *get_string2())); + return state + value; + } + + virtual bool run_bool() = 0; + virtual void pure_virtual() = 0; + + // Returning a reference/pointer to a type converted from python (numbers, strings, etc.) is a + // bit trickier, because the actual int& or std::string& or whatever only exists temporarily, so + // we have to handle it specially in the trampoline class (see below). + virtual const std::string &get_string1() { return str1; } + virtual const std::string *get_string2() { return &str2; } + +private: + int state; + const std::string str1{"default1"}, str2{"default2"}; +}; + +/* This is a wrapper class that must be generated */ +class PyExampleVirt : public ExampleVirt { +public: + using ExampleVirt::ExampleVirt; /* Inherit constructors */ + + int run(int value) override { + /* Generate wrapping code that enables native function overloading */ + PYBIND11_OVERLOAD( + int, /* Return type */ + ExampleVirt, /* Parent class */ + run, /* Name of function */ + value /* Argument(s) */ + ); + } + + bool run_bool() override { + PYBIND11_OVERLOAD_PURE( + bool, /* Return type */ + ExampleVirt, /* Parent class */ + run_bool, /* Name of function */ + /* This function has no arguments. The trailing comma + in the previous line is needed for some compilers */ + ); + } + + void pure_virtual() override { + PYBIND11_OVERLOAD_PURE( + void, /* Return type */ + ExampleVirt, /* Parent class */ + pure_virtual, /* Name of function */ + /* This function has no arguments. The trailing comma + in the previous line is needed for some compilers */ + ); + } + + // We can return reference types for compatibility with C++ virtual interfaces that do so, but + // note they have some significant limitations (see the documentation). + const std::string &get_string1() override { + PYBIND11_OVERLOAD( + const std::string &, /* Return type */ + ExampleVirt, /* Parent class */ + get_string1, /* Name of function */ + /* (no arguments) */ + ); + } + + const std::string *get_string2() override { + PYBIND11_OVERLOAD( + const std::string *, /* Return type */ + ExampleVirt, /* Parent class */ + get_string2, /* Name of function */ + /* (no arguments) */ + ); + } + +}; + +class NonCopyable { +public: + NonCopyable(int a, int b) : value{new int(a*b)} { print_created(this, a, b); } + NonCopyable(NonCopyable &&o) { value = std::move(o.value); print_move_created(this); } + NonCopyable(const NonCopyable &) = delete; + NonCopyable() = delete; + void operator=(const NonCopyable &) = delete; + void operator=(NonCopyable &&) = delete; + std::string get_value() const { + if (value) return std::to_string(*value); else return "(null)"; + } + ~NonCopyable() { print_destroyed(this); } + +private: + std::unique_ptr value; +}; + +// This is like the above, but is both copy and movable. In effect this means it should get moved +// when it is not referenced elsewhere, but copied if it is still referenced. +class Movable { +public: + Movable(int a, int b) : value{a+b} { print_created(this, a, b); } + Movable(const Movable &m) { value = m.value; print_copy_created(this); } + Movable(Movable &&m) { value = std::move(m.value); print_move_created(this); } + std::string get_value() const { return std::to_string(value); } + ~Movable() { print_destroyed(this); } +private: + int value; +}; + +class NCVirt { +public: + virtual ~NCVirt() { } + virtual NonCopyable get_noncopyable(int a, int b) { return NonCopyable(a, b); } + virtual Movable get_movable(int a, int b) = 0; + + std::string print_nc(int a, int b) { return get_noncopyable(a, b).get_value(); } + std::string print_movable(int a, int b) { return get_movable(a, b).get_value(); } +}; +class NCVirtTrampoline : public NCVirt { +#if !defined(__INTEL_COMPILER) + NonCopyable get_noncopyable(int a, int b) override { + PYBIND11_OVERLOAD(NonCopyable, NCVirt, get_noncopyable, a, b); + } +#endif + Movable get_movable(int a, int b) override { + PYBIND11_OVERLOAD_PURE(Movable, NCVirt, get_movable, a, b); + } +}; + +struct Base { + /* for some reason MSVC2015 can't compile this if the function is pure virtual */ + virtual std::string dispatch() const { return {}; }; + virtual ~Base() = default; +}; + +struct DispatchIssue : Base { + virtual std::string dispatch() const { + PYBIND11_OVERLOAD_PURE(std::string, Base, dispatch, /* no arguments */); + } +}; + +static void test_gil() { + { + py::gil_scoped_acquire lock; + py::print("1st lock acquired"); + + } + + { + py::gil_scoped_acquire lock; + py::print("2nd lock acquired"); + } + +} + +static void test_gil_from_thread() { + py::gil_scoped_release release; + + std::thread t(test_gil); + t.join(); +} + + +// Forward declaration (so that we can put the main tests here; the inherited virtual approaches are +// rather long). +void initialize_inherited_virtuals(py::module &m); + +TEST_SUBMODULE(virtual_functions, m) { + // test_override + py::class_(m, "ExampleVirt") + .def(py::init()) + /* Reference original class in function definitions */ + .def("run", &ExampleVirt::run) + .def("run_bool", &ExampleVirt::run_bool) + .def("pure_virtual", &ExampleVirt::pure_virtual); + + py::class_(m, "NonCopyable") + .def(py::init()); + + py::class_(m, "Movable") + .def(py::init()); + + // test_move_support +#if !defined(__INTEL_COMPILER) + py::class_(m, "NCVirt") + .def(py::init<>()) + .def("get_noncopyable", &NCVirt::get_noncopyable) + .def("get_movable", &NCVirt::get_movable) + .def("print_nc", &NCVirt::print_nc) + .def("print_movable", &NCVirt::print_movable); +#endif + + m.def("runExampleVirt", [](ExampleVirt *ex, int value) { return ex->run(value); }); + m.def("runExampleVirtBool", [](ExampleVirt* ex) { return ex->run_bool(); }); + m.def("runExampleVirtVirtual", [](ExampleVirt *ex) { ex->pure_virtual(); }); + + m.def("cstats_debug", &ConstructorStats::get); + initialize_inherited_virtuals(m); + + // test_alias_delay_initialization1 + // don't invoke Python dispatch classes by default when instantiating C++ classes + // that were not extended on the Python side + struct A { + virtual ~A() {} + virtual void f() { py::print("A.f()"); } + }; + + struct PyA : A { + PyA() { py::print("PyA.PyA()"); } + ~PyA() { py::print("PyA.~PyA()"); } + + void f() override { + py::print("PyA.f()"); + // This convolution just gives a `void`, but tests that PYBIND11_TYPE() works to protect + // a type containing a , + PYBIND11_OVERLOAD(PYBIND11_TYPE(typename std::enable_if::type), A, f); + } + }; + + py::class_(m, "A") + .def(py::init<>()) + .def("f", &A::f); + + m.def("call_f", [](A *a) { a->f(); }); + + // test_alias_delay_initialization2 + // ... unless we explicitly request it, as in this example: + struct A2 { + virtual ~A2() {} + virtual void f() { py::print("A2.f()"); } + }; + + struct PyA2 : A2 { + PyA2() { py::print("PyA2.PyA2()"); } + ~PyA2() { py::print("PyA2.~PyA2()"); } + void f() override { + py::print("PyA2.f()"); + PYBIND11_OVERLOAD(void, A2, f); + } + }; + + py::class_(m, "A2") + .def(py::init_alias<>()) + .def(py::init([](int) { return new PyA2(); })) + .def("f", &A2::f); + + m.def("call_f", [](A2 *a2) { a2->f(); }); + + // test_dispatch_issue + // #159: virtual function dispatch has problems with similar-named functions + py::class_(m, "DispatchIssue") + .def(py::init<>()) + .def("dispatch", &Base::dispatch); + + m.def("dispatch_issue_go", [](const Base * b) { return b->dispatch(); }); + + // test_override_ref + // #392/397: overriding reference-returning functions + class OverrideTest { + public: + struct A { std::string value = "hi"; }; + std::string v; + A a; + explicit OverrideTest(const std::string &v) : v{v} {} + virtual std::string str_value() { return v; } + virtual std::string &str_ref() { return v; } + virtual A A_value() { return a; } + virtual A &A_ref() { return a; } + virtual ~OverrideTest() = default; + }; + + class PyOverrideTest : public OverrideTest { + public: + using OverrideTest::OverrideTest; + std::string str_value() override { PYBIND11_OVERLOAD(std::string, OverrideTest, str_value); } + // Not allowed (uncommenting should hit a static_assert failure): we can't get a reference + // to a python numeric value, since we only copy values in the numeric type caster: +// std::string &str_ref() override { PYBIND11_OVERLOAD(std::string &, OverrideTest, str_ref); } + // But we can work around it like this: + private: + std::string _tmp; + std::string str_ref_helper() { PYBIND11_OVERLOAD(std::string, OverrideTest, str_ref); } + public: + std::string &str_ref() override { return _tmp = str_ref_helper(); } + + A A_value() override { PYBIND11_OVERLOAD(A, OverrideTest, A_value); } + A &A_ref() override { PYBIND11_OVERLOAD(A &, OverrideTest, A_ref); } + }; + + py::class_(m, "OverrideTest_A") + .def_readwrite("value", &OverrideTest::A::value); + py::class_(m, "OverrideTest") + .def(py::init()) + .def("str_value", &OverrideTest::str_value) +// .def("str_ref", &OverrideTest::str_ref) + .def("A_value", &OverrideTest::A_value) + .def("A_ref", &OverrideTest::A_ref); +} + + +// Inheriting virtual methods. We do two versions here: the repeat-everything version and the +// templated trampoline versions mentioned in docs/advanced.rst. +// +// These base classes are exactly the same, but we technically need distinct +// classes for this example code because we need to be able to bind them +// properly (pybind11, sensibly, doesn't allow us to bind the same C++ class to +// multiple python classes). +class A_Repeat { +#define A_METHODS \ +public: \ + virtual int unlucky_number() = 0; \ + virtual std::string say_something(unsigned times) { \ + std::string s = ""; \ + for (unsigned i = 0; i < times; ++i) \ + s += "hi"; \ + return s; \ + } \ + std::string say_everything() { \ + return say_something(1) + " " + std::to_string(unlucky_number()); \ + } +A_METHODS + virtual ~A_Repeat() = default; +}; +class B_Repeat : public A_Repeat { +#define B_METHODS \ +public: \ + int unlucky_number() override { return 13; } \ + std::string say_something(unsigned times) override { \ + return "B says hi " + std::to_string(times) + " times"; \ + } \ + virtual double lucky_number() { return 7.0; } +B_METHODS +}; +class C_Repeat : public B_Repeat { +#define C_METHODS \ +public: \ + int unlucky_number() override { return 4444; } \ + double lucky_number() override { return 888; } +C_METHODS +}; +class D_Repeat : public C_Repeat { +#define D_METHODS // Nothing overridden. +D_METHODS +}; + +// Base classes for templated inheritance trampolines. Identical to the repeat-everything version: +class A_Tpl { A_METHODS; virtual ~A_Tpl() = default; }; +class B_Tpl : public A_Tpl { B_METHODS }; +class C_Tpl : public B_Tpl { C_METHODS }; +class D_Tpl : public C_Tpl { D_METHODS }; + + +// Inheritance approach 1: each trampoline gets every virtual method (11 in total) +class PyA_Repeat : public A_Repeat { +public: + using A_Repeat::A_Repeat; + int unlucky_number() override { PYBIND11_OVERLOAD_PURE(int, A_Repeat, unlucky_number, ); } + std::string say_something(unsigned times) override { PYBIND11_OVERLOAD(std::string, A_Repeat, say_something, times); } +}; +class PyB_Repeat : public B_Repeat { +public: + using B_Repeat::B_Repeat; + int unlucky_number() override { PYBIND11_OVERLOAD(int, B_Repeat, unlucky_number, ); } + std::string say_something(unsigned times) override { PYBIND11_OVERLOAD(std::string, B_Repeat, say_something, times); } + double lucky_number() override { PYBIND11_OVERLOAD(double, B_Repeat, lucky_number, ); } +}; +class PyC_Repeat : public C_Repeat { +public: + using C_Repeat::C_Repeat; + int unlucky_number() override { PYBIND11_OVERLOAD(int, C_Repeat, unlucky_number, ); } + std::string say_something(unsigned times) override { PYBIND11_OVERLOAD(std::string, C_Repeat, say_something, times); } + double lucky_number() override { PYBIND11_OVERLOAD(double, C_Repeat, lucky_number, ); } +}; +class PyD_Repeat : public D_Repeat { +public: + using D_Repeat::D_Repeat; + int unlucky_number() override { PYBIND11_OVERLOAD(int, D_Repeat, unlucky_number, ); } + std::string say_something(unsigned times) override { PYBIND11_OVERLOAD(std::string, D_Repeat, say_something, times); } + double lucky_number() override { PYBIND11_OVERLOAD(double, D_Repeat, lucky_number, ); } +}; + +// Inheritance approach 2: templated trampoline classes. +// +// Advantages: +// - we have only 2 (template) class and 4 method declarations (one per virtual method, plus one for +// any override of a pure virtual method), versus 4 classes and 6 methods (MI) or 4 classes and 11 +// methods (repeat). +// - Compared to MI, we also don't have to change the non-trampoline inheritance to virtual, and can +// properly inherit constructors. +// +// Disadvantage: +// - the compiler must still generate and compile 14 different methods (more, even, than the 11 +// required for the repeat approach) instead of the 6 required for MI. (If there was no pure +// method (or no pure method override), the number would drop down to the same 11 as the repeat +// approach). +template +class PyA_Tpl : public Base { +public: + using Base::Base; // Inherit constructors + int unlucky_number() override { PYBIND11_OVERLOAD_PURE(int, Base, unlucky_number, ); } + std::string say_something(unsigned times) override { PYBIND11_OVERLOAD(std::string, Base, say_something, times); } +}; +template +class PyB_Tpl : public PyA_Tpl { +public: + using PyA_Tpl::PyA_Tpl; // Inherit constructors (via PyA_Tpl's inherited constructors) + int unlucky_number() override { PYBIND11_OVERLOAD(int, Base, unlucky_number, ); } + double lucky_number() override { PYBIND11_OVERLOAD(double, Base, lucky_number, ); } +}; +// Since C_Tpl and D_Tpl don't declare any new virtual methods, we don't actually need these (we can +// use PyB_Tpl and PyB_Tpl for the trampoline classes instead): +/* +template class PyC_Tpl : public PyB_Tpl { +public: + using PyB_Tpl::PyB_Tpl; +}; +template class PyD_Tpl : public PyC_Tpl { +public: + using PyC_Tpl::PyC_Tpl; +}; +*/ + +void initialize_inherited_virtuals(py::module &m) { + // test_inherited_virtuals + + // Method 1: repeat + py::class_(m, "A_Repeat") + .def(py::init<>()) + .def("unlucky_number", &A_Repeat::unlucky_number) + .def("say_something", &A_Repeat::say_something) + .def("say_everything", &A_Repeat::say_everything); + py::class_(m, "B_Repeat") + .def(py::init<>()) + .def("lucky_number", &B_Repeat::lucky_number); + py::class_(m, "C_Repeat") + .def(py::init<>()); + py::class_(m, "D_Repeat") + .def(py::init<>()); + + // test_ + // Method 2: Templated trampolines + py::class_>(m, "A_Tpl") + .def(py::init<>()) + .def("unlucky_number", &A_Tpl::unlucky_number) + .def("say_something", &A_Tpl::say_something) + .def("say_everything", &A_Tpl::say_everything); + py::class_>(m, "B_Tpl") + .def(py::init<>()) + .def("lucky_number", &B_Tpl::lucky_number); + py::class_>(m, "C_Tpl") + .def(py::init<>()); + py::class_>(m, "D_Tpl") + .def(py::init<>()); + + + // Fix issue #1454 (crash when acquiring/releasing GIL on another thread in Python 2.7) + m.def("test_gil", &test_gil); + m.def("test_gil_from_thread", &test_gil_from_thread); +}; diff --git a/wrap/python/pybind11/tests/test_virtual_functions.py b/wrap/python/pybind11/tests/test_virtual_functions.py new file mode 100644 index 000000000..5ce9abd35 --- /dev/null +++ b/wrap/python/pybind11/tests/test_virtual_functions.py @@ -0,0 +1,377 @@ +import pytest + +from pybind11_tests import virtual_functions as m +from pybind11_tests import ConstructorStats + + +def test_override(capture, msg): + class ExtendedExampleVirt(m.ExampleVirt): + def __init__(self, state): + super(ExtendedExampleVirt, self).__init__(state + 1) + self.data = "Hello world" + + def run(self, value): + print('ExtendedExampleVirt::run(%i), calling parent..' % value) + return super(ExtendedExampleVirt, self).run(value + 1) + + def run_bool(self): + print('ExtendedExampleVirt::run_bool()') + return False + + def get_string1(self): + return "override1" + + def pure_virtual(self): + print('ExtendedExampleVirt::pure_virtual(): %s' % self.data) + + class ExtendedExampleVirt2(ExtendedExampleVirt): + def __init__(self, state): + super(ExtendedExampleVirt2, self).__init__(state + 1) + + def get_string2(self): + return "override2" + + ex12 = m.ExampleVirt(10) + with capture: + assert m.runExampleVirt(ex12, 20) == 30 + assert capture == """ + Original implementation of ExampleVirt::run(state=10, value=20, str1=default1, str2=default2) + """ # noqa: E501 line too long + + with pytest.raises(RuntimeError) as excinfo: + m.runExampleVirtVirtual(ex12) + assert msg(excinfo.value) == 'Tried to call pure virtual function "ExampleVirt::pure_virtual"' + + ex12p = ExtendedExampleVirt(10) + with capture: + assert m.runExampleVirt(ex12p, 20) == 32 + assert capture == """ + ExtendedExampleVirt::run(20), calling parent.. + Original implementation of ExampleVirt::run(state=11, value=21, str1=override1, str2=default2) + """ # noqa: E501 line too long + with capture: + assert m.runExampleVirtBool(ex12p) is False + assert capture == "ExtendedExampleVirt::run_bool()" + with capture: + m.runExampleVirtVirtual(ex12p) + assert capture == "ExtendedExampleVirt::pure_virtual(): Hello world" + + ex12p2 = ExtendedExampleVirt2(15) + with capture: + assert m.runExampleVirt(ex12p2, 50) == 68 + assert capture == """ + ExtendedExampleVirt::run(50), calling parent.. + Original implementation of ExampleVirt::run(state=17, value=51, str1=override1, str2=override2) + """ # noqa: E501 line too long + + cstats = ConstructorStats.get(m.ExampleVirt) + assert cstats.alive() == 3 + del ex12, ex12p, ex12p2 + assert cstats.alive() == 0 + assert cstats.values() == ['10', '11', '17'] + assert cstats.copy_constructions == 0 + assert cstats.move_constructions >= 0 + + +def test_alias_delay_initialization1(capture): + """`A` only initializes its trampoline class when we inherit from it + + If we just create and use an A instance directly, the trampoline initialization is + bypassed and we only initialize an A() instead (for performance reasons). + """ + class B(m.A): + def __init__(self): + super(B, self).__init__() + + def f(self): + print("In python f()") + + # C++ version + with capture: + a = m.A() + m.call_f(a) + del a + pytest.gc_collect() + assert capture == "A.f()" + + # Python version + with capture: + b = B() + m.call_f(b) + del b + pytest.gc_collect() + assert capture == """ + PyA.PyA() + PyA.f() + In python f() + PyA.~PyA() + """ + + +def test_alias_delay_initialization2(capture): + """`A2`, unlike the above, is configured to always initialize the alias + + While the extra initialization and extra class layer has small virtual dispatch + performance penalty, it also allows us to do more things with the trampoline + class such as defining local variables and performing construction/destruction. + """ + class B2(m.A2): + def __init__(self): + super(B2, self).__init__() + + def f(self): + print("In python B2.f()") + + # No python subclass version + with capture: + a2 = m.A2() + m.call_f(a2) + del a2 + pytest.gc_collect() + a3 = m.A2(1) + m.call_f(a3) + del a3 + pytest.gc_collect() + assert capture == """ + PyA2.PyA2() + PyA2.f() + A2.f() + PyA2.~PyA2() + PyA2.PyA2() + PyA2.f() + A2.f() + PyA2.~PyA2() + """ + + # Python subclass version + with capture: + b2 = B2() + m.call_f(b2) + del b2 + pytest.gc_collect() + assert capture == """ + PyA2.PyA2() + PyA2.f() + In python B2.f() + PyA2.~PyA2() + """ + + +# PyPy: Reference count > 1 causes call with noncopyable instance +# to fail in ncv1.print_nc() +@pytest.unsupported_on_pypy +@pytest.mark.skipif(not hasattr(m, "NCVirt"), reason="NCVirt test broken on ICPC") +def test_move_support(): + class NCVirtExt(m.NCVirt): + def get_noncopyable(self, a, b): + # Constructs and returns a new instance: + nc = m.NonCopyable(a * a, b * b) + return nc + + def get_movable(self, a, b): + # Return a referenced copy + self.movable = m.Movable(a, b) + return self.movable + + class NCVirtExt2(m.NCVirt): + def get_noncopyable(self, a, b): + # Keep a reference: this is going to throw an exception + self.nc = m.NonCopyable(a, b) + return self.nc + + def get_movable(self, a, b): + # Return a new instance without storing it + return m.Movable(a, b) + + ncv1 = NCVirtExt() + assert ncv1.print_nc(2, 3) == "36" + assert ncv1.print_movable(4, 5) == "9" + ncv2 = NCVirtExt2() + assert ncv2.print_movable(7, 7) == "14" + # Don't check the exception message here because it differs under debug/non-debug mode + with pytest.raises(RuntimeError): + ncv2.print_nc(9, 9) + + nc_stats = ConstructorStats.get(m.NonCopyable) + mv_stats = ConstructorStats.get(m.Movable) + assert nc_stats.alive() == 1 + assert mv_stats.alive() == 1 + del ncv1, ncv2 + assert nc_stats.alive() == 0 + assert mv_stats.alive() == 0 + assert nc_stats.values() == ['4', '9', '9', '9'] + assert mv_stats.values() == ['4', '5', '7', '7'] + assert nc_stats.copy_constructions == 0 + assert mv_stats.copy_constructions == 1 + assert nc_stats.move_constructions >= 0 + assert mv_stats.move_constructions >= 0 + + +def test_dispatch_issue(msg): + """#159: virtual function dispatch has problems with similar-named functions""" + class PyClass1(m.DispatchIssue): + def dispatch(self): + return "Yay.." + + class PyClass2(m.DispatchIssue): + def dispatch(self): + with pytest.raises(RuntimeError) as excinfo: + super(PyClass2, self).dispatch() + assert msg(excinfo.value) == 'Tried to call pure virtual function "Base::dispatch"' + + p = PyClass1() + return m.dispatch_issue_go(p) + + b = PyClass2() + assert m.dispatch_issue_go(b) == "Yay.." + + +def test_override_ref(): + """#392/397: overriding reference-returning functions""" + o = m.OverrideTest("asdf") + + # Not allowed (see associated .cpp comment) + # i = o.str_ref() + # assert o.str_ref() == "asdf" + assert o.str_value() == "asdf" + + assert o.A_value().value == "hi" + a = o.A_ref() + assert a.value == "hi" + a.value = "bye" + assert a.value == "bye" + + +def test_inherited_virtuals(): + class AR(m.A_Repeat): + def unlucky_number(self): + return 99 + + class AT(m.A_Tpl): + def unlucky_number(self): + return 999 + + obj = AR() + assert obj.say_something(3) == "hihihi" + assert obj.unlucky_number() == 99 + assert obj.say_everything() == "hi 99" + + obj = AT() + assert obj.say_something(3) == "hihihi" + assert obj.unlucky_number() == 999 + assert obj.say_everything() == "hi 999" + + for obj in [m.B_Repeat(), m.B_Tpl()]: + assert obj.say_something(3) == "B says hi 3 times" + assert obj.unlucky_number() == 13 + assert obj.lucky_number() == 7.0 + assert obj.say_everything() == "B says hi 1 times 13" + + for obj in [m.C_Repeat(), m.C_Tpl()]: + assert obj.say_something(3) == "B says hi 3 times" + assert obj.unlucky_number() == 4444 + assert obj.lucky_number() == 888.0 + assert obj.say_everything() == "B says hi 1 times 4444" + + class CR(m.C_Repeat): + def lucky_number(self): + return m.C_Repeat.lucky_number(self) + 1.25 + + obj = CR() + assert obj.say_something(3) == "B says hi 3 times" + assert obj.unlucky_number() == 4444 + assert obj.lucky_number() == 889.25 + assert obj.say_everything() == "B says hi 1 times 4444" + + class CT(m.C_Tpl): + pass + + obj = CT() + assert obj.say_something(3) == "B says hi 3 times" + assert obj.unlucky_number() == 4444 + assert obj.lucky_number() == 888.0 + assert obj.say_everything() == "B says hi 1 times 4444" + + class CCR(CR): + def lucky_number(self): + return CR.lucky_number(self) * 10 + + obj = CCR() + assert obj.say_something(3) == "B says hi 3 times" + assert obj.unlucky_number() == 4444 + assert obj.lucky_number() == 8892.5 + assert obj.say_everything() == "B says hi 1 times 4444" + + class CCT(CT): + def lucky_number(self): + return CT.lucky_number(self) * 1000 + + obj = CCT() + assert obj.say_something(3) == "B says hi 3 times" + assert obj.unlucky_number() == 4444 + assert obj.lucky_number() == 888000.0 + assert obj.say_everything() == "B says hi 1 times 4444" + + class DR(m.D_Repeat): + def unlucky_number(self): + return 123 + + def lucky_number(self): + return 42.0 + + for obj in [m.D_Repeat(), m.D_Tpl()]: + assert obj.say_something(3) == "B says hi 3 times" + assert obj.unlucky_number() == 4444 + assert obj.lucky_number() == 888.0 + assert obj.say_everything() == "B says hi 1 times 4444" + + obj = DR() + assert obj.say_something(3) == "B says hi 3 times" + assert obj.unlucky_number() == 123 + assert obj.lucky_number() == 42.0 + assert obj.say_everything() == "B says hi 1 times 123" + + class DT(m.D_Tpl): + def say_something(self, times): + return "DT says:" + (' quack' * times) + + def unlucky_number(self): + return 1234 + + def lucky_number(self): + return -4.25 + + obj = DT() + assert obj.say_something(3) == "DT says: quack quack quack" + assert obj.unlucky_number() == 1234 + assert obj.lucky_number() == -4.25 + assert obj.say_everything() == "DT says: quack 1234" + + class DT2(DT): + def say_something(self, times): + return "DT2: " + ('QUACK' * times) + + def unlucky_number(self): + return -3 + + class BT(m.B_Tpl): + def say_something(self, times): + return "BT" * times + + def unlucky_number(self): + return -7 + + def lucky_number(self): + return -1.375 + + obj = BT() + assert obj.say_something(3) == "BTBTBT" + assert obj.unlucky_number() == -7 + assert obj.lucky_number() == -1.375 + assert obj.say_everything() == "BT -7" + + +def test_issue_1454(): + # Fix issue #1454 (crash when acquiring/releasing GIL on another thread in Python 2.7) + m.test_gil() + m.test_gil_from_thread() diff --git a/wrap/python/pybind11/tools/FindCatch.cmake b/wrap/python/pybind11/tools/FindCatch.cmake new file mode 100644 index 000000000..9d490c5aa --- /dev/null +++ b/wrap/python/pybind11/tools/FindCatch.cmake @@ -0,0 +1,57 @@ +# - Find the Catch test framework or download it (single header) +# +# This is a quick module for internal use. It assumes that Catch is +# REQUIRED and that a minimum version is provided (not EXACT). If +# a suitable version isn't found locally, the single header file +# will be downloaded and placed in the build dir: PROJECT_BINARY_DIR. +# +# This code sets the following variables: +# CATCH_INCLUDE_DIR - path to catch.hpp +# CATCH_VERSION - version number + +if(NOT Catch_FIND_VERSION) + message(FATAL_ERROR "A version number must be specified.") +elseif(Catch_FIND_REQUIRED) + message(FATAL_ERROR "This module assumes Catch is not required.") +elseif(Catch_FIND_VERSION_EXACT) + message(FATAL_ERROR "Exact version numbers are not supported, only minimum.") +endif() + +# Extract the version number from catch.hpp +function(_get_catch_version) + file(STRINGS "${CATCH_INCLUDE_DIR}/catch.hpp" version_line REGEX "Catch v.*" LIMIT_COUNT 1) + if(version_line MATCHES "Catch v([0-9]+)\\.([0-9]+)\\.([0-9]+)") + set(CATCH_VERSION "${CMAKE_MATCH_1}.${CMAKE_MATCH_2}.${CMAKE_MATCH_3}" PARENT_SCOPE) + endif() +endfunction() + +# Download the single-header version of Catch +function(_download_catch version destination_dir) + message(STATUS "Downloading catch v${version}...") + set(url https://github.com/philsquared/Catch/releases/download/v${version}/catch.hpp) + file(DOWNLOAD ${url} "${destination_dir}/catch.hpp" STATUS status) + list(GET status 0 error) + if(error) + message(FATAL_ERROR "Could not download ${url}") + endif() + set(CATCH_INCLUDE_DIR "${destination_dir}" CACHE INTERNAL "") +endfunction() + +# Look for catch locally +find_path(CATCH_INCLUDE_DIR NAMES catch.hpp PATH_SUFFIXES catch) +if(CATCH_INCLUDE_DIR) + _get_catch_version() +endif() + +# Download the header if it wasn't found or if it's outdated +if(NOT CATCH_VERSION OR CATCH_VERSION VERSION_LESS ${Catch_FIND_VERSION}) + if(DOWNLOAD_CATCH) + _download_catch(${Catch_FIND_VERSION} "${PROJECT_BINARY_DIR}/catch/") + _get_catch_version() + else() + set(CATCH_FOUND FALSE) + return() + endif() +endif() + +set(CATCH_FOUND TRUE) diff --git a/wrap/python/pybind11/tools/FindEigen3.cmake b/wrap/python/pybind11/tools/FindEigen3.cmake new file mode 100644 index 000000000..9c546a05d --- /dev/null +++ b/wrap/python/pybind11/tools/FindEigen3.cmake @@ -0,0 +1,81 @@ +# - Try to find Eigen3 lib +# +# This module supports requiring a minimum version, e.g. you can do +# find_package(Eigen3 3.1.2) +# to require version 3.1.2 or newer of Eigen3. +# +# Once done this will define +# +# EIGEN3_FOUND - system has eigen lib with correct version +# EIGEN3_INCLUDE_DIR - the eigen include directory +# EIGEN3_VERSION - eigen version + +# Copyright (c) 2006, 2007 Montel Laurent, +# Copyright (c) 2008, 2009 Gael Guennebaud, +# Copyright (c) 2009 Benoit Jacob +# Redistribution and use is allowed according to the terms of the 2-clause BSD license. + +if(NOT Eigen3_FIND_VERSION) + if(NOT Eigen3_FIND_VERSION_MAJOR) + set(Eigen3_FIND_VERSION_MAJOR 2) + endif(NOT Eigen3_FIND_VERSION_MAJOR) + if(NOT Eigen3_FIND_VERSION_MINOR) + set(Eigen3_FIND_VERSION_MINOR 91) + endif(NOT Eigen3_FIND_VERSION_MINOR) + if(NOT Eigen3_FIND_VERSION_PATCH) + set(Eigen3_FIND_VERSION_PATCH 0) + endif(NOT Eigen3_FIND_VERSION_PATCH) + + set(Eigen3_FIND_VERSION "${Eigen3_FIND_VERSION_MAJOR}.${Eigen3_FIND_VERSION_MINOR}.${Eigen3_FIND_VERSION_PATCH}") +endif(NOT Eigen3_FIND_VERSION) + +macro(_eigen3_check_version) + file(READ "${EIGEN3_INCLUDE_DIR}/Eigen/src/Core/util/Macros.h" _eigen3_version_header) + + string(REGEX MATCH "define[ \t]+EIGEN_WORLD_VERSION[ \t]+([0-9]+)" _eigen3_world_version_match "${_eigen3_version_header}") + set(EIGEN3_WORLD_VERSION "${CMAKE_MATCH_1}") + string(REGEX MATCH "define[ \t]+EIGEN_MAJOR_VERSION[ \t]+([0-9]+)" _eigen3_major_version_match "${_eigen3_version_header}") + set(EIGEN3_MAJOR_VERSION "${CMAKE_MATCH_1}") + string(REGEX MATCH "define[ \t]+EIGEN_MINOR_VERSION[ \t]+([0-9]+)" _eigen3_minor_version_match "${_eigen3_version_header}") + set(EIGEN3_MINOR_VERSION "${CMAKE_MATCH_1}") + + set(EIGEN3_VERSION ${EIGEN3_WORLD_VERSION}.${EIGEN3_MAJOR_VERSION}.${EIGEN3_MINOR_VERSION}) + if(${EIGEN3_VERSION} VERSION_LESS ${Eigen3_FIND_VERSION}) + set(EIGEN3_VERSION_OK FALSE) + else(${EIGEN3_VERSION} VERSION_LESS ${Eigen3_FIND_VERSION}) + set(EIGEN3_VERSION_OK TRUE) + endif(${EIGEN3_VERSION} VERSION_LESS ${Eigen3_FIND_VERSION}) + + if(NOT EIGEN3_VERSION_OK) + + message(STATUS "Eigen3 version ${EIGEN3_VERSION} found in ${EIGEN3_INCLUDE_DIR}, " + "but at least version ${Eigen3_FIND_VERSION} is required") + endif(NOT EIGEN3_VERSION_OK) +endmacro(_eigen3_check_version) + +if (EIGEN3_INCLUDE_DIR) + + # in cache already + _eigen3_check_version() + set(EIGEN3_FOUND ${EIGEN3_VERSION_OK}) + +else (EIGEN3_INCLUDE_DIR) + + find_path(EIGEN3_INCLUDE_DIR NAMES signature_of_eigen3_matrix_library + PATHS + ${CMAKE_INSTALL_PREFIX}/include + ${KDE4_INCLUDE_DIR} + PATH_SUFFIXES eigen3 eigen + ) + + if(EIGEN3_INCLUDE_DIR) + _eigen3_check_version() + endif(EIGEN3_INCLUDE_DIR) + + include(FindPackageHandleStandardArgs) + find_package_handle_standard_args(Eigen3 DEFAULT_MSG EIGEN3_INCLUDE_DIR EIGEN3_VERSION_OK) + + mark_as_advanced(EIGEN3_INCLUDE_DIR) + +endif(EIGEN3_INCLUDE_DIR) + diff --git a/wrap/python/pybind11/tools/FindPythonLibsNew.cmake b/wrap/python/pybind11/tools/FindPythonLibsNew.cmake new file mode 100644 index 000000000..7d85af4a5 --- /dev/null +++ b/wrap/python/pybind11/tools/FindPythonLibsNew.cmake @@ -0,0 +1,202 @@ +# - Find python libraries +# This module finds the libraries corresponding to the Python interpreter +# FindPythonInterp provides. +# This code sets the following variables: +# +# PYTHONLIBS_FOUND - have the Python libs been found +# PYTHON_PREFIX - path to the Python installation +# PYTHON_LIBRARIES - path to the python library +# PYTHON_INCLUDE_DIRS - path to where Python.h is found +# PYTHON_MODULE_EXTENSION - lib extension, e.g. '.so' or '.pyd' +# PYTHON_MODULE_PREFIX - lib name prefix: usually an empty string +# PYTHON_SITE_PACKAGES - path to installation site-packages +# PYTHON_IS_DEBUG - whether the Python interpreter is a debug build +# +# Thanks to talljimbo for the patch adding the 'LDVERSION' config +# variable usage. + +#============================================================================= +# Copyright 2001-2009 Kitware, Inc. +# Copyright 2012 Continuum Analytics, Inc. +# +# All rights reserved. +# +# Redistribution and use in source and binary forms, with or without +# modification, are permitted provided that the following conditions +# are met: +# +# * Redistributions of source code must retain the above copyright +# notice, this list of conditions and the following disclaimer. +# +# * Redistributions in binary form must reproduce the above copyright +# notice, this list of conditions and the following disclaimer in the +# documentation and/or other materials provided with the distribution. +# +# * Neither the names of Kitware, Inc., the Insight Software Consortium, +# nor the names of their contributors may be used to endorse or promote +# products derived from this software without specific prior written +# permission. +# +# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR +# # A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT +# HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, +# SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT +# LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, +# DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY +# THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT +# (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE +# OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +#============================================================================= + +# Checking for the extension makes sure that `LibsNew` was found and not just `Libs`. +if(PYTHONLIBS_FOUND AND PYTHON_MODULE_EXTENSION) + return() +endif() + +# Use the Python interpreter to find the libs. +if(PythonLibsNew_FIND_REQUIRED) + find_package(PythonInterp ${PythonLibsNew_FIND_VERSION} REQUIRED) +else() + find_package(PythonInterp ${PythonLibsNew_FIND_VERSION}) +endif() + +if(NOT PYTHONINTERP_FOUND) + set(PYTHONLIBS_FOUND FALSE) + set(PythonLibsNew_FOUND FALSE) + return() +endif() + +# According to http://stackoverflow.com/questions/646518/python-how-to-detect-debug-interpreter +# testing whether sys has the gettotalrefcount function is a reliable, cross-platform +# way to detect a CPython debug interpreter. +# +# The library suffix is from the config var LDVERSION sometimes, otherwise +# VERSION. VERSION will typically be like "2.7" on unix, and "27" on windows. +execute_process(COMMAND "${PYTHON_EXECUTABLE}" "-c" + "from distutils import sysconfig as s;import sys;import struct; +print('.'.join(str(v) for v in sys.version_info)); +print(sys.prefix); +print(s.get_python_inc(plat_specific=True)); +print(s.get_python_lib(plat_specific=True)); +print(s.get_config_var('SO')); +print(hasattr(sys, 'gettotalrefcount')+0); +print(struct.calcsize('@P')); +print(s.get_config_var('LDVERSION') or s.get_config_var('VERSION')); +print(s.get_config_var('LIBDIR') or ''); +print(s.get_config_var('MULTIARCH') or ''); +" + RESULT_VARIABLE _PYTHON_SUCCESS + OUTPUT_VARIABLE _PYTHON_VALUES + ERROR_VARIABLE _PYTHON_ERROR_VALUE) + +if(NOT _PYTHON_SUCCESS MATCHES 0) + if(PythonLibsNew_FIND_REQUIRED) + message(FATAL_ERROR + "Python config failure:\n${_PYTHON_ERROR_VALUE}") + endif() + set(PYTHONLIBS_FOUND FALSE) + set(PythonLibsNew_FOUND FALSE) + return() +endif() + +# Convert the process output into a list +if(WIN32) + string(REGEX REPLACE "\\\\" "/" _PYTHON_VALUES ${_PYTHON_VALUES}) +endif() +string(REGEX REPLACE ";" "\\\\;" _PYTHON_VALUES ${_PYTHON_VALUES}) +string(REGEX REPLACE "\n" ";" _PYTHON_VALUES ${_PYTHON_VALUES}) +list(GET _PYTHON_VALUES 0 _PYTHON_VERSION_LIST) +list(GET _PYTHON_VALUES 1 PYTHON_PREFIX) +list(GET _PYTHON_VALUES 2 PYTHON_INCLUDE_DIR) +list(GET _PYTHON_VALUES 3 PYTHON_SITE_PACKAGES) +list(GET _PYTHON_VALUES 4 PYTHON_MODULE_EXTENSION) +list(GET _PYTHON_VALUES 5 PYTHON_IS_DEBUG) +list(GET _PYTHON_VALUES 6 PYTHON_SIZEOF_VOID_P) +list(GET _PYTHON_VALUES 7 PYTHON_LIBRARY_SUFFIX) +list(GET _PYTHON_VALUES 8 PYTHON_LIBDIR) +list(GET _PYTHON_VALUES 9 PYTHON_MULTIARCH) + +# Make sure the Python has the same pointer-size as the chosen compiler +# Skip if CMAKE_SIZEOF_VOID_P is not defined +if(CMAKE_SIZEOF_VOID_P AND (NOT "${PYTHON_SIZEOF_VOID_P}" STREQUAL "${CMAKE_SIZEOF_VOID_P}")) + if(PythonLibsNew_FIND_REQUIRED) + math(EXPR _PYTHON_BITS "${PYTHON_SIZEOF_VOID_P} * 8") + math(EXPR _CMAKE_BITS "${CMAKE_SIZEOF_VOID_P} * 8") + message(FATAL_ERROR + "Python config failure: Python is ${_PYTHON_BITS}-bit, " + "chosen compiler is ${_CMAKE_BITS}-bit") + endif() + set(PYTHONLIBS_FOUND FALSE) + set(PythonLibsNew_FOUND FALSE) + return() +endif() + +# The built-in FindPython didn't always give the version numbers +string(REGEX REPLACE "\\." ";" _PYTHON_VERSION_LIST ${_PYTHON_VERSION_LIST}) +list(GET _PYTHON_VERSION_LIST 0 PYTHON_VERSION_MAJOR) +list(GET _PYTHON_VERSION_LIST 1 PYTHON_VERSION_MINOR) +list(GET _PYTHON_VERSION_LIST 2 PYTHON_VERSION_PATCH) + +# Make sure all directory separators are '/' +string(REGEX REPLACE "\\\\" "/" PYTHON_PREFIX ${PYTHON_PREFIX}) +string(REGEX REPLACE "\\\\" "/" PYTHON_INCLUDE_DIR ${PYTHON_INCLUDE_DIR}) +string(REGEX REPLACE "\\\\" "/" PYTHON_SITE_PACKAGES ${PYTHON_SITE_PACKAGES}) + +if(CMAKE_HOST_WIN32) + set(PYTHON_LIBRARY + "${PYTHON_PREFIX}/libs/Python${PYTHON_LIBRARY_SUFFIX}.lib") + + # when run in a venv, PYTHON_PREFIX points to it. But the libraries remain in the + # original python installation. They may be found relative to PYTHON_INCLUDE_DIR. + if(NOT EXISTS "${PYTHON_LIBRARY}") + get_filename_component(_PYTHON_ROOT ${PYTHON_INCLUDE_DIR} DIRECTORY) + set(PYTHON_LIBRARY + "${_PYTHON_ROOT}/libs/Python${PYTHON_LIBRARY_SUFFIX}.lib") + endif() + + # raise an error if the python libs are still not found. + if(NOT EXISTS "${PYTHON_LIBRARY}") + message(FATAL_ERROR "Python libraries not found") + endif() + +else() + if(PYTHON_MULTIARCH) + set(_PYTHON_LIBS_SEARCH "${PYTHON_LIBDIR}/${PYTHON_MULTIARCH}" "${PYTHON_LIBDIR}") + else() + set(_PYTHON_LIBS_SEARCH "${PYTHON_LIBDIR}") + endif() + #message(STATUS "Searching for Python libs in ${_PYTHON_LIBS_SEARCH}") + # Probably this needs to be more involved. It would be nice if the config + # information the python interpreter itself gave us were more complete. + find_library(PYTHON_LIBRARY + NAMES "python${PYTHON_LIBRARY_SUFFIX}" + PATHS ${_PYTHON_LIBS_SEARCH} + NO_DEFAULT_PATH) + + # If all else fails, just set the name/version and let the linker figure out the path. + if(NOT PYTHON_LIBRARY) + set(PYTHON_LIBRARY python${PYTHON_LIBRARY_SUFFIX}) + endif() +endif() + +MARK_AS_ADVANCED( + PYTHON_LIBRARY + PYTHON_INCLUDE_DIR +) + +# We use PYTHON_INCLUDE_DIR, PYTHON_LIBRARY and PYTHON_DEBUG_LIBRARY for the +# cache entries because they are meant to specify the location of a single +# library. We now set the variables listed by the documentation for this +# module. +SET(PYTHON_INCLUDE_DIRS "${PYTHON_INCLUDE_DIR}") +SET(PYTHON_LIBRARIES "${PYTHON_LIBRARY}") +SET(PYTHON_DEBUG_LIBRARIES "${PYTHON_DEBUG_LIBRARY}") + +find_package_message(PYTHON + "Found PythonLibs: ${PYTHON_LIBRARY}" + "${PYTHON_EXECUTABLE}${PYTHON_VERSION}") + +set(PYTHONLIBS_FOUND TRUE) +set(PythonLibsNew_FOUND TRUE) diff --git a/wrap/python/pybind11/tools/check-style.sh b/wrap/python/pybind11/tools/check-style.sh new file mode 100755 index 000000000..0a9f7d24f --- /dev/null +++ b/wrap/python/pybind11/tools/check-style.sh @@ -0,0 +1,70 @@ +#!/bin/bash +# +# Script to check include/test code for common pybind11 code style errors. +# +# This script currently checks for +# +# 1. use of tabs instead of spaces +# 2. MSDOS-style CRLF endings +# 3. trailing spaces +# 4. missing space between keyword and parenthesis, e.g.: for(, if(, while( +# 5. Missing space between right parenthesis and brace, e.g. 'for (...){' +# 6. opening brace on its own line. It should always be on the same line as the +# if/while/for/do statement. +# +# Invoke as: tools/check-style.sh +# + +check_style_errors=0 +IFS=$'\n' + +found="$( GREP_COLORS='mt=41' GREP_COLOR='41' grep $'\t' include tests/*.{cpp,py,h} docs/*.rst -rn --color=always )" +if [ -n "$found" ]; then + # The mt=41 sets a red background for matched tabs: + echo -e '\033[31;01mError: found tab characters in the following files:\033[0m' + check_style_errors=1 + echo "$found" | sed -e 's/^/ /' +fi + + +found="$( grep -IUlr $'\r' include tests/*.{cpp,py,h} docs/*.rst --color=always )" +if [ -n "$found" ]; then + echo -e '\033[31;01mError: found CRLF characters in the following files:\033[0m' + check_style_errors=1 + echo "$found" | sed -e 's/^/ /' +fi + +found="$(GREP_COLORS='mt=41' GREP_COLOR='41' grep '[[:blank:]]\+$' include tests/*.{cpp,py,h} docs/*.rst -rn --color=always )" +if [ -n "$found" ]; then + # The mt=41 sets a red background for matched trailing spaces + echo -e '\033[31;01mError: found trailing spaces in the following files:\033[0m' + check_style_errors=1 + echo "$found" | sed -e 's/^/ /' +fi + +found="$(grep '\<\(if\|for\|while\|catch\)(\|){' include tests/*.{cpp,h} -rn --color=always)" +if [ -n "$found" ]; then + echo -e '\033[31;01mError: found the following coding style problems:\033[0m' + check_style_errors=1 + echo "$found" | sed -e 's/^/ /' +fi + +found="$(awk ' +function prefix(filename, lineno) { + return " \033[35m" filename "\033[36m:\033[32m" lineno "\033[36m:\033[0m" +} +function mark(pattern, string) { sub(pattern, "\033[01;31m&\033[0m", string); return string } +last && /^\s*{/ { + print prefix(FILENAME, FNR-1) mark("\\)\\s*$", last) + print prefix(FILENAME, FNR) mark("^\\s*{", $0) + last="" +} +{ last = /(if|for|while|catch|switch)\s*\(.*\)\s*$/ ? $0 : "" } +' $(find include -type f) tests/*.{cpp,h} docs/*.rst)" +if [ -n "$found" ]; then + check_style_errors=1 + echo -e '\033[31;01mError: braces should occur on the same line as the if/while/.. statement. Found issues in the following files:\033[0m' + echo "$found" +fi + +exit $check_style_errors diff --git a/wrap/python/pybind11/tools/libsize.py b/wrap/python/pybind11/tools/libsize.py new file mode 100644 index 000000000..5dcb8b0d0 --- /dev/null +++ b/wrap/python/pybind11/tools/libsize.py @@ -0,0 +1,38 @@ +from __future__ import print_function, division +import os +import sys + +# Internal build script for generating debugging test .so size. +# Usage: +# python libsize.py file.so save.txt -- displays the size of file.so and, if save.txt exists, compares it to the +# size in it, then overwrites save.txt with the new size for future runs. + +if len(sys.argv) != 3: + sys.exit("Invalid arguments: usage: python libsize.py file.so save.txt") + +lib = sys.argv[1] +save = sys.argv[2] + +if not os.path.exists(lib): + sys.exit("Error: requested file ({}) does not exist".format(lib)) + +libsize = os.path.getsize(lib) + +print("------", os.path.basename(lib), "file size:", libsize, end='') + +if os.path.exists(save): + with open(save) as sf: + oldsize = int(sf.readline()) + + if oldsize > 0: + change = libsize - oldsize + if change == 0: + print(" (no change)") + else: + print(" (change of {:+} bytes = {:+.2%})".format(change, change / oldsize)) +else: + print() + +with open(save, 'w') as sf: + sf.write(str(libsize)) + diff --git a/wrap/python/pybind11/tools/mkdoc.py b/wrap/python/pybind11/tools/mkdoc.py new file mode 100755 index 000000000..44164af3d --- /dev/null +++ b/wrap/python/pybind11/tools/mkdoc.py @@ -0,0 +1,379 @@ +#!/usr/bin/env python3 +# +# Syntax: mkdoc.py [-I ..] [.. a list of header files ..] +# +# Extract documentation from C++ header files to use it in Python bindings +# + +import os +import sys +import platform +import re +import textwrap + +from clang import cindex +from clang.cindex import CursorKind +from collections import OrderedDict +from glob import glob +from threading import Thread, Semaphore +from multiprocessing import cpu_count + +RECURSE_LIST = [ + CursorKind.TRANSLATION_UNIT, + CursorKind.NAMESPACE, + CursorKind.CLASS_DECL, + CursorKind.STRUCT_DECL, + CursorKind.ENUM_DECL, + CursorKind.CLASS_TEMPLATE +] + +PRINT_LIST = [ + CursorKind.CLASS_DECL, + CursorKind.STRUCT_DECL, + CursorKind.ENUM_DECL, + CursorKind.ENUM_CONSTANT_DECL, + CursorKind.CLASS_TEMPLATE, + CursorKind.FUNCTION_DECL, + CursorKind.FUNCTION_TEMPLATE, + CursorKind.CONVERSION_FUNCTION, + CursorKind.CXX_METHOD, + CursorKind.CONSTRUCTOR, + CursorKind.FIELD_DECL +] + +PREFIX_BLACKLIST = [ + CursorKind.TRANSLATION_UNIT +] + +CPP_OPERATORS = { + '<=': 'le', '>=': 'ge', '==': 'eq', '!=': 'ne', '[]': 'array', + '+=': 'iadd', '-=': 'isub', '*=': 'imul', '/=': 'idiv', '%=': + 'imod', '&=': 'iand', '|=': 'ior', '^=': 'ixor', '<<=': 'ilshift', + '>>=': 'irshift', '++': 'inc', '--': 'dec', '<<': 'lshift', '>>': + 'rshift', '&&': 'land', '||': 'lor', '!': 'lnot', '~': 'bnot', + '&': 'band', '|': 'bor', '+': 'add', '-': 'sub', '*': 'mul', '/': + 'div', '%': 'mod', '<': 'lt', '>': 'gt', '=': 'assign', '()': 'call' +} + +CPP_OPERATORS = OrderedDict( + sorted(CPP_OPERATORS.items(), key=lambda t: -len(t[0]))) + +job_count = cpu_count() +job_semaphore = Semaphore(job_count) + + +class NoFilenamesError(ValueError): + pass + + +def d(s): + return s if isinstance(s, str) else s.decode('utf8') + + +def sanitize_name(name): + name = re.sub(r'type-parameter-0-([0-9]+)', r'T\1', name) + for k, v in CPP_OPERATORS.items(): + name = name.replace('operator%s' % k, 'operator_%s' % v) + name = re.sub('<.*>', '', name) + name = ''.join([ch if ch.isalnum() else '_' for ch in name]) + name = re.sub('_$', '', re.sub('_+', '_', name)) + return '__doc_' + name + + +def process_comment(comment): + result = '' + + # Remove C++ comment syntax + leading_spaces = float('inf') + for s in comment.expandtabs(tabsize=4).splitlines(): + s = s.strip() + if s.startswith('/*'): + s = s[2:].lstrip('*') + elif s.endswith('*/'): + s = s[:-2].rstrip('*') + elif s.startswith('///'): + s = s[3:] + if s.startswith('*'): + s = s[1:] + if len(s) > 0: + leading_spaces = min(leading_spaces, len(s) - len(s.lstrip())) + result += s + '\n' + + if leading_spaces != float('inf'): + result2 = "" + for s in result.splitlines(): + result2 += s[leading_spaces:] + '\n' + result = result2 + + # Doxygen tags + cpp_group = '([\w:]+)' + param_group = '([\[\w:\]]+)' + + s = result + s = re.sub(r'\\c\s+%s' % cpp_group, r'``\1``', s) + s = re.sub(r'\\a\s+%s' % cpp_group, r'*\1*', s) + s = re.sub(r'\\e\s+%s' % cpp_group, r'*\1*', s) + s = re.sub(r'\\em\s+%s' % cpp_group, r'*\1*', s) + s = re.sub(r'\\b\s+%s' % cpp_group, r'**\1**', s) + s = re.sub(r'\\ingroup\s+%s' % cpp_group, r'', s) + s = re.sub(r'\\param%s?\s+%s' % (param_group, cpp_group), + r'\n\n$Parameter ``\2``:\n\n', s) + s = re.sub(r'\\tparam%s?\s+%s' % (param_group, cpp_group), + r'\n\n$Template parameter ``\2``:\n\n', s) + + for in_, out_ in { + 'return': 'Returns', + 'author': 'Author', + 'authors': 'Authors', + 'copyright': 'Copyright', + 'date': 'Date', + 'remark': 'Remark', + 'sa': 'See also', + 'see': 'See also', + 'extends': 'Extends', + 'throw': 'Throws', + 'throws': 'Throws' + }.items(): + s = re.sub(r'\\%s\s*' % in_, r'\n\n$%s:\n\n' % out_, s) + + s = re.sub(r'\\details\s*', r'\n\n', s) + s = re.sub(r'\\brief\s*', r'', s) + s = re.sub(r'\\short\s*', r'', s) + s = re.sub(r'\\ref\s*', r'', s) + + s = re.sub(r'\\code\s?(.*?)\s?\\endcode', + r"```\n\1\n```\n", s, flags=re.DOTALL) + + # HTML/TeX tags + s = re.sub(r'(.*?)', r'``\1``', s, flags=re.DOTALL) + s = re.sub(r'
(.*?)
', r"```\n\1\n```\n", s, flags=re.DOTALL) + s = re.sub(r'(.*?)', r'*\1*', s, flags=re.DOTALL) + s = re.sub(r'(.*?)', r'**\1**', s, flags=re.DOTALL) + s = re.sub(r'\\f\$(.*?)\\f\$', r'$\1$', s, flags=re.DOTALL) + s = re.sub(r'
  • ', r'\n\n* ', s) + s = re.sub(r'', r'', s) + s = re.sub(r'
  • ', r'\n\n', s) + + s = s.replace('``true``', '``True``') + s = s.replace('``false``', '``False``') + + # Re-flow text + wrapper = textwrap.TextWrapper() + wrapper.expand_tabs = True + wrapper.replace_whitespace = True + wrapper.drop_whitespace = True + wrapper.width = 70 + wrapper.initial_indent = wrapper.subsequent_indent = '' + + result = '' + in_code_segment = False + for x in re.split(r'(```)', s): + if x == '```': + if not in_code_segment: + result += '```\n' + else: + result += '\n```\n\n' + in_code_segment = not in_code_segment + elif in_code_segment: + result += x.strip() + else: + for y in re.split(r'(?: *\n *){2,}', x): + wrapped = wrapper.fill(re.sub(r'\s+', ' ', y).strip()) + if len(wrapped) > 0 and wrapped[0] == '$': + result += wrapped[1:] + '\n' + wrapper.initial_indent = \ + wrapper.subsequent_indent = ' ' * 4 + else: + if len(wrapped) > 0: + result += wrapped + '\n\n' + wrapper.initial_indent = wrapper.subsequent_indent = '' + return result.rstrip().lstrip('\n') + + +def extract(filename, node, prefix, output): + if not (node.location.file is None or + os.path.samefile(d(node.location.file.name), filename)): + return 0 + if node.kind in RECURSE_LIST: + sub_prefix = prefix + if node.kind not in PREFIX_BLACKLIST: + if len(sub_prefix) > 0: + sub_prefix += '_' + sub_prefix += d(node.spelling) + for i in node.get_children(): + extract(filename, i, sub_prefix, output) + if node.kind in PRINT_LIST: + comment = d(node.raw_comment) if node.raw_comment is not None else '' + comment = process_comment(comment) + sub_prefix = prefix + if len(sub_prefix) > 0: + sub_prefix += '_' + if len(node.spelling) > 0: + name = sanitize_name(sub_prefix + d(node.spelling)) + output.append((name, filename, comment)) + + +class ExtractionThread(Thread): + def __init__(self, filename, parameters, output): + Thread.__init__(self) + self.filename = filename + self.parameters = parameters + self.output = output + job_semaphore.acquire() + + def run(self): + print('Processing "%s" ..' % self.filename, file=sys.stderr) + try: + index = cindex.Index( + cindex.conf.lib.clang_createIndex(False, True)) + tu = index.parse(self.filename, self.parameters) + extract(self.filename, tu.cursor, '', self.output) + finally: + job_semaphore.release() + + +def read_args(args): + parameters = [] + filenames = [] + if "-x" not in args: + parameters.extend(['-x', 'c++']) + if not any(it.startswith("-std=") for it in args): + parameters.append('-std=c++11') + + if platform.system() == 'Darwin': + dev_path = '/Applications/Xcode.app/Contents/Developer/' + lib_dir = dev_path + 'Toolchains/XcodeDefault.xctoolchain/usr/lib/' + sdk_dir = dev_path + 'Platforms/MacOSX.platform/Developer/SDKs' + libclang = lib_dir + 'libclang.dylib' + + if os.path.exists(libclang): + cindex.Config.set_library_path(os.path.dirname(libclang)) + + if os.path.exists(sdk_dir): + sysroot_dir = os.path.join(sdk_dir, next(os.walk(sdk_dir))[1][0]) + parameters.append('-isysroot') + parameters.append(sysroot_dir) + elif platform.system() == 'Linux': + # clang doesn't find its own base includes by default on Linux, + # but different distros install them in different paths. + # Try to autodetect, preferring the highest numbered version. + def clang_folder_version(d): + return [int(ver) for ver in re.findall(r'(?:${PYBIND11_CPP_STANDARD}>) + endif() + + get_property(_iid TARGET ${PN}::pybind11 PROPERTY INTERFACE_INCLUDE_DIRECTORIES) + get_property(_ill TARGET ${PN}::module PROPERTY INTERFACE_LINK_LIBRARIES) + set(${PN}_INCLUDE_DIRS ${_iid}) + set(${PN}_LIBRARIES ${_ico} ${_ill}) +endif() +endif() diff --git a/wrap/python/pybind11/tools/pybind11Tools.cmake b/wrap/python/pybind11/tools/pybind11Tools.cmake new file mode 100644 index 000000000..e3ec572b5 --- /dev/null +++ b/wrap/python/pybind11/tools/pybind11Tools.cmake @@ -0,0 +1,227 @@ +# tools/pybind11Tools.cmake -- Build system for the pybind11 modules +# +# Copyright (c) 2015 Wenzel Jakob +# +# All rights reserved. Use of this source code is governed by a +# BSD-style license that can be found in the LICENSE file. + +cmake_minimum_required(VERSION 2.8.12) + +# Add a CMake parameter for choosing a desired Python version +if(NOT PYBIND11_PYTHON_VERSION) + set(PYBIND11_PYTHON_VERSION "" CACHE STRING "Python version to use for compiling modules") +endif() + +set(Python_ADDITIONAL_VERSIONS 3.7 3.6 3.5 3.4) +find_package(PythonLibsNew ${PYBIND11_PYTHON_VERSION} REQUIRED) + +include(CheckCXXCompilerFlag) +include(CMakeParseArguments) + +if(NOT PYBIND11_CPP_STANDARD AND NOT CMAKE_CXX_STANDARD) + if(NOT MSVC) + check_cxx_compiler_flag("-std=c++14" HAS_CPP14_FLAG) + + if (HAS_CPP14_FLAG) + set(PYBIND11_CPP_STANDARD -std=c++14) + else() + check_cxx_compiler_flag("-std=c++11" HAS_CPP11_FLAG) + if (HAS_CPP11_FLAG) + set(PYBIND11_CPP_STANDARD -std=c++11) + else() + message(FATAL_ERROR "Unsupported compiler -- pybind11 requires C++11 support!") + endif() + endif() + elseif(MSVC) + set(PYBIND11_CPP_STANDARD /std:c++14) + endif() + + set(PYBIND11_CPP_STANDARD ${PYBIND11_CPP_STANDARD} CACHE STRING + "C++ standard flag, e.g. -std=c++11, -std=c++14, /std:c++14. Defaults to C++14 mode." FORCE) +endif() + +# Checks whether the given CXX/linker flags can compile and link a cxx file. cxxflags and +# linkerflags are lists of flags to use. The result variable is a unique variable name for each set +# of flags: the compilation result will be cached base on the result variable. If the flags work, +# sets them in cxxflags_out/linkerflags_out internal cache variables (in addition to ${result}). +function(_pybind11_return_if_cxx_and_linker_flags_work result cxxflags linkerflags cxxflags_out linkerflags_out) + set(CMAKE_REQUIRED_LIBRARIES ${linkerflags}) + check_cxx_compiler_flag("${cxxflags}" ${result}) + if (${result}) + set(${cxxflags_out} "${cxxflags}" CACHE INTERNAL "" FORCE) + set(${linkerflags_out} "${linkerflags}" CACHE INTERNAL "" FORCE) + endif() +endfunction() + +# Internal: find the appropriate link time optimization flags for this compiler +function(_pybind11_add_lto_flags target_name prefer_thin_lto) + if (NOT DEFINED PYBIND11_LTO_CXX_FLAGS) + set(PYBIND11_LTO_CXX_FLAGS "" CACHE INTERNAL "") + set(PYBIND11_LTO_LINKER_FLAGS "" CACHE INTERNAL "") + + if(CMAKE_CXX_COMPILER_ID MATCHES "GNU|Clang") + set(cxx_append "") + set(linker_append "") + if (CMAKE_CXX_COMPILER_ID MATCHES "Clang" AND NOT APPLE) + # Clang Gold plugin does not support -Os; append -O3 to MinSizeRel builds to override it + set(linker_append ";$<$:-O3>") + elseif(CMAKE_CXX_COMPILER_ID MATCHES "GNU") + set(cxx_append ";-fno-fat-lto-objects") + endif() + + if (CMAKE_CXX_COMPILER_ID MATCHES "Clang" AND prefer_thin_lto) + _pybind11_return_if_cxx_and_linker_flags_work(HAS_FLTO_THIN + "-flto=thin${cxx_append}" "-flto=thin${linker_append}" + PYBIND11_LTO_CXX_FLAGS PYBIND11_LTO_LINKER_FLAGS) + endif() + + if (NOT HAS_FLTO_THIN) + _pybind11_return_if_cxx_and_linker_flags_work(HAS_FLTO + "-flto${cxx_append}" "-flto${linker_append}" + PYBIND11_LTO_CXX_FLAGS PYBIND11_LTO_LINKER_FLAGS) + endif() + elseif (CMAKE_CXX_COMPILER_ID MATCHES "Intel") + # Intel equivalent to LTO is called IPO + _pybind11_return_if_cxx_and_linker_flags_work(HAS_INTEL_IPO + "-ipo" "-ipo" PYBIND11_LTO_CXX_FLAGS PYBIND11_LTO_LINKER_FLAGS) + elseif(MSVC) + # cmake only interprets libraries as linker flags when they start with a - (otherwise it + # converts /LTCG to \LTCG as if it was a Windows path). Luckily MSVC supports passing flags + # with - instead of /, even if it is a bit non-standard: + _pybind11_return_if_cxx_and_linker_flags_work(HAS_MSVC_GL_LTCG + "/GL" "-LTCG" PYBIND11_LTO_CXX_FLAGS PYBIND11_LTO_LINKER_FLAGS) + endif() + + if (PYBIND11_LTO_CXX_FLAGS) + message(STATUS "LTO enabled") + else() + message(STATUS "LTO disabled (not supported by the compiler and/or linker)") + endif() + endif() + + # Enable LTO flags if found, except for Debug builds + if (PYBIND11_LTO_CXX_FLAGS) + target_compile_options(${target_name} PRIVATE "$<$>:${PYBIND11_LTO_CXX_FLAGS}>") + endif() + if (PYBIND11_LTO_LINKER_FLAGS) + target_link_libraries(${target_name} PRIVATE "$<$>:${PYBIND11_LTO_LINKER_FLAGS}>") + endif() +endfunction() + +# Build a Python extension module: +# pybind11_add_module( [MODULE | SHARED] [EXCLUDE_FROM_ALL] +# [NO_EXTRAS] [SYSTEM] [THIN_LTO] source1 [source2 ...]) +# +function(pybind11_add_module target_name) + set(options MODULE SHARED EXCLUDE_FROM_ALL NO_EXTRAS SYSTEM THIN_LTO) + cmake_parse_arguments(ARG "${options}" "" "" ${ARGN}) + + if(ARG_MODULE AND ARG_SHARED) + message(FATAL_ERROR "Can't be both MODULE and SHARED") + elseif(ARG_SHARED) + set(lib_type SHARED) + else() + set(lib_type MODULE) + endif() + + if(ARG_EXCLUDE_FROM_ALL) + set(exclude_from_all EXCLUDE_FROM_ALL) + endif() + + add_library(${target_name} ${lib_type} ${exclude_from_all} ${ARG_UNPARSED_ARGUMENTS}) + + if(ARG_SYSTEM) + set(inc_isystem SYSTEM) + endif() + + target_include_directories(${target_name} ${inc_isystem} + PRIVATE ${PYBIND11_INCLUDE_DIR} # from project CMakeLists.txt + PRIVATE ${pybind11_INCLUDE_DIR} # from pybind11Config + PRIVATE ${PYTHON_INCLUDE_DIRS}) + + # Python debug libraries expose slightly different objects + # https://docs.python.org/3.6/c-api/intro.html#debugging-builds + # https://stackoverflow.com/questions/39161202/how-to-work-around-missing-pymodule-create2-in-amd64-win-python35-d-lib + if(PYTHON_IS_DEBUG) + target_compile_definitions(${target_name} PRIVATE Py_DEBUG) + endif() + + # The prefix and extension are provided by FindPythonLibsNew.cmake + set_target_properties(${target_name} PROPERTIES PREFIX "${PYTHON_MODULE_PREFIX}") + set_target_properties(${target_name} PROPERTIES SUFFIX "${PYTHON_MODULE_EXTENSION}") + + # -fvisibility=hidden is required to allow multiple modules compiled against + # different pybind versions to work properly, and for some features (e.g. + # py::module_local). We force it on everything inside the `pybind11` + # namespace; also turning it on for a pybind module compilation here avoids + # potential warnings or issues from having mixed hidden/non-hidden types. + set_target_properties(${target_name} PROPERTIES CXX_VISIBILITY_PRESET "hidden") + set_target_properties(${target_name} PROPERTIES CUDA_VISIBILITY_PRESET "hidden") + + if(WIN32 OR CYGWIN) + # Link against the Python shared library on Windows + target_link_libraries(${target_name} PRIVATE ${PYTHON_LIBRARIES}) + elseif(APPLE) + # It's quite common to have multiple copies of the same Python version + # installed on one's system. E.g.: one copy from the OS and another copy + # that's statically linked into an application like Blender or Maya. + # If we link our plugin library against the OS Python here and import it + # into Blender or Maya later on, this will cause segfaults when multiple + # conflicting Python instances are active at the same time (even when they + # are of the same version). + + # Windows is not affected by this issue since it handles DLL imports + # differently. The solution for Linux and Mac OS is simple: we just don't + # link against the Python library. The resulting shared library will have + # missing symbols, but that's perfectly fine -- they will be resolved at + # import time. + + target_link_libraries(${target_name} PRIVATE "-undefined dynamic_lookup") + + if(ARG_SHARED) + # Suppress CMake >= 3.0 warning for shared libraries + set_target_properties(${target_name} PROPERTIES MACOSX_RPATH ON) + endif() + endif() + + # Make sure C++11/14 are enabled + if(CMAKE_VERSION VERSION_LESS 3.3) + target_compile_options(${target_name} PUBLIC ${PYBIND11_CPP_STANDARD}) + else() + target_compile_options(${target_name} PUBLIC $<$:${PYBIND11_CPP_STANDARD}>) + endif() + + if(ARG_NO_EXTRAS) + return() + endif() + + _pybind11_add_lto_flags(${target_name} ${ARG_THIN_LTO}) + + if (NOT MSVC AND NOT ${CMAKE_BUILD_TYPE} MATCHES Debug) + # Strip unnecessary sections of the binary on Linux/Mac OS + if(CMAKE_STRIP) + if(APPLE) + add_custom_command(TARGET ${target_name} POST_BUILD + COMMAND ${CMAKE_STRIP} -x $) + else() + add_custom_command(TARGET ${target_name} POST_BUILD + COMMAND ${CMAKE_STRIP} $) + endif() + endif() + endif() + + if(MSVC) + # /MP enables multithreaded builds (relevant when there are many files), /bigobj is + # needed for bigger binding projects due to the limit to 64k addressable sections + target_compile_options(${target_name} PRIVATE /bigobj) + if(CMAKE_VERSION VERSION_LESS 3.11) + target_compile_options(${target_name} PRIVATE $<$>:/MP>) + else() + # Only set these options for C++ files. This is important so that, for + # instance, projects that include other types of source files like CUDA + # .cu files don't get these options propagated to nvcc since that would + # cause the build to fail. + target_compile_options(${target_name} PRIVATE $<$>:$<$:/MP>>) + endif() + endif() +endfunction() From 906d0277e93b43f5160c7a18df6e83a5990d1ce9 Mon Sep 17 00:00:00 2001 From: Thomas Jespersen Date: Mon, 16 Mar 2020 00:48:36 +0800 Subject: [PATCH 006/869] Added ported C++ version of ISAM2 Kitti example --- examples/IMUKittiExampleGPS.cpp | 293 ++++++++++++++++++++++++++++++++ 1 file changed, 293 insertions(+) create mode 100644 examples/IMUKittiExampleGPS.cpp diff --git a/examples/IMUKittiExampleGPS.cpp b/examples/IMUKittiExampleGPS.cpp new file mode 100644 index 000000000..9f302ab2f --- /dev/null +++ b/examples/IMUKittiExampleGPS.cpp @@ -0,0 +1,293 @@ +/* ---------------------------------------------------------------------------- + + * GTSAM Copyright 2010, Georgia Tech Research Corporation, + * Atlanta, Georgia 30332-0415 + * All Rights Reserved + * Authors: Frank Dellaert, et al. (see THANKS for the full author list) + + * See LICENSE for the license information + + * -------------------------------------------------------------------------- */ + +/** + * @file IMUKittiExampleGPS + * @brief Example of application of ISAM2 for GPS-aided navigation on the KITTI VISION BENCHMARK SUITE + * @author Ported by Thomas Jespersen (thomasj@tkjelectronics.dk), TKJ Electronics + */ + +// GTSAM related includes. +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +using namespace gtsam; +using namespace std; + +using symbol_shorthand::X; // Pose3 (x,y,z,r,p,y) +using symbol_shorthand::V; // Vel (xdot,ydot,zdot) +using symbol_shorthand::B; // Bias (ax,ay,az,gx,gy,gz) + +typedef struct { + double Time; + double dt; + Vector3 Accelerometer; + Vector3 Gyroscope; // omega +} imuMeasurement_t; + +typedef struct { + double Time; + Vector3 Position; // x,y,z +} gpsMeasurement_t; + +const string output_filename = "IMUKittyExampleGPSResults.csv"; + +int main(int argc, char* argv[]) +{ + string line; + + // Read IMU metadata and compute relative sensor pose transforms + // BodyPtx BodyPty BodyPtz BodyPrx BodyPry BodyPrz AccelerometerSigma GyroscopeSigma IntegrationSigma AccelerometerBiasSigma GyroscopeBiasSigma AverageDeltaT + // 0 0 0 0 0 0 0.01 0.000175 0 0.000167 2.91e-006 0.0100395199348279 + string IMU_metadata_file = findExampleDataFile("KittiEquivBiasedImu_metadata.txt"); + ifstream IMU_metadata(IMU_metadata_file.c_str()); + + printf("-- Reading sensor metadata\n"); + + getline(IMU_metadata, line, '\n'); // ignore the first line + + double BodyPtx, BodyPty, BodyPtz, BodyPrx, BodyPry, BodyPrz, AccelerometerSigma, GyroscopeSigma, IntegrationSigma, AccelerometerBiasSigma, GyroscopeBiasSigma, AverageDeltaT; + getline(IMU_metadata, line, '\n'); + sscanf(line.c_str(), "%lf %lf %lf %lf %lf %lf %lf %lf %lf %lf %lf %lf", &BodyPtx, &BodyPty, &BodyPtz, &BodyPrx, &BodyPry, &BodyPrz, &AccelerometerSigma, &GyroscopeSigma, &IntegrationSigma, &AccelerometerBiasSigma, &GyroscopeBiasSigma, &AverageDeltaT); + printf("IMU metadata: %lf %lf %lf %lf %lf %lf %lf %lf %lf %lf %lf %lf\n", BodyPtx, BodyPty, BodyPtz, BodyPrx, BodyPry, BodyPrz, AccelerometerSigma, GyroscopeSigma, IntegrationSigma, AccelerometerBiasSigma, GyroscopeBiasSigma, AverageDeltaT); + + Vector6 BodyP = (Vector(6) << BodyPtx, BodyPty, BodyPtz, BodyPrx, BodyPry, BodyPrz).finished(); + auto body_T_imu = Pose3::Expmap(BodyP); + if (!body_T_imu.equals(Pose3(), 1e-5)) { + printf("Currently only support IMUinBody is identity, i.e. IMU and body frame are the same"); + exit(-1); + } + + // Read IMU data + // Time dt accelX accelY accelZ omegaX omegaY omegaZ + // 46534.47837579 46534.47837579 1.7114864219577 0.1717911743144 9.80533438749 -0.0032006241515747 0.031231284764596 -0.0063569265706488 + vector IMU_measurements; + string IMU_data_file = findExampleDataFile("KittiEquivBiasedImu.txt"); + + printf("-- Reading IMU measurements from file\n"); + { + ifstream IMU_data(IMU_data_file.c_str()); + getline(IMU_data, line, '\n'); // ignore the first line + + double time = 0, dt = 0, acc_x = 0, acc_y = 0, acc_z = 0, gyro_x = 0, gyro_y = 0, gyro_z = 0; + while (!IMU_data.eof()) { + getline(IMU_data, line, '\n'); + sscanf(line.c_str(), "%lf %lf %lf %lf %lf %lf %lf %lf", &time, &dt, &acc_x, &acc_y, &acc_z, &gyro_x, + &gyro_y, &gyro_z); + + imuMeasurement_t measurement; + measurement.Time = time; + measurement.dt = dt; + measurement.Accelerometer = Vector3(acc_x, acc_y, acc_z); + measurement.Gyroscope = Vector3(gyro_x, gyro_y, gyro_z); + IMU_measurements.push_back(measurement); + } + } + + // Read GPS data + // Time,X,Y,Z + // 46534.478375790000428,-6.8269361350059405424,-11.868164241239471224,0.040306091310000624617 + vector GPS_measurements; + string GPS_data_file = findExampleDataFile("KittiGps_converted.txt"); + + printf("-- Reading GPS measurements from file\n"); + { + ifstream GPS_data(GPS_data_file.c_str()); + getline(GPS_data, line, '\n'); // ignore the first line + + double time = 0, gps_x = 0, gps_y = 0, gps_z = 0; + while (!GPS_data.eof()) { + getline(GPS_data, line, '\n'); + sscanf(line.c_str(), "%lf,%lf,%lf,%lf", &time, &gps_x, &gps_y, &gps_z); + + gpsMeasurement_t measurement; + measurement.Time = time; + measurement.Position = Vector3(gps_x, gps_y, gps_z); + GPS_measurements.push_back(measurement); + } + } + + // Configure different variables + double tOffset = GPS_measurements[0].Time; + size_t firstGPSPose = 1; + size_t GPSskip = 10; // Skip this many GPS measurements each time + double g = 9.8; + auto w_coriolis = Vector3(); // zero vector + + // Configure noise models + noiseModel::Diagonal::shared_ptr noiseModelGPS = noiseModel::Diagonal::Precisions((Vector(6) << Vector3::Constant(0), Vector3::Constant(1.0/0.07)).finished()); + + // Set initial conditions for the estimated trajectory + auto currentPoseGlobal = Pose3(Rot3(), GPS_measurements[firstGPSPose].Position); // initial pose is the reference frame (navigation frame) + auto currentVelocityGlobal = Vector3(); // the vehicle is stationary at the beginning at position 0,0,0 + auto currentBias = imuBias::ConstantBias(); // init with zero bias + + noiseModel::Diagonal::shared_ptr sigma_init_x = noiseModel::Isotropic::Precisions((Vector(6) << Vector3::Constant(0), Vector3::Constant(1.0)).finished()); + noiseModel::Diagonal::shared_ptr sigma_init_v = noiseModel::Isotropic::Sigma(3, 1000.0); + noiseModel::Diagonal::shared_ptr sigma_init_b = noiseModel::Isotropic::Sigmas((Vector(6) << Vector3::Constant(0.100), Vector3::Constant(5.00e-05)).finished()); + + // Set IMU preintegration parameters + Matrix33 measured_acc_cov = Matrix33::Identity(3,3) * pow(AccelerometerSigma,2); + Matrix33 measured_omega_cov = Matrix33::Identity(3,3) * pow(GyroscopeSigma,2); + Matrix33 integration_error_cov = Matrix33::Identity(3,3) * pow(IntegrationSigma,2); // error committed in integrating position from velocities + + boost::shared_ptr IMU_params = PreintegratedImuMeasurements::Params::MakeSharedU(g); + IMU_params->accelerometerCovariance = measured_acc_cov; // acc white noise in continuous + IMU_params->integrationCovariance = integration_error_cov; // integration uncertainty continuous + IMU_params->gyroscopeCovariance = measured_omega_cov; // gyro white noise in continuous + IMU_params->omegaCoriolis = w_coriolis; + + std::shared_ptr currentSummarizedMeasurement = nullptr; + + // Set ISAM2 parameters and create ISAM2 solver object + ISAM2Params isamParams; + isamParams.factorization = ISAM2Params::CHOLESKY; + isamParams.relinearizeSkip = 10; + + ISAM2 isam(isamParams); + + // Create the factor graph and values object that will store new factors and values to add to the incremental graph + NonlinearFactorGraph newFactors; + Values newValues; // values storing the initial estimates of new nodes in the factor graph + + /// Main loop: + /// (1) we read the measurements + /// (2) we create the corresponding factors in the graph + /// (3) we solve the graph to obtain and optimal estimate of robot trajectory + printf("-- Starting main loop: inference is performed at each time step, but we plot trajectory every 10 steps\n"); + size_t imuMeasurementIndex = 0; + for (size_t gpsMeasurementIndex = firstGPSPose; gpsMeasurementIndex < GPS_measurements.size() - 1; gpsMeasurementIndex++) { + // At each non=IMU measurement we initialize a new node in the graph + auto currentPoseKey = X(gpsMeasurementIndex); + auto currentVelKey = V(gpsMeasurementIndex); + auto currentBiasKey = B(gpsMeasurementIndex); + double t = GPS_measurements[gpsMeasurementIndex].Time; + + if (gpsMeasurementIndex == firstGPSPose) { + // Create initial estimate and prior on initial pose, velocity, and biases + newValues.insert(currentPoseKey, currentPoseGlobal); + newValues.insert(currentVelKey, currentVelocityGlobal); + newValues.insert(currentBiasKey, currentBias); + newFactors.add(PriorFactor(currentPoseKey, currentPoseGlobal, sigma_init_x)); + newFactors.add(PriorFactor(currentVelKey, currentVelocityGlobal, sigma_init_v)); + newFactors.add(PriorFactor(currentBiasKey, currentBias, sigma_init_b)); + } else { + double t_previous = GPS_measurements[gpsMeasurementIndex-1].Time; + + // Summarize IMU data between the previous GPS measurement and now + currentSummarizedMeasurement = std::make_shared(IMU_params, currentBias); + static size_t includedIMUmeasurementCount = 0; + while (imuMeasurementIndex < IMU_measurements.size() && IMU_measurements[imuMeasurementIndex].Time <= t) { + if (IMU_measurements[imuMeasurementIndex].Time >= t_previous) { + currentSummarizedMeasurement->integrateMeasurement(IMU_measurements[imuMeasurementIndex].Accelerometer, IMU_measurements[imuMeasurementIndex].Gyroscope, IMU_measurements[imuMeasurementIndex].dt); + includedIMUmeasurementCount++; + } + imuMeasurementIndex++; + } + + // Create IMU factor + auto previousPoseKey = X(gpsMeasurementIndex-1); + auto previousVelKey = V(gpsMeasurementIndex-1); + auto previousBiasKey = B(gpsMeasurementIndex-1); + + newFactors.add(ImuFactor( + previousPoseKey, previousVelKey, + currentPoseKey, currentVelKey, + previousBiasKey, *currentSummarizedMeasurement)); + + // Bias evolution as given in the IMU metadata + noiseModel::Diagonal::shared_ptr sigma_between_b = noiseModel::Diagonal::Sigmas((Vector(6) << Vector3::Constant(sqrt(includedIMUmeasurementCount) * AccelerometerBiasSigma), Vector3::Constant(sqrt(includedIMUmeasurementCount) * GyroscopeBiasSigma)).finished()); + newFactors.add(BetweenFactor(previousBiasKey, currentBiasKey, imuBias::ConstantBias(), sigma_between_b)); + + // Create GPS factor + auto GPSPose = Pose3(currentPoseGlobal.rotation(), GPS_measurements[gpsMeasurementIndex].Position); + if ((gpsMeasurementIndex % GPSskip) == 0) { + newFactors.add(PriorFactor(currentPoseKey, GPSPose, noiseModelGPS)); + newValues.insert(currentPoseKey, GPSPose); + + printf("################ POSE INCLUDED AT TIME %lf ################\n", t); + GPSPose.translation().print(); + printf("\n\n"); + } else { + newValues.insert(currentPoseKey, currentPoseGlobal); + } + + // Add initial values for velocity and bias based on the previous estimates + newValues.insert(currentVelKey, currentVelocityGlobal); + newValues.insert(currentBiasKey, currentBias); + + // Update solver + // ======================================================================= + // We accumulate 2*GPSskip GPS measurements before updating the solver at + //first so that the heading becomes observable. + if (gpsMeasurementIndex > (firstGPSPose + 2*GPSskip)) { + printf("################ NEW FACTORS AT TIME %lf ################\n", t); + newFactors.print(); + + isam.update(newFactors, newValues); + + // Reset the newFactors and newValues list + newFactors.resize(0); + newValues.clear(); + + // Extract the result/current estimates + Values result = isam.calculateEstimate(); + + currentPoseGlobal = result.at(currentPoseKey); + currentVelocityGlobal = result.at(currentVelKey); + currentBias = result.at(currentBiasKey); + + printf("\n################ POSE AT TIME %lf ################\n", t); + currentPoseGlobal.print(); + printf("\n\n"); + } + } + } + + // Save results to file + printf("\nWriting results to file...\n"); + FILE* fp_out = fopen(output_filename.c_str(), "w+"); + fprintf(fp_out, "#time(s),x(m),y(m),z(m),qx,qy,qz,qw,gt_x(m),gt_y(m),gt_z(m)\n"); + + Values result = isam.calculateEstimate(); + for (size_t gpsMeasurementIndex = firstGPSPose; gpsMeasurementIndex < GPS_measurements.size() - 1; gpsMeasurementIndex++) { + auto poseKey = X(gpsMeasurementIndex); + auto velKey = V(gpsMeasurementIndex); + auto biasKey = B(gpsMeasurementIndex); + + auto pose = result.at(poseKey); + auto velocity = result.at(velKey); + auto bias = result.at(biasKey); + + auto pose_quat = pose.rotation().toQuaternion(); + auto gps = GPS_measurements[gpsMeasurementIndex].Position; + + fprintf(fp_out, "%f,%f,%f,%f,%f,%f,%f,%f,%f,%f,%f\n", + GPS_measurements[gpsMeasurementIndex].Time, + pose.x(), pose.y(), pose.z(), + pose_quat.x(), pose_quat.y(), pose_quat.z(), pose_quat.w(), + gps(0), gps(1), gps(2)); + } + + fclose(fp_out); +} \ No newline at end of file From 221dcaa13ac427082e55b7b3b67c78b9eec396a1 Mon Sep 17 00:00:00 2001 From: kvmanohar22 Date: Mon, 30 Mar 2020 22:16:30 +0530 Subject: [PATCH 007/869] adding functionality to use ISAM2 for imu preintegration example --- examples/ImuFactorsExample.cpp | 29 ++++++++++++++++++++++++++++- 1 file changed, 28 insertions(+), 1 deletion(-) diff --git a/examples/ImuFactorsExample.cpp b/examples/ImuFactorsExample.cpp index e038f5117..bdeb99d0c 100644 --- a/examples/ImuFactorsExample.cpp +++ b/examples/ImuFactorsExample.cpp @@ -33,6 +33,8 @@ * optional arguments: * data_csv_path path to the CSV file with the IMU data. * -c use CombinedImuFactor + * Note: Define USE_LM to use Levenberg Marquardt Optimizer + * By default ISAM2 is used */ // GTSAM related includes. @@ -44,11 +46,15 @@ #include #include #include +#include #include #include #include #include +// Uncomment the following to use Levenberg Marquardt Optimizer +// #define USE_LM + using namespace gtsam; using namespace std; @@ -67,6 +73,17 @@ int main(int argc, char* argv[]) { string data_filename; bool use_combined_imu = false; + +#ifndef USE_LM + printf("Using ISAM2\n"); + ISAM2Params parameters; + parameters.relinearizeThreshold = 0.01; + parameters.relinearizeSkip = 1; + ISAM2 isam2(parameters); +#else + printf("Using Levenberg Marquardt Optimizer\n"); +#endif + if (argc < 2) { printf("using default CSV file\n"); data_filename = findExampleDataFile("imuAndGPSdata.csv"); @@ -248,9 +265,19 @@ int main(int argc, char* argv[]) initial_values.insert(V(correction_count), prop_state.v()); initial_values.insert(B(correction_count), prev_bias); + Values result; +#ifdef USE_LM LevenbergMarquardtOptimizer optimizer(*graph, initial_values); - Values result = optimizer.optimize(); + result = optimizer.optimize(); +#else + isam2.update(*graph, initial_values); + isam2.update(); + result = isam2.calculateEstimate(); + // reset the graph + graph->resize(0); + initial_values.clear(); +#endif // Overwrite the beginning of the preintegration for the next step. prev_state = NavState(result.at(X(correction_count)), result.at(V(correction_count))); From 201539680f6e2e1db00b6d2b49ceb1a8c9b8db4f Mon Sep 17 00:00:00 2001 From: yetongumich Date: Wed, 1 Apr 2020 20:07:49 -0400 Subject: [PATCH 008/869] remove distance in noisemodel, replace with error --- gtsam/linear/JacobianFactor.cpp | 2 +- gtsam/linear/NoiseModel.cpp | 4 ++-- gtsam/linear/NoiseModel.h | 19 ++++++++++++------- gtsam/linear/tests/testNoiseModel.cpp | 10 +++++----- gtsam/nonlinear/NonlinearFactor.cpp | 2 +- 5 files changed, 21 insertions(+), 16 deletions(-) diff --git a/gtsam/linear/JacobianFactor.cpp b/gtsam/linear/JacobianFactor.cpp index 2310d88f0..2e634190c 100644 --- a/gtsam/linear/JacobianFactor.cpp +++ b/gtsam/linear/JacobianFactor.cpp @@ -515,7 +515,7 @@ Vector JacobianFactor::error_vector(const VectorValues& c) const { double JacobianFactor::error(const VectorValues& c) const { Vector e = unweighted_error(c); // Use the noise model distance function to get the correct error if available. - if (model_) return 0.5 * model_->distance(e); + if (model_) return model_->error(e); return 0.5 * e.dot(e); } diff --git a/gtsam/linear/NoiseModel.cpp b/gtsam/linear/NoiseModel.cpp index 33f51e1f0..d1a03eb5b 100644 --- a/gtsam/linear/NoiseModel.cpp +++ b/gtsam/linear/NoiseModel.cpp @@ -369,12 +369,12 @@ Vector Constrained::whiten(const Vector& v) const { } /* ************************************************************************* */ -double Constrained::distance(const Vector& v) const { +double Constrained::error(const Vector& v) const { Vector w = Diagonal::whiten(v); // get noisemodel for constrained elements for (size_t i=0; i& A, Vector& b) const = 0; virtual void WhitenSystem(Matrix& A, Vector& b) const = 0; @@ -224,8 +229,8 @@ namespace gtsam { } #endif - inline virtual double distance(const Vector& v) const { - return SquaredMahalanobisDistance(v); + inline virtual double error(const Vector& v) const { + return 0.5 * SquaredMahalanobisDistance(v); } /** @@ -477,7 +482,7 @@ namespace gtsam { * for non-constrained versions, uses sigmas, otherwise * uses the penalty function with mu */ - virtual double distance(const Vector& v) const; + virtual double error(const Vector& v) const; /** Fully constrained variations */ static shared_ptr All(size_t dim) { @@ -705,11 +710,11 @@ namespace gtsam { { Vector b; Matrix B=A; this->WhitenSystem(B,b); return B; } inline virtual Vector unwhiten(const Vector& /*v*/) const { throw std::invalid_argument("unwhiten is not currently supported for robust noise models."); } - // Fold the use of the m-estimator loss(...) function into distance(...) - inline virtual double distance(const Vector& v) const + // Fold the use of the m-estimator loss(...) function into error(...) + inline virtual double error(const Vector& v) const { return robust_->loss(this->unweightedWhiten(v).norm()); } - inline virtual double distance_non_whitened(const Vector& v) const - { return robust_->loss(v.norm()); } + // inline virtual double distance_non_whitened(const Vector& v) const + // { return robust_->loss(v.norm()); } // TODO: these are really robust iterated re-weighting support functions virtual void WhitenSystem(Vector& b) const; virtual void WhitenSystem(std::vector& A, Vector& b) const; diff --git a/gtsam/linear/tests/testNoiseModel.cpp b/gtsam/linear/tests/testNoiseModel.cpp index 0290fc5d8..52e1eefee 100644 --- a/gtsam/linear/tests/testNoiseModel.cpp +++ b/gtsam/linear/tests/testNoiseModel.cpp @@ -182,8 +182,8 @@ TEST(NoiseModel, ConstrainedMixed ) EXPECT(assert_equal(Vector3(0.5, 1.0, 0.5),d->whiten(infeasible))); EXPECT(assert_equal(Vector3(0.5, 0.0, 0.5),d->whiten(feasible))); - DOUBLES_EQUAL(1000.0 + 0.25 + 0.25,d->distance(infeasible),1e-9); - DOUBLES_EQUAL(0.5,d->distance(feasible),1e-9); + DOUBLES_EQUAL(0.5 * (1000.0 + 0.25 + 0.25),d->error(infeasible),1e-9); + DOUBLES_EQUAL(0.5 * 0.5,d->error(feasible),1e-9); } /* ************************************************************************* */ @@ -197,8 +197,8 @@ TEST(NoiseModel, ConstrainedAll ) EXPECT(assert_equal(Vector3(1.0, 1.0, 1.0),i->whiten(infeasible))); EXPECT(assert_equal(Vector3(0.0, 0.0, 0.0),i->whiten(feasible))); - DOUBLES_EQUAL(1000.0 * 3.0,i->distance(infeasible),1e-9); - DOUBLES_EQUAL(0.0,i->distance(feasible),1e-9); + DOUBLES_EQUAL(0.5 * 1000.0 * 3.0,i->error(infeasible),1e-9); + DOUBLES_EQUAL(0.0,i->error(feasible),1e-9); } /* ************************************************************************* */ @@ -687,7 +687,7 @@ TEST(NoiseModel, robustNoiseL2WithDeadZone) EQUALITY(cov, gaussian->covariance());\ EXPECT(assert_equal(white, gaussian->whiten(e)));\ EXPECT(assert_equal(e, gaussian->unwhiten(white)));\ - EXPECT_DOUBLES_EQUAL(251, gaussian->distance(e), 1e-9);\ + EXPECT_DOUBLES_EQUAL(0.5 * 251, gaussian->error(e), 1e-9);\ Matrix A = R.inverse(); Vector b = e;\ gaussian->WhitenSystem(A, b);\ EXPECT(assert_equal(I, A));\ diff --git a/gtsam/nonlinear/NonlinearFactor.cpp b/gtsam/nonlinear/NonlinearFactor.cpp index ee14e8073..40fc1c427 100644 --- a/gtsam/nonlinear/NonlinearFactor.cpp +++ b/gtsam/nonlinear/NonlinearFactor.cpp @@ -121,7 +121,7 @@ double NoiseModelFactor::error(const Values& c) const { const Vector b = unwhitenedError(c); check(noiseModel_, b.size()); if (noiseModel_) - return 0.5 * noiseModel_->distance(b); + return noiseModel_->error(b); else return 0.5 * b.squaredNorm(); } else { From 3b183e2da0534ffc26ce66b69aeee03ddfb2730f Mon Sep 17 00:00:00 2001 From: yetongumich Date: Thu, 2 Apr 2020 11:03:05 -0400 Subject: [PATCH 009/869] add test on robust loss functions to behave like quadratic --- gtsam/linear/tests/testNoiseModel.cpp | 30 +++++++++++++++++++++++++++ 1 file changed, 30 insertions(+) diff --git a/gtsam/linear/tests/testNoiseModel.cpp b/gtsam/linear/tests/testNoiseModel.cpp index 52e1eefee..c6fcdd77a 100644 --- a/gtsam/linear/tests/testNoiseModel.cpp +++ b/gtsam/linear/tests/testNoiseModel.cpp @@ -681,6 +681,36 @@ TEST(NoiseModel, robustNoiseL2WithDeadZone) } +TEST(NoiseModel, lossFunctionAtZero) +{ + const double k = 5.0; + auto fair = mEstimator::Fair::Create(k); + DOUBLES_EQUAL(fair->loss(0), 0, 1e-8); + DOUBLES_EQUAL(fair->weight(0), 1, 1e-8); + auto huber = mEstimator::Huber::Create(k); + DOUBLES_EQUAL(huber->loss(0), 0, 1e-8); + DOUBLES_EQUAL(huber->weight(0), 1, 1e-8); + auto cauchy = mEstimator::Cauchy::Create(k); + DOUBLES_EQUAL(cauchy->loss(0), 0, 1e-8); + DOUBLES_EQUAL(cauchy->weight(0), 1, 1e-8); + auto gmc = mEstimator::GemanMcClure::Create(k); + DOUBLES_EQUAL(gmc->loss(0), 0, 1e-8); + DOUBLES_EQUAL(gmc->weight(0), 1, 1e-8); + auto welsch = mEstimator::Welsch::Create(k); + DOUBLES_EQUAL(welsch->loss(0), 0, 1e-8); + DOUBLES_EQUAL(welsch->weight(0), 1, 1e-8); + auto tukey = mEstimator::Tukey::Create(k); + DOUBLES_EQUAL(tukey->loss(0), 0, 1e-8); + DOUBLES_EQUAL(tukey->weight(0), 1, 1e-8); + auto dcs = mEstimator::DCS::Create(k); + DOUBLES_EQUAL(dcs->loss(0), 0, 1e-8); + DOUBLES_EQUAL(dcs->weight(0), 1, 1e-8); + // auto lsdz = mEstimator::L2WithDeadZone::Create(k); + // DOUBLES_EQUAL(lsdz->loss(0), 0, 1e-8); + // DOUBLES_EQUAL(lsdz->weight(0), 1, 1e-8); +} + + /* ************************************************************************* */ #define TEST_GAUSSIAN(gaussian)\ EQUALITY(info, gaussian->information());\ From 227bff6aeeddb4b85d6c05ce75f18df22c099447 Mon Sep 17 00:00:00 2001 From: yetongumich Date: Thu, 2 Apr 2020 11:04:31 -0400 Subject: [PATCH 010/869] Revert "add implementation for deprecated Mahalanobis" This reverts commit 351c6f8bccca726e3515721cde22626750fc4011. --- gtsam/linear/NoiseModel.h | 4 +--- 1 file changed, 1 insertion(+), 3 deletions(-) diff --git a/gtsam/linear/NoiseModel.h b/gtsam/linear/NoiseModel.h index feacf7b19..4c74d9e46 100644 --- a/gtsam/linear/NoiseModel.h +++ b/gtsam/linear/NoiseModel.h @@ -224,9 +224,7 @@ namespace gtsam { } #ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V4 - virtual double Mahalanobis(const Vector& v) const { - return SquaredMahalanobisDistance(v); - } + virtual double Mahalanobis(const Vector& v) const; #endif inline virtual double error(const Vector& v) const { From 9d60c505e87ca3eb965a16ab2919d96c0e32753c Mon Sep 17 00:00:00 2001 From: yetongumich Date: Thu, 2 Apr 2020 11:06:31 -0400 Subject: [PATCH 011/869] merge with mahalanobis renaming --- gtsam/linear/NoiseModel.cpp | 4 ++-- gtsam/linear/NoiseModel.h | 10 +++++----- gtsam/linear/tests/testNoiseModel.cpp | 2 +- 3 files changed, 8 insertions(+), 8 deletions(-) diff --git a/gtsam/linear/NoiseModel.cpp b/gtsam/linear/NoiseModel.cpp index d1a03eb5b..e0ca3726b 100644 --- a/gtsam/linear/NoiseModel.cpp +++ b/gtsam/linear/NoiseModel.cpp @@ -157,7 +157,7 @@ Vector Gaussian::unwhiten(const Vector& v) const { } /* ************************************************************************* */ -double Gaussian::SquaredMahalanobisDistance(const Vector& v) const { +double Gaussian::squaredMahalanobisDistance(const Vector& v) const { // Note: for Diagonal, which does ediv_, will be correct for constraints Vector w = whiten(v); return w.dot(w); @@ -573,7 +573,7 @@ void Isotropic::print(const string& name) const { } /* ************************************************************************* */ -double Isotropic::SquaredMahalanobisDistance(const Vector& v) const { +double Isotropic::squaredMahalanobisDistance(const Vector& v) const { return v.dot(v) * invsigma_ * invsigma_; } diff --git a/gtsam/linear/NoiseModel.h b/gtsam/linear/NoiseModel.h index 4c74d9e46..cccca225b 100644 --- a/gtsam/linear/NoiseModel.h +++ b/gtsam/linear/NoiseModel.h @@ -214,13 +214,13 @@ namespace gtsam { /** * Squared Mahalanobis distance v'*R'*R*v = */ - virtual double SquaredMahalanobisDistance(const Vector& v) const; + virtual double squaredMahalanobisDistance(const Vector& v) const; /** * Mahalanobis distance */ virtual double MahalanobisDistance(const Vector& v) const { - return std::sqrt(SquaredMahalanobisDistance(v)); + return std::sqrt(squaredMahalanobisDistance(v)); } #ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V4 @@ -228,7 +228,7 @@ namespace gtsam { #endif inline virtual double error(const Vector& v) const { - return 0.5 * SquaredMahalanobisDistance(v); + return 0.5 * squaredMahalanobisDistance(v); } /** @@ -580,7 +580,7 @@ namespace gtsam { } virtual void print(const std::string& name) const; - virtual double SquaredMahalanobisDistance(const Vector& v) const; + virtual double squaredMahalanobisDistance(const Vector& v) const; virtual Vector whiten(const Vector& v) const; virtual Vector unwhiten(const Vector& v) const; virtual Matrix Whiten(const Matrix& H) const; @@ -632,7 +632,7 @@ namespace gtsam { virtual bool isUnit() const { return true; } virtual void print(const std::string& name) const; - virtual double SquaredMahalanobisDistance(const Vector& v) const {return v.dot(v); } + virtual double squaredMahalanobisDistance(const Vector& v) const {return v.dot(v); } virtual Vector whiten(const Vector& v) const { return v; } virtual Vector unwhiten(const Vector& v) const { return v; } virtual Matrix Whiten(const Matrix& H) const { return H; } diff --git a/gtsam/linear/tests/testNoiseModel.cpp b/gtsam/linear/tests/testNoiseModel.cpp index c6fcdd77a..e879731cb 100644 --- a/gtsam/linear/tests/testNoiseModel.cpp +++ b/gtsam/linear/tests/testNoiseModel.cpp @@ -71,7 +71,7 @@ TEST(NoiseModel, constructors) // test squared Mahalanobis distance double distance = 5*5+10*10+15*15; for(Gaussian::shared_ptr mi: m) - DOUBLES_EQUAL(distance,mi->SquaredMahalanobisDistance(unwhitened),1e-9); + DOUBLES_EQUAL(distance,mi->squaredMahalanobisDistance(unwhitened),1e-9); // test R matrix for(Gaussian::shared_ptr mi: m) From d86bab0e7dc8f9a16cda03cf69f0869cbbb37372 Mon Sep 17 00:00:00 2001 From: yetongumich Date: Thu, 2 Apr 2020 11:04:31 -0400 Subject: [PATCH 012/869] re-add implemntation for deprecated Mahalanobis --- gtsam/linear/NoiseModel.h | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/gtsam/linear/NoiseModel.h b/gtsam/linear/NoiseModel.h index cccca225b..2badad838 100644 --- a/gtsam/linear/NoiseModel.h +++ b/gtsam/linear/NoiseModel.h @@ -224,7 +224,9 @@ namespace gtsam { } #ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V4 - virtual double Mahalanobis(const Vector& v) const; + virtual double Mahalanobis(const Vector& v) const { + return squaredMahalanobisDistance(v); + } #endif inline virtual double error(const Vector& v) const { From 12b0267ab7d9cdc8a61dd5da5c442fd89752cf25 Mon Sep 17 00:00:00 2001 From: yetongumich Date: Thu, 2 Apr 2020 11:08:58 -0400 Subject: [PATCH 013/869] renamed mahalanobisDistance --- gtsam/linear/NoiseModel.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/gtsam/linear/NoiseModel.h b/gtsam/linear/NoiseModel.h index 2badad838..627c0de2b 100644 --- a/gtsam/linear/NoiseModel.h +++ b/gtsam/linear/NoiseModel.h @@ -219,7 +219,7 @@ namespace gtsam { /** * Mahalanobis distance */ - virtual double MahalanobisDistance(const Vector& v) const { + virtual double mahalanobisDistance(const Vector& v) const { return std::sqrt(squaredMahalanobisDistance(v)); } From 9e4be90111da17b50a00306b33e7b6b7f8d57c4a Mon Sep 17 00:00:00 2001 From: yetongumich Date: Fri, 3 Apr 2020 13:53:51 -0400 Subject: [PATCH 014/869] add document for robust noise model --- doc/robust.pdf | Bin 0 -> 197566 bytes 1 file changed, 0 insertions(+), 0 deletions(-) create mode 100644 doc/robust.pdf diff --git a/doc/robust.pdf b/doc/robust.pdf new file mode 100644 index 0000000000000000000000000000000000000000..3404719b492e481bb77b96853eea0fa3a2fc39ba GIT binary patch literal 197566 zcmeFYW3(teyCu48+g^Lwwz-#W+qP}nwr%fa+qP}=e$RKm?sK|(+|lFy=wG+Ss8N+v zl1gSWpX8~UA(ayrrD33DfggW&%2;f08rOvlH<0 zLK)i_{Zl5v|Gfi>f%QK%M9JOGn1D`A!Pw+)GmLFaoy-W>|JGR4+{($=;qTQ--^p0m z*wEJKZ>oP?<@6n_9SQycLCDt1+1kdDfQ5ig&cWEo+|bF^fq;SWZ?g#KRQ~~jfa&k~ z7X=9$BV)IJB3KC682=SvVoSil^tT=g1au0vwoU{LZ2t-<{>7Alo$WtLbom!f9RD*m zbP~b@n%sX8HPB}?X4BVaGBz?YU}0b}U}rEkU|?o5VqxPjVB_WHFlJ?DVPs%uVq-Sp zU@)R*Gv+X0F<@opFf=w`*Jn53)&8dk9Gx7D^{t`YvJ4H3^ma}44D|HaA&Jx{`>hP= z+rfnyQv$?ehzS(DDbip7J)I z`!5m+={xCL*_!?*Rx|wb{NGvrx0F&OVEe~@{EK*h4aa{Ska~K0CVG1I273B>a)u@d zMt(r_nV=-&eGTz<<1E+rz%W%GY<4ux(l=V((=6W0Ii5Aj@Voo`#@sMcC$#|PyadPK znetEt#?~~M27EdD+M_G=m$~j5mGj%-t?;%+rrr6_N`L_72n5dm>mdDWxBf@ng=}q{ zjBT782^i`B)ne(tbk`TO{fE^5#ISI%&@!^I60kEf(Ec?ae<}ahO8m|6-w{$UcC>YN zF#L-d(?8bdFYEt>**`e`C&2!r`2SbH{tXoe1M`2u>Pmgfc7qkccSbkAb&P*1d`HQT z$Ek0<*$ldhr7pGwzF}}^-H0mr@Yk7cFBhJ%X3RXhC7V@W4t2cPy<5k}*3GoKL%h-0 zLgHo4&W$PA4)5Nty%fkAWkxPp;a_P9MDgyMYR`iC0D0! z%GxbCc)H7p<@9IiwZCpmXY>^_?WP^7L2W2WnbM{B6C`NOX2_7q<_%ycf~9j)|GWpN zKqafCY(yOh!a_SFlK(Q6nXnmtR+YktmwFk(+w1xD<-G59-igHuf744dGE*Oe>H5Q= zm}CFz_SXPI=0*XN$U%ad(WxX^<)P%zd6U*vViCr^Y=dmi+i*fn_ABj#kB^1(DXdd6yYCY|VK~ zrHz@Ld@Xv9`UjIoH)SU&r1L~u)xF5;?Cq-0suf$i)w%nT>J^1Wid|uvsHfTMUeQcN zlm>K`DPclUkl7Qd-uE03P zUX>N$9uR8rhL1rPc6~Inz;+i*$AD4=qd5^?=yiO{7`P}z_+$vRJ^gj{?jFsL7*Z*v zPbHO-J58@C#orw;^#I6686o5{dU~Mt4d$OvDgz-<6F|kh&wG#; z&>3YB#{(~7T@!8FZeem6m93I2-Qj)3%@Kg}uP%ztR*cRBT$$|YKtbe{_CR%{)s>L4 zX9djLG!rQ~<1JfmvuchxtcdH$Eau9s^7~$maQurg98t3o>6=%dk`eVY0I@Pw2azy4 zZk&*}he!^g(idp`5TWZ+Kq4vK4I)Yvffo->Tf=Ox0A?_+!vMU33DN~@!bwE0lxGu* zL2AnlQX7VZ6NpA<9|XU-AsSxkT`p-R$HCK_Q?*%`EKEO$<4jlzRHvJ!D2k@!#SMG# zns^@hw+FF(c;VKtBtVM>@IVNBu=z@o4q+T$c}(nd*I@2%7=eooxZk^MPK#+&QKri+hn4`Xy8(=LcdD_LRhdroELFgN+7b`e-*5$a`wn%dHm= z`uZz>;f{Ku3Su*+Gi|)LGcek`M;cgHYUsP2UfFk!?wZKp_yVC`zWJY<2jQq^hqvyk ziJ1DDKt?eP@>hZ}0o=hPd!Eih#uJhDXV3t&!{?Q6C`&wD9crN~~*`52BFh5MWN;jgIXA^`ZaVAJtBADx($iNjIB_PAa5cW*Klwfu{`nMb#7$^`IdhaMaSJy+W6% zJgLx!zxJUBuApXilt9xFmr;1kvF}kU(-kp<<@T{ZZ1t$GWy*T+N%3OMt^vY_zD`}J zIPsD&LNo%UnRr0_3=KSa9f<7CxtjQBTb{C8)=OpM0&tB0CT;i&eeGBqomttO zScARVwUTq+uluvu!HxT-*+hCPZdmmmlky=OZ{`UdHt8M89{lcnX1&8~@C+ZF7VBaC zs9aQI?5$j@4BrWehPCUOUMvL}IsIdFj@_84k%_uim|ZBtC!9;?PUstTIl{af;Vz;VOIuT4)2b zt}37yl?4vcVgJ-uvE9{STzeNfxUDBqk5^RjrSV<(OjB9z&iUjSGXqJ~GpT>DZ`s(hcS%= zw-Z0;8l>EA$f-JJ;C%n=os!j0QU~eBmZ$|fr%VKJB^X&Ext;YX%<}_Wickj>INg5R ze7#J)NTMF1pLNqg#%I_Zo>l|Wc9(&tfiG6(8z^g>buY5B16kM&PIw?s`8b#)wGxLj z;5D;7;CLx<@a-*&mE*dFw^`bd0uRzrRSwXOpY&A85R4|C%WQ2 zkeM~=e2y2>HNk$$6}PUw?qJdem?`DSEabu_PVIuF5GE$NN((>9LsswwzP)Ci!6s~M*qxXwot?iKq72z6^qC3*ZkR% zv_I{SK&6q%4^hk;Ei66BalHQeY2MaUry65>n7T|~+p%K(WzD0bZfW|vEP-h=J2e-c z8Zd5U_6QxouRp*`uMPkXJCk>E3-LV_Gjs|e!Y+_wkn~$5PK=-M8lDw2>;qVK5ED-B z!4BjW8t7GoUPtOkkgZdl4fJqQ258y6H9hmtQz+&323>z-9t1%KD$i(vG+iueL z8^}*33&6+TUOtC!5U@c;4rCGv2;7W+^D0jUo=igk2hd|$g}$tF#! z0tm{Do_(My&#pBT0=|s}1<;KhC$F>uZq~tnz&CNp7ugNKcM7a;X5`1Uqqo49G@$$8%FjS6J)&sOvd?D1=*$ZRb$yrN2w<^&fPhrr&o4SVmoq90+N3cTS9;8%}2 zcv~a-<_(=5aG>VKr^UefAgB>QXuAi$GU|5$cbeUI{hHtw;D8>znvxa-fHNq6cl9NI z@BGC_8~=~f{SPCb6TK!(7dkoU0r-30J)pc z0qX2UcRxGi<>>*69w#2LAp!XOv`Qm=|^j>>+g(y#a`$N@+dh;Lv4!_yF(y&Ii zE_N@gk*}i&9td9Koxx1Krulom4Kf!g z_MW5nwo;!OnsmB46Jt%+T%s8{+`m!~c<@$0(#*4*Ir1;Upx2t}eF~PWMRwaK84s#= zQe#Xe%chmGYjVHYW)huuZd~@LWfWm#lfB}tu?j{?4wh2a9(tXh*kJ7WulTQ(4XNy& z5Qt}KiMk)Ll%8#{Dl{--wN{tbDv{j-JQZ06GxZQ`(G++`RLs)3WdB6%P5+MlBjRu< z&F<>M@H>Ied8RC7G8*}oMWAkR#z=_Z&SKm3s=3E+L(@XV0-4fd(J|rf<hk=96&K;C!?g6{t(?5&1evRU}oh^(PS0GyUFMm=RvdTQ6 zIuUHw!?(uaExNX>HRlg)AszPAIicLvu?m=qYvT(Gs3C{2-*w9Lx+FTy`NGyRZgS+Z zwvyytB;o5ykuqJtqG;JzOOLrST^u}KDwEJDhm{RWiNr$-PF@lg38l$JKJ1!ljd5Fj%%%i7oIG8Lk{(T$-+kP@u{`LjEYH%EEjSdW1ZU0@8_+jBoo?1!QRi zUV-twf`UqL>Q6$ud1KGW_QsIJ)}i9T3ByX`^9T>LLlqXHs=_rx$G~U3yKs(BP?Wvo zK=BQ9v|@=^1DN|OWcMdiU3aBMvl?j5M+Wxx(Ht&nDfTzEvGB%{hswIwsl#tySv$OT zlLQaAvVM^1*8KIzhB1jv4x*sFofO=&qE-X07G0XJ*8^p zd5o8f!{6SMcGL0&*6Aw^LgqbxZD71_MJ$7=JYPfV>`)B^!ptrCm}g75L|73f2_*J& zOhYj77)Resxvp1G)9YkKDjGpP;P%b84esxh<$JE|Nj#$7RLkJK z;i<8C@A~YT*-2kdC_P0HLlJ%{W=w?Gf6eomfA90uiQh@J+qS8KbwkHuT*u*_cEW$P z;BYBbITNzn+H2C#^+>ShGTAaVa*jJ8U>9DnsH1fYO!ggUI^_<6Q0_T8q^62pb-aP` zt;>q9iS=z|qZUcz-*1D+N5oomSwVJ!2Ai zGp#~=Q%)VKrR3E=zIXf4lrMin;j0II=b2G1IajVISs;`;fm@VwFM9}d1b z=p41L7p|zhvS--pI%MzDk&-WT(@?Fc-OtFRW9x;nlDD^JlxfqglVMcaWkIh?p{CbQ zAPKPjK~vMPO`n!E&|_Y^WoDmPceq@BHa%d*F(tiv?~I~suwSA`&9YuxlJ5H zZoT&86=kiGhcC{@Z{ijyp%raR6M;#JSWzgxawtOIrK^C0#Du>TF=5@TGDnKyK{J_Q^J6f+(o-AqXuNN? z3T?D56r!G$M_i{@k(qIUTHVUQGD}bJY(-iakI?s5%|dd{a~)4}{>09%&JY}N(cLas zD)j>|-ssp7;}%PrZ8iH1)A)=Ad1p-JN^g>i5#b|S$XeB?3=%@54n|_*8&~^4rPrzw zj-*J#HGnFXop%-SCV##{5FeD5_8zh!PI4R-<6^#ms2+^El~2{9(^e$0SUvHB9Wc!_ zxq21=eopO=#w;~B%cfWc#$$>|hS$$8OIuy@-pETO2?g;$HqA?&{MEIycFh2am6Y%#4?PT zNVO20c{8xQJy!(KuXiHzVW6NPCz!YBedab6nyqq%nwWYROm#rm-}+8V${Vc?#8)vs zC8pk>_u6bMS>1F(aHcpVVbdJ7cf~nRi1-Y&T)W1XNMi3T&fD0A@SRp67Q7IYy|(gj zc2l%Rlr1KI)u@Ur7JfB-^uY>qM9C!<*^8TN$XZ&}4z)~5N%$0V&!*3aPvmt_4DqJ7 zK>y%f1$*q2n@B(+4Bb$*)b%qi@Nf?FG$z@*YXg6GHzpt?-kh?PlyNy)Syf^~@!)`D zKl8apf={a<1*c5*^1P-2X(^pD7&W_}dfwRNiJ*NG09X=+ZCQe+t#z2XCNQT?qcsAG zLDf@N0O~D(m(`T)KKjX@Ytif#lLvFY)u!@2=X^tAoHIOB4vSY^;Zr93FDW%;U(6lF1R7TS0y~jCR;A~(y0`z z6IeIvuXeVtYS;d(%j%`n{7Khr#b6OO+3FR)JuM{n)M?0Nv^f!x2CS9!l)bz7uG@se zvOrGPrX*8pnqr2*n3hY!#@UD{tbs45-};vGFIpNAs{<0Ruwd^lD~pyfIoe`2mjUm0W$o8?o8!SlmC!MLyzF5P>X6-0F*!Hant*2RZt3ak?aI9b}5sqzv}R`;uBHmMX4K>46WiCxX8pZGm#QX{ruv z>UH86Ti?wv$QY%7RG2YcPB6PkiHncDU_1GP!2p{uGA&FVg7=1uo9G!h_PA=g_ikZs zVBKP240HEoQ9!Re%cp_JsnXBi##J9&UgtF-t`{gN?k5I_z*C|%=+1ak{ilvU!WaEF zq+e3Bpx%>PrDom$w;BVN!$f=Mu`RojtaBDI(-TcMBdf=F>hGz7dT>wd4EUOW>#kJ; z*SE<=?wq(U9|$MFo1&gfmgthAXt$056KFCokLB=?Kd%H@+f~pah`E_z5vEBFhC;E>#)fF{ll`U}-`8(cmu@AdGfog~p&o*?rSz@4R#Yb^>ROG&5Ti$$%S2U4 zcnm(?rkSXKNUe=zFj035!=03JebkbnVJJdHwQ#RJ<}Ll3DcDyLq;o^>lSHRFjA0>< z271$ja-4Z7(v6H81P-QEM{?3G$I;|d{+oOM;@wG|8?oSwTU^NcQPeptJN1;s@pn*Q71r4+fh!U?mIeupsOB-IEgi3im}!IAHX{ z+#DK*!~@I+ZW>MuS#BmsSeddJ{P@V-yS-vW(=q7_Ov1NwV1$xwYgknaxDd7npk>e_ zr*W4)!0E#UkF)aWB_UvzXCC|$6t+b!$>61SzrEvYE-ssY$`0z;-cjxo1YO&gg__n- ze=JvuyAz3JjI2`hco)tQo7ss-KcS_8U_Sgt2Mpz+%H`9NOU9t8_s9Eom!g+D#ry%O zP=l_9QkNC>>I<3GZXkviYHu;Expwplh`F#f**#OXhmReR*%&VB-gxnhs_FR!pX02E zRgveEr`z0Cx;XKU&K~Vc!xOGPE%K;(%|kBNE=Jbx0r%J{XFyfNj&W>e#>CfpVG4Kg zxC2CjFt#a_l<7|+#M){)UXI!$Th79cX;PPv)e z$Ze0ak#JqU$Ekq(Jj&^F07M{4nMbe!azm~NR3yQ)wZuLv_G7U!`$SUkC4-#RDE=W zJyuPHy~L$jJj?@6>y)MPw~6y{9Jei% zt{Xd!Md4`gLCWgXYSd`M4*Wr%Q!PFF%nuPUcB>;l%Px>(;m8aFI^U#w>@X%zqwmE< zO)(+l($WKQ0Ia@}(_@QS#oi7cg3l%P_%&)o>kp{gSZ-tRO#bLd|7g#`=rGW1i6uw_ zr+r)iP2+X&b$N4X9NeQfMdP}AmyexP z=i_CG6Mauq7Nl$4P?12jC**Bg+;LXf(htH$OSR#c{)e9o9D4@Jy}sF%xM(l_^>zQ9 z_7@}FWcc84sQknrv|a(N^%79Ec|Pa)l5{~dDXs0@26>e+ul+giMQ3ZG4y$v7UA)QL zxpo%dvB1N6qRX>2=a`M=ABC;^*(626!`FySrzCL>BQqrtycr{EM(`=dYfey5&^GON zsY4TQ;2MyyhY_y}z}_u;&G9I_q1Qcsyhc~ixAJZ4A~nn%vh}JUg>PZlazCaZ@2~1a zQ5bBRb(elOI+GO43@h86$Jg+($j^%agC~as1(tTW+c(fV_ZFL7<@$y0(ZaeREGyY7 z8X1M7j?619Ju+89(hIeOKD^7fO38LDUD+lf=nm6+aN?P&wwFMm z?Ge`ywnE3??oNyHt))CrS0}M=@=rZh29MA^?#VWX47c+|^DxCR#R}VX?+E#>CICpj zLkvL@+Fo^wOs`4pKG)svF5{3;;=cX(|xfyY(35U z-ep=aR}=(%ya~h3?Yqi|a6^KYn>)^2!<@+7w+F{XyMVCgm;7WG$ELI8KT#pq&e*jg z+*hKwI!DCuJkgdv`JaFreTlpHvVeHXC9pAM{3qANo>A=xni;Aw5kb1$3LEPmXantm z2Z37CRjHX#xMMox7@qVAs7DkBF7#?pW_kRUx2}e5dHB3qHG@v7QQdzyjb4~g_B=?; zO*#&PF+h1SBN{V<2-m*KYTpOVu1akl|GbsMH7iaaI#>TToq7BM-|_U*eY3$ZA3FE; z(8^7U@PH~6(J6$?v>)vm@4=Sp3z#Ooy(EK~)@2+=qa#0}2S*@0m0c>RR2IbO`xTX$(Vdak1!q)A>?r8t>bq=Eb# zpLpX_>N0H2L2|)AWs{jyiY4qMy@P8z{bQ)~GRDS&)+V_dR1gvADO63Lb2k0{HqMqO z>MZ$T=6p_bdu4BX+NidvMo$MMSQm<$;D`fa)L87Yb~Z4Hz4Bb{?7hR+LKwp#e$v&{ zoT~l%=r*PyX`v;hYJ-*~SK=_;mA+JV@TOh(q=cI${OH|r6B6Lkb4;e9iF~~ zO?wV?vnvI4cNwPfd!Xwmyoe;A+AYVxV^mCyox`%A9J7M|ckk9u_*_f`ch72W{Nd>s z8O2^YJFot3;*{mRI)%;TD7{TSZLWJd)P3w}d-#IG!;W+=V~cAq_lS@5jHSI0PA=L5 zPW!38#6hl z?N7lQXqN8^96!X1cQ4S=)E0z^zb?mBocCgdSi5FK(f#?${Qd4cPCJPm|9wlul()03 z8utp>w?^@fa+Qu=l~IJ+ZJXKs;i1s1*R#4jhHjV+8rTbYF$|Z!tX0F>?uV(ZBTe)& zbb16cUrGmcybxGVprVzI6IYK~pzG8=IVH(1OQ+uT1Tjg>h3r|l>q*Z!LOu`ewt(a| z*#_1Oi$%UjF~WnPxJv??nw95b$$^hpXSSsVwq=8kh@cf;*3#tlSVCjC>oiz7CDA+C->-I{Ub#FcwLyp3j3>ynoK@8KWjvb-eyECj{r>GISBArgNsRuxdL>2pc+0ucINE6r*Lz} z)B0(mQWdjD&q!HjLWX1nNO_v~Y%|PjNGctB$B;9s5|Q z;P4;rDmwZkZ@nq*^owwxph(Zb1^?iq5Gk#*%uyFJ9La(KyCqr0r=cM}51u1=vBGJZ z9$wd9^b5geT4fF`^TrW@?nVWE8N4=W9p>FfpVD`%@ksYM@%?^_r#0{X?~8J>*)l-! ztCEbnqJb0(TADr0>uj~X)NfIc!hqLsf0mpE?J+qoRxGlQUG|(N4ikU;@%TX99<%Xu zY#qLiw>9?b?~q1qwtTOrSo~o;X0mi4Vr3sl;?+Nx9r+KHICMGb^X{toR z@wMf>!X7{RK|vkq67@a!BJJgrMM`fyVQjwTW0wsR>Q*FmYBA9=LT3A2-Ej~nsHo49 z9P&&r%1zaszst~NBe{?@ zmf+Wvy{sFle3d(GSE3bC%bW<_2LYunQ^=VLMrW*a6xwH0|1cmW2Xnta?jsHBBvq+J zyi>X1I&aOy4nCiO`eIx*LWquGl#&JSyCD7&D1Z|FRGxI;LbujJ;rKUWgTL ziT*WORSj#;-}sKRYeun$nwC+1v=fv1n+-!gG+Um;8a)(6F%M?V88mi$+ck1*Ek4kr z+)IzEJCMqa-nGZDj>3^zh6NBdv5>vHG9uFw;8~_^IZCy<%-q}uj`GY9Q$j<*dqj5| zUIqre0#m=c%^Im<2k`N7=h1gU5|&(Ht1$M?&p1rG^p)q!TEtGV!(Hyt&#G%bhOG|< zEy|0~uvszEE}Q~u8qDS85)!#jZfM$BMTKJqa7?zDI96M{(OO9^>_w%Qy&K7{h?Xe?O4RCN<#W9z-mpK0!C+oWOlS2q7j(AXu#nnwOHeb2g<`@bOrGK5?0h zCzp%BlltL9EUc{8>az^ZSwh>|L`x1R9K|qxF>~T!KJF=wYp|x;|M4-!U~#qDT1>T! zzNUy29Bm$@Q5;+Hysud;kjBWJ{=fu)CaySJqgR-$&de-o8WRnak4*6sF)Khs54}7n zrJ@^HC&h8Kv%TwS$=p&Oz5`>m;LadP;v{)6y~3)tbz<)b8Y#dJ4lGeN=}2h&nuK4! z6Ddtsf~Vx1yMgYR9=9)9+Kx`4{3UN$M_^ilR~r0MwWsp5fi2k;U5j?}0Oh87Cbd6{ z#YPNon5@x(M1WlY)PD_hW;r8q-dRFi>$^ECgG)<75l0RI6DE3Tg3Z0a&q&JdR?4miJY zRd81*E_jG5(VlE!u+wNWoA$@03-=T>Es)Vu-M$E?mQCA6xm%uakw9R)L7P zoDIG%ZBL1mN}DWuW`KaNURzZkEUfoG^lgF)NB~i9a ztzLG?)m^6-`~>6&QIun5s|-b6ihvhWXHl(Tv>>f)rboDPfF-Y6CW2y@tcEI*CA?W5`%j2KBl>#g>x$hH zTduhs$!@uM8#)GD42Nr8^9*53*I}{L${MX|K@$aSjgA;jGu3r-bYQxD(~;x5r^P^w zry#B+QJy`+>{K}t7SShy7!k@mkD*|sZKGYz{R~ZWzm6k++3!#=|1MwS&dh$9?SUbZ z9mwn|D4?fA0~rp<%|c-znDV}pcG3R5F!sc`8tHM(9+Mis#Or~FZ1Fs>u*+CYKUY{@ z(=acQX3;7dVO9b9r#hE4P{I`#*WVteM0b2ABoQ)~YODg}Ui-YuhJ}NmfXWOOeS3&U zLU1Q%-{$&<0*Pr{)8S*juFaFuzZ&;usr?Nq(l3AtF1FkQfey^^=iK7{0-^PdGf?TI zbtMZ63Wrg$Uxl5D^c1P`k3nr%yguRp^7|q)e0f;U25p7Ycb%}R8i0(5c za%~#9q7XwtezXkIP4WK4D$dDO>iHD8bJg{aUx25~8tgD)-&PreOkUGgq88d4;Y_xq z1#VcuG1B?D8AuahPS4s+wHukxM7yk{cUSYd87L@Ik;8A|;vmqP1}aVYvk}?a-`LzfHs{`|Be`xZ9SiZjx3V?MirFhLLWjW9}w%=!ecnF{LsyU*-`@ihqqn z1#pHN$zdJ28H?BIeSk$t>G|vVK$Q0oJUSXfYz#aIz;d$iTuD*n2%)H|7x)c7R?Xsn zk{Tjzp)aMWm}aj4+cj+7L}_Pdja#AJ(7#^*>PC1a7_MJOcZJm0z}3arywvKg1HT;C zN$9}rnc-3-9IuKH^{0*!S|sq*Vs;M~`sqE}IxcEKDxo`elVxEXl3pHuSv3x-hfjX; zu=@8&nkyOOP$>R79 zE}L!2>7}o$=2RJo0P|y7JFpyFHS9jgE&9tkZJWFawDMJ#I;iXuJwBD{rlu3udk@!n z+=DYT4#AOOjDmo4Z=WdqNY!G9uWdPBrM}-o4cB=&;!Dqh3qhgko42$jd~Lo;g%Y6& zt8nXSlRuxjA5K@(ev+pT`bcMAzrL%ozxXMX*nbpN9842RA~LExlf;w zByQ!MCi{h-XgWgP$4MUQXT?bAE4F}s95HnN9&Km(i2m-r;NQT%0)KMS2(}SFF-l`{ zlW~R`r$zVYExGB*>8%0nES3vZ*a~-!tge{tlVLKc7~yj1+|)dl%6idO-YErzc7)Cz zrHPa9arSi>SBta-&dVGd6O7f`Rpg3V3#Bdvv^AQ@`^2H}%pAvEATfZ(6W)ULmAlL$ z-LrsJ^|l~hl{1ihNK*kbk9A&Aiw#<{p&BQk#xoAniGE|i7E_-{?G(;SGJLyKBvRNG z=XFw0NJ;YLR%iATAr;3-2E$?k?WqVZO;Zh#(pcKDA@$B?FM&KsrS>pl8`#1j)MhLW z4Aa-&{F)|_Fcz@YYN;k$`3HXWilXj+Bhq91KNjh+u>W^0-d~X(D=Xu_m3jYJq{qR^ z@n82YM7M&O5N_FX@Nmc=k;%GZDE387=fkkUK6%)L4vr#;*qpz+Cf6*?4r@G zZ8dhDeEKeRvnVs|EIhlsd^oMJJuaSWSRtv<|E{BkIUgP#nrF)=!dUf7KQ@jaHu@nLjWHNJs~- zdz(;oAFW^MAfN`+H~FmH_%)RMt2WWCYg#Go1b=mrUQCQ$Stix`&1VrIt=_ESMz_E3b`=lGG33)5w3<+! z%5raHor5dTIX~g_wI1kMuT+k(+0Up|pACQx92^`kpbo$)Ccrb$8jx@3%Cig5PyXR2 zjZej2X(8k>NSzNQ&?R_17~fakTbqWPAD|8GwH{xtFV#18zP$rb6#)U8AL%L>kjMww zdm@I_7nx6o7kU_aU)VvoXBI%rPHu0mRL-d}XdtKCkKy;o7mzbd5ednW+IQ8fZFUjK zB=qj!@D!}x!Tu2d#O*E6s~ZS_&kwH17SO#a8qQA}C4aR(fInZN_xZdp((~)ZH|9?U z?5{rG5rtr$cr+Nj&(MQmoUXsZNV@4C(~_UP`ya8}9rP12uf(^d0`%2r*z&d*eyU*Bb^9KHB+04PG@Oa;{KH0#B9kFqK z0s6`vm(&LnDv?<6nWV0Q||m2z&r#?`-=gKmaU10-FGN%Y0$r0E^$)klb(T-_brR z5KZssUYv-ZbgxNphq||8D|`5_%xwIty}OC^7rnbw0JB%Rw-lZ)e7n9ZFo)Os_f3r7 zd5?;0KY>51vU+vs7(p$}@W7D4>r25tT{ZCp4@Mif=;`@8OTSGG9@HJq?0WwQO6XTi z!|AxTCyBppMm9Fk47w5aNImU3&aV3*&7~C0`J8y#rsQ!nZ^X2)OR&?+dlAU*$lhgT zNo#&q-UK$*+Qjh)UNq8*ynC6t`cOX!ep=4RI_Nxo8S9D;p188~sPrlb_R?jVL@tE0 zz)_|b)74F;6PF0M7#8vy4|6>YC4(Esqd}<}JQ4w9{A>YlFf^ag>59oJB(|$CP#j{_wgSPWF&1 zf~R9E(Dm>i}8X#I;ZiT+}vKqg#Gj-X(UiPG1I$z2+={LS_VG&>r z;PQ9Jdz4zlrh`5&+&uadOpnavQdLf^dBHJ*Nf{qsOXBVyNPP}4Xx)+N35!arE$P!9 zD&_dlouV!Ew0qX13vsZou;S&KxgDv_`^I`#w9)txV$LBFskYm4F969`VVy{wP|Fb9 zErg=yp3UXVjow|zcbBotW@D}|`)sm;c)@2Y(JJz(c0Yr`00VZWAOs^4Bk& zB}N1&Ll?}m*{03eCA&x1maq||%u`b-K%lOEPj25kv?L4!nUJxx zaH2ELyV1-Tu=o>hvo}689>P-Sr28~d^mMJD3LZo>bVikBGDL>C;F=*0$9c=LS9WA8 z-t7_!ENhUljhMq#CI1}TqdFrXR(cSwo};|C1Sprxny$7uZ|joXbiOV#TymcmXJY!i z`y3s1n!i8NS_Vn9@=f-;axafjuazd-D#@ON8@L&Aup0fwZ<%4eto=htd@eU$&zp`j%8@`u_}&U49KW=g$V1-?;2gW@xPg& z-@~Dpim@6=Z6KAPi-^qgtrD#l+GOK}3!Z~*ozA^QrX!*COzr|JuWNO4?xe(B4| z6dc@RKy&4vZk;?QDa;`80AFo4`^R1N8M2+{_B0-}2vL(yRw=?q0pD23p{@pa$ z+P_Yht@3MB={b-);U>?R3fM8!0})XLKN}J|Zq>w)DkZ$7ZmU}eypa+}G$907onp}7 zH>w4BOr@vsRWN-GGlknp>Je2B=0^`t0O59?*44rzEZ8+8I$Y4Hu_Jl3c&MdmQsD|+ z=(u!DR<+qoa8}XPsxI*Z&Er%9YS+(F^lhd56zA`Rax?)`$#IR4+-^KYf!IM)YfCws z=P!G;`__}_*Mw%(IYa$~*9;Pwrk1P9(KfXYZB0p&3q*8n%9GUJJ)HA%mY7G543map zlV86}c^1xfVzS#=Xp=tZSPfsv{N4xGN$6fVnT1IGuR$kr<%e{)N{B$OU z?JRp{?p|SSczC-a0P>ny!L_1^r5J{R5SfI;w(A(O%h1-`bbUh)f!WzYJYaUQ`*<0| zPYzQ)Z>*lB7GvV{0I|qzZX*+Ex4_=qphU3-k>d6^jS~4K z_tqi>JkcXrl##KIWCrtB_e)Y#W??TJcQ|vG4&-?21!uirE|uCnJmnt09=eV*ot=7B z&4ithDR9{KstSXZ_5MplQliXtET*y&K!aSeAX{dR&nT6*1{0`J;0m^AO>FLd(p-gU z?)K8A2R3Kc_QP95Qy|e0l;^U=EIJrLg%nEF$-&v$;JOkrKNOllL?d1FOOuZLRpt&%w;I zI>gXZcVs5fqBQwZY4k6n`BaRIvRpr7-zc-tJG$iBOAa{J3O{qn+kNU)yFq zb|JAAB-Gf-gss=zy-vdZsDK+&@IY8+Ztb#MpInp%)fDCZAoz*M5iU0! z?t7sOx;9$4u^;-EC93-x8k2V{-3hxGp;2SIe#8;dsy?B=`fP%93mU2aoT=d90H}9e z1KFO)>scKGL)MR=XG1s>cI_6T7Bpq*o^D@u^4zjFE*Eu(I2Mi4U}uq8a$%JbKAC{xbOVAP0=QP7B-h z$AMK+EQM2f{2Ef6d$lE1x)QbTretkY4j~|8VQ2`;iD4gS{3y!IVYn#hv;!DQGJaw+ z4h|EWrDSI>pH$|7HMrJ1HP=~FcC#tVG(fbN7zAYz3bh|ldJ`pe8`g76gYAbkIYk{GYE(MmRJGhKvw+j{QN#(z>bxtv& zgzc7Y+qP}nw(Z@vZQHhO+qSve?%lRAedf=Z%w$d~sZ=H3RaNTZt#7U8sb|$bs0TOo za4@VDnx;EF;cjbJ5)sE2l1sbOTRAnp(n%gXe2)fm3f65tP4BKImy}(FeX7IAyJoA` zB2-L~w}tb*4#>DBoa9if5Ejt)9}~*mYTC3~-en!cC;m#cL9ZO5TuUyC{wDS`JPW#< z460oJ-ZKM>#|Xg`N?OPUKY<-r);7Ov*-rO0Mjj5;jEz6%I1+teHeS<=d`@jBh#}R5X^_Zkh$K?jEj@#(A31tg2`O73|Fd;t z!7tXJ9`aevY(lC`_^D_8I64Ve z*BEP#5g6Q!egOBPgbyg3!?^1SC>cty#=G8MS@WVRb+{Ma@HsqKQNpy~q3BAYXrnov zCZ9b+PP19s9qev+2lX(O*N5veioTMEtB(ENO{pg|O@93IaQgJF7Y3O`MPUKksCVn8 zH<^G}?pBw}7v?X@+8V0-CV?cMA+c@3^yr1jrc_NCU=%&NZ6xyn`_`49f)Gr}VTamG zU9J!s($)3Og7Y}UVG3cyC38}08lL>b`nRjW7h8a- zbF&&2bEkzVtnB_b(nRx@NbBm@@~4>XU4G&k&?+CKm&SpWL}l2{EGsERMKWb;zU% zqcB6Ekq*|mzU9usjbH?2w3#1H$8I)1n$2UaNRrX1TOlParqd8k8vU^^Vi}qzLjtq;kBqZpc_JWbq6L>(DzEt-S>tNZ!-i0+iiS$1!^V zYOCw3p)&5Kq(fV$LdU4v`Mgni9qY)jb)O^tB zZExbiXfc^aRqvxdHS66+kzjdYiYB7nrCxVU&Oeady2#a{g?JvMvjPk`L@U z?apw};j6O^WI2S*ihxR*sKyz2+>C}R!kRA_%ChpqFEb%T)82>SpiFJbo{c^!qcN<0 zb<;Y>$K)ISTWLY>#y2{gvX;D_KxZ1q3-TZOWpHe-oHrF9T(rj}u8Hp620xS{!z4N`|W zubb@5V2?+=1SGQumDPlkNIH4GPG?p)>gZG&_CgWZ19csK#4V|rK;;!tlo6SQ@$wMO z@)(FB)kT7X?f-=4rqi?-A$JmIz<82m8}~^sb8>FW@BZc@w?;AtF=PeH0s3D5aAL~~ zRPW=1JGFLhYfEljGdr?2Ne5a>2MajRboN)Nou2q%i4S5lGz}t{42R{-*m_LDTV&O7 zx#}kq&3sTA`C*Ufu%Q`S(rZeh*ZQM~;3LVkE$Fv}=&PJ1AO;>{nC$nLHqQ76{ZkqDeAqo!lvDOCO^)?DRl&q{*lsI8yD66X~`!DcILJ38qCo-mz@=^GQWFq8w1 zis>4WOzP3@Vha}xhxD2?c@g}PQ~`p26B~aolMkyJ3c0K|vFyrav5HKx+6YXn<-A3Z z#d7~tYGHI`0Zxt#*4@DF-@iPYQhoe2OM{P)OcwGxI77_n7?z0~WlCt|)MY04@Vp`| z>vq)BV2Wux7eX`~#}wN6@(%~{1k;jb&RkvcDg~UL0`p44Ze-v8(yP^za%ttbThec* z7%p450z@#W4BdCG{Uw!w1@hIKK?{#*P9j6<RWiGpIhkIkC}FwG*_ z*wHv;{qX6kEtCvpY3Y5BDmfNd$)5f-MpYswoNlM-OJ0MrGc{eKLn$XmJxtM;ClC4+ zaeYpf z{CRa+Kv6C^J;lyzc1&Tq4OZ-@K%G)2#NV;2pi_9P^hR2VTCjiYf74(pa+AhJ(xCvy zof^b$SaRmcAZ_z`d#j49X52E59HlYpLvvO8f&}WJc(-^lsJxgka)!otWx zYn3C@q6=3MmA0I38O^Q;HX0L8-MLp1t+79&^x}?wsjLQu^*@D}Y9!%!0Kt8Uf1iA-yeKFbj`RyNm zmg^<#0%Z~2`}FnQH0fq@CJ!khsnn*e&S6ptF{HVsHBbEhhG~(D%-BUMo&u*$hy!&z z7P)y9A#XGgORJKqO<2&S$7e>yUG_wF6!AUYZ!G&b()qVahcb8A(b6;!0d1nuuX^CYJSy)_rtE_0mDPVRkd8f^G5~oT% z4o0J_Mbq&ii(GPLk#Su)?~6MfyXzqt#N*R4ci${M+`|)qwSgrlN#WCMQ=2mca>2p< zVX?JN5Y@Oe;xVx7DATL<(C+o3)~ZTM5&Tg}8&ldijH@ljDr_IVKWWWcS#s7yeapF^ z#6(t1CeH4g4>ec!y-J*VMh%xC78B-f07!GOrL4{rLW+H!stZ|m8MR&(YT03nTdyb$ zngkULh-mSDeL3_tdIG3fIIp9SZvU=zN;Nl=QT%+Ij|n1CznGD}{3*xM2D$HV!qX4P z-FL@xKAEzcO>xe8#G35N+z_{0@aN>+tP>Os`I7T3M~CS;a7a?|jw7jKsxA zL_bM&@+tk}_8}$`Y1Y%-r;k|QTg*!}e)f_NdxaJ3+iI}w1k!Dgqs`VMTOXzPCYb>3 zic~7K>*tY|`Hgo&*ALUv;#}qqUVBHK(7zBj{0frd6*x*nZ>4E)aS0sewLXZcm@JD;J9;bR-6I{uo~ z0_#u1C9amKGs&8OC>`z>XY0EjFw};0S`6C=Y}sx%H|Xjhi8=y?HV1y(*=Cf$Nu97aDo;M}m$_Hv;@Hwbu_cx4Q+ME|m+sQeG` zvg^2Il}DQU0^DJ=WE1o>Pt~v};OJoBP%y^C9ixgBP_7|-ewJ7zmlivSlBnd#eTQg# zdWUYy_(86%DD-~_EF)EfpJWe#N>{^ zc(Lv_babtrM`=zUoLX25$dwmpFWB4p>{8ERYgqMgc%)=*pWQ?Q#k;D7wh}NCmBCF4 zX^tDLX0!E5_`O75iu(duZP|(U!oo`8*LJV;>oL2nca(LyUDV(ST1d;QlsxuvJ!s>H z;(E5r<>j&ZP!q$RizWI4_G_+nqBVX0+qog`2@qx}uWIPzv-%}=T*}$_2}le=qeJUl zBYE@t;q5p}{-2ncXBZ#fnKaG`N*bOR;4z*mi6a|*t`7$)8fEt62(mGOfrrlzEkDMv>fvIQWY{6NtxK%3&6WiEMp0Zzv%eQeI3fQ+i~0Bm~_spQFZIOWujIs zyx=ZDEL1+FA)ota|;M|;2q+}XsUaqd+aI4Kct=_Qkf zfs0Lc?~lh2Gha%GYlK^WRpf^G_tdKpd>luOm?6$9(rc^w2Y_2>I`JKw_meo=Gg27 zlruh?IPY?Z|BC8dZM%z9$xrbdj*7qY!PUO85&AB_k&MqcDx+%hxvO@YAtbzLzRRXF zw|eDbn}`&hdKVTi<>X={Ix#H1Ls4SX-dsJdD@_DE%brpTla1=tmkq3TC0cTlj#xRF z^?Ae)&I6I|SFH+;=85DXGcH;_rF`yRTZ#WYV6A$qFg$pNdpVAU0~$;5kQF-i(pTS* zPW_Fx{>i09GyPVfkLN-ff8#)n6en=3G3`;{TTW=Ril}~S_rj$=RCF(wdhkW>qq8w0 zef`MTE;KFqa96)wKm;#^K0@&rITjcnw>KmF`YICRO5&MRaCVRmo`s&IP>G~n#IJTg z_?l8CiY}3y=KTU~#mQQ{Y%EQB!@OC4kq^R}V_G;TF=vV9M$qV!}*RU%3}=Uh$Tyb=x`koFT#n+%Ip+&bV3Ev98@!Y;pKyn$E2 zXI%o>@16_N=X!F)pXLfVE|pPAIj7yAkJh&&IZvRu>UDlZw##$G{NfrljJ4$c)|I)r zmd%UeLC|e95~TWxZ0$`tJF&qs_NdsG`($Mv=EZNL zRsZ*M7Up3iS2Fp#NEzpM8#-7Kn~V9$Nt!3QBd=v<~~xa);S5w^7S>n+4^i??_pt zydNG;Qvk_(o#t{&!9R$2GulYIeg{DzJ}efujjGa-AMgOeTiE|0Q}$nhu>S_X{Ri(V zZ)mCPZ1dlNv0wHp`!Ct~e+1#m5wQN!-^45&oqnOQOl|@U9lw%O))3;X+=YrD2qrEGeFfXiBL{+h<{|=FT8G zeo$jS#6ig7Pq)2PI)QWepvWK6Xwv=Wu-aQT$SM&CH4R!rs6niPVzoi7f@DylBcx*g zTBZp|>|jTz(IN%BR3Ko~VpKV(lxU$pT3iT~A!>-d*afh&+OLmd9OTVGH2{$HDT4#E zh7g0IuQCjI!E%cb@LCuKCk_t;!$YmWGC{?|!p;noNaxUK5@7r}5^&GR-4ckGpt_`_7~sz^p#fL^45UG> z{qS6nn3VM?V5CK2MU)7DYAQPgG-tyg%I4yve?VX=V%UD(|B>Il-gVZToaUWIJ;)!x zEA~{XSD8AHR+7)8O;|j<|I2+{PrRBdZ5p}j=Chd}QtC!q8CY9cI#lfmL>wXxYpO~S zI2S&iAK-zo4H6jt@?VJmK-`}4aqhAGz}n9FKpP7E2sI>s0S=Y87Kh2≦u*_xp6O ziJw@iLu*<(G!^aS<3w4Jd~j(|bEwl}D;9h@`TD-zS^Bx|^M?JXfg_JPw)`p7%U_cm zBcHiZsYwapC&kGg(`Mx%IX+tOQyx9)j z>8)$~2f20_JoaZl%ub(glb0xKN~!fcDwcP_H2bW6v_7JM0wcf&E; zx^LzL|5@)k=rYJnx5s98f8hDRyLe{1{w_+0^RvbPKK?XyWDQwg_4>#Ri=7I;JeImq_1>+?C$fl{q=T~x{US-XLdf7u z%L~(~cJ)D?vmKPQ>pKgv&Kpy4lRGo7V6dThy%G8e-qqEI1W z@N3SG)A!-TKR+Kio$cAgZV+KH8gX0j`|GfAv?4cR>hra{k-k zKDV(@15#SdMtYn@tuNJ>*pTcdP7OuQ=nuI+cY@ublKCf+inD-wcs>XYJ1=&MCo zGu(qIj8dw5#d|&B*_=-5mH&fd{J!}eEhK$}Hi%oRVU9Vkb(|_*C>~i(6pInz6$4cR z@&Ptw^(dZ*=9;p{WckOeK39#bBL4}}4StR1Qy@_y3lLV-5Y&E3gr@y6Eg3B~bk?Sn(lll$o}%MP8%nj^sMFuH4NUforYerg zJ;wiNgA&VVc#v>ZQ`9TMS!R#H0|rPQDJ9vlX#o%(y$voeeQUo?2iumT+6!(gIt*~M zzu2AtWrPj{laDO|1I0O=VFxfo(R5H+5mp9oAE3TY0cA72RTUvQjkA_;*E zW^BJ0Vq99B#6A&VTFVBJeR~A@tf#*O)ODe*_6SuVtp@NubUj2b%dnz!BMVqfOuKTF zd>YX8uEthV$lDGF*~aF02CeRgBk4Fs@lymqBns4b=m4Cf_%+;?+&6b`zH|hk=3!t2N^>D0 zg_j6sEE^PiL^R32cnr7Bv3R6fN8}a1%iQ8K!QUEoG`NZ z6o)+{Mvw~1!GnQ=#AHR`9QWpLB@cT^QHg@^zb;=7Z6=yzW=(bz$g&rSQB?pVo$?_y z^Ox=R5ot&2niUQ~uef+E`97h%? zXf_ihlM%^(P)sGwXi~Uvq#_){3#$SM^X*mSz^NMS+37~SH})Ck+$D~wz%fkjkr=&v zX4^>*Qo+N7cNz9zmyyT)U=>N-K6A^nRh1MYbV&MHT^rI}>WZlrW>GPNPa?0j+W@GN z96TJGJm#Gf6|==E+D{kBc6T_AfpzIXpm+)C!;5Wo`i+{|oKCYqF?k-`tmPmsuaP!Vt<1V4rN=%`IUvPyJQgD@~Pb8=WY;lpD0o74zzQwgq zlC+~R{3k#YL{C$ZVr7%Nkx6-qN3b&r-cjqcoom3>2+tLG!{fY(4$4KyLB(B4;FF0H zejkWPn`7DsVr(rDewYNq0qsJ8K}mk*9$gz>XqIkK_99k^SU6Ecdg1n2Qr!ibJpa<6 zc@=*QnY9N=Mm*(eGmjnaAIR!(XL`!hb)l^}8*L?&mpmKy*)K*Luz99G(fT}*F5l~X z%9D80k-||tyXNIzvqZRuT$;w~`D}_g6SOO>BO&ROlhQUGEyt;(rxH?Z;y@tSykZV| zNNTq&ddK4EboWCry?%)L#1)-S&XNxpJqwjtr=p0%2Zu0F0vLcVV)Cjq`l7u5PH48b z&LZh4jXXWQRn0f;q(4#!HYrn}#*#bQ^z#_<8h7@xylW}S;~aLjRW0U}=)^kU;^Q_# z1l!n$@y!#YKhSwH*F9z7TUg%GqGNBUNt}Yj23kW1`JDfhGm4m$>-m3>*DNQ)67{A9 zRLM-mshjRN$AwtdAIGSG6=}U^(Z|+yScP=;Jh2-a!KUD{^X8m6`Y_8=n@>~9Pk`wA zk6YQ5yU!vFV|lvwe?8&YrG0D_ddwOi-C6@Pl}=simu?zEYj3%eqpirCQ}@y2Af6pl_1CL>y8LSN8O# zbcBxo{A{W}f`5?kaF8$xCFUXBG9{kNpDlx}_^Eem<+JhVtLoKSS(dc4UFDQNqED?h zbFA&{QTka>_!?2bRrEDrm|P3K^5?1AQ?IAow? z=s(&M&TiWKA0SrB6N?IYXipZ*Hhgu@WT&Sqg?w4rt4s1p50)N29-4JzO;t@3j(jzJ zHQ;J9YpNA}X^v6f`3J-~JbKwVBLFv8{ZFv-9)yPT0Bl>8{Kn(jh9k~%BXbDor%|PP ztkB^heFR7+Pll`&WoAipd7Byl??KLc zhvN?{PNaZcN0pI#=(+yaL*7^+heIf*t0P7+1ny;iVN{_V5U$&G0!z@m9H~zpqJt$?`8v8jm|?N2gxwqb*WgIZ9wBrWE0tYMUDk zyWZSZqCtJVmqyBI)PxB$lD;6}=MR9`QWhd^h-Zt<3vLtbdAnCK>#q7~H6MRiVeF?f z`ZmEg9%)$I+butIFkO2(Uc0mY*3L<_*YN4f+##Po1(11;9cxapcZMf-2ZbZlUR4kA$@ zaqeIbw7$`?zP`b!Xl~JBy>&V8(^@ot?oU|DCKns{6CNMvFKAoGW)Z(>l^>ZzEU>VR z*FONdw}*PPhiq&HZr|7h{mDHKNdyrO=CQ5;pt24SDHm&?j-o|LZe|xAlhU$z!S&+{ z!jR4k!~p{Gs_`uYF2UhX$aX>??hiFSgLQe^S;#q#m;cY$7WluKQAjX@tG2eY|7k{H zj}N5GKpK)xjsx8`J2Zir`|A!Mz}JKB#iasP5`f?8*EAH&12tFM==>bdJ2yH%fC%>c zs|WSOaIP;rv5ssn0Kouu*TT)KD1ddlfN_6QYrN?L()jnWf%gxL-sL&^nfxe@kKWB0 z$9Hrj1u>5=Y>qBK8CV#>gLS8=yMX}ep#d&U zY+*l*0BP;aZu8_~`KRl6Uq86GIe}^PHvv92H3Ieh6ufl>@eKU2hjA}&KIF&zh*99+ z{6k_ou=`=GO%B8F-JaB$*YEXTpFRoM^ZlRX+8{1y>^8&HY zT+m2xYA%18V%TaM+4KycS+UujF8n5r^JfDDce%zp59FPt+r zd-U*Y>oPx=Kz(s@fAo|_7q%u2;wTS~_J0xN2=VMtA63a59_|3WICY2SfY0yBBLDVC$zRwGfc{W^#I^tmcXq?j08~FQuYdw8 zKLp=vRKJ*WIRJ%2yGJeMhu@Rvson4k)xi%zfI7%Kc2BLrGrOmW%{TtzST7*$Hy|f~ zz%BnCHQ>}w{~9NN)?fF}tJAlkt0TBK@jZY+j{&myY-@qOEM*8}2KlXh}4&R$!ot(3E$On&ct9rW}0%^aiEq@4R@1$m)@NZlE zH+Ow{f45Cw0e^}f)E#Ye<$fgGw;f-8SNZ1p3D2(C*Zp2L^7#$^AQg9TgWP-4{&<*l zS3d2&&ba|#T!ONRYwFoEp+hy*z+ZINq!8R0Z)c#qiFFly1SG7uVJ;r~#s#F$Y9t}w z13S_t@GZu*w9*dQllBVT9eFLUhGT5xR_@&Gy_hFfGdBG;X<1_UIiCJW6z)@FGEr8g zzSiz0MdiuW<62`o#}V1|Msf3pY7x%XoT78qh1MNc9U?+=pLel#OO?kRH&x&LbqF0G zb!rAR?RW@Qfv~MMmXKLD(@S?!U)!yJDAl7tNy`A0T`JlMeVQ_;=69_wR74kfdg#urR%!nON4%rFjqbjtsH zjQByJ0o7=Ko7;gUJw_D02KS|&G|Cb9Rz@hbCf_iRcq@HT7>2dX^iPf8--R_DNoMPY zJ1NvNgtB_i-b^KgGi5PnLS6@};uVvL7_5vv<3pJZYn1Z<(U@Y<$lYk6w@1nL?gq1D zC{vdalyohv_hjO>Kxy`ta`sFc@ApFS1lT;c2G3ZT*C4cn$#MEhvIPbRLSV%b%W;IA zF_`8Wg>&l#G@s30tBb(|vJ?2fbGfYar<)XUF)Wh&;H7Oa>@KPs#gUlKrm*s=Zf=qf zUGLf*I|lu8lHp&i>;sNh)XEVGRvnb$S8}(l%a3&1I%kZV?#zq^RC{tK*$nPAt*qH9 zRp)S;1}bO{ZFJJ<@EN$NxjJ;_H_BO2taNwe))poHH&;2rZxdQv|B7Z<8l+}bJJ9WW zX!S285zd>6=pdN+1J?xu8tOR*QrUvcu2=M8^^XK!d$ZFCsX??g^f^M^D5JzJT0b@y6wj?1`g*;Q8W|udXlZN*xELK6;i^`rfY6Qkd(yyimR? zfOM7atZ|CiU276a**2v2GeSe^Kh^~!j7Pahg`O|}aRLFIMsb6ICIX%I+A&?Y-GLzC z4ENAd@{||_YT;V<9EFALK$CVBvto6B>GfQ}9gUo?cI&xiE_OMh*VyI=)#PQ5;2W+U z)sC+M2Xo1v!*~^eq4=+rZB-K(*Dz7Cu`)LOyT7kAPBXCxE;l~5TI`}`P?8!3$FE3 zc6S4-*=#RyTPbijwTocnTCP&pUHG{ws@B^qMbr>%BPk^^qbtC)N5i@GY6%?i+_JtM zDTz*|OvX6|J9`46%253;LM7&gv7+%pNU!LDW`>Kgn39k60lFgn%32-*fA_|wXF`KhMMlpdZiRT_E&Q%-nprnR91X{k3 zf+%ph)Z8;a&HevyzBS{Sp32 z;z>7=VzHfM?(Z4*AMa1G_9nh(+e^M;}MA}6^#xrsN&}#eNtD`q=YJoczL2$8m zS@a5(qdr>Zvw}uvE)b|W{7AzV!T3F;u`5}67f|B$xs>B>vgblH^d?g<__6M9MM{J_%)9E&ma|44g&IXsmsb4sp*&V~ zm%4_Q9b73!jwzHXEMb4_8-?C+%JUC;Kac*9zNROn3V29P+|!buyqxdVzybuF>lC>v z!CDc&mOvw=qrYt8$`%#QaLY~2;^{Z%{3blUU$Oso_RBz6VIAtu1$p60)p0Y|`V@_< z$X}NRspT;_nXHYgd}`B*f&dG?O2tVYjNNW?Fm9W#Y-*tLl)64@sk&z^A)8D=OK)%* zL||AVF1u$UuO78Sng=rZ!TLzw&(EAqk`LEM5n%T^^2!3IL+*b&H~R(GIqGKy@WZF{ zP+VYgctf2O$TPg-u9xptu?b%Dz~t1ouYY1H5wlgNf1M-ebzFaDk#6^HhT=2=GF0m z+i(*}TV<(Nu7(dfEbbePaw_STVK>(fUgj?&t+H_#PYAVu9YImND-l21=M1Pr99>i) zVLBOZFXh8VZfx666R0LzlcBn8h4}8L81SF9U5~89qn6JsX$d^Y8d4O0*o!?7^H3_- zUoLiry`CIXDISlsy1_TFz}rL|q1znLJFBl-jCE9n{I@!^M-ry~+y~->4C6gEx&bY7j;NU-iI3xBskloez;*Q057P99Z_p8nmi1VN*J3L^G#}n>kgXQi7CR(-pdj1i|5hzA){s+eO-z^YBip3kB?V(uN#hMJb*xJ#`^g zt2dlV#B_L1_qgrG(9_*HY=0V$p=N$I{$nuxl`olO^*kmx;~BW+!-N*EUC{>Xy!|%K zanuphde=sSzEFg!=Ad`yNuyg3`Lk&Gk3l`RdAq*FqWcft@V3z7SjT*fY!*m_69}kd&UsM?4meiqFb~IjG6QR_J|JDyo>G7sGCUqndP_ z9o)DWjxAmUK6Z35Ec%F}(Tv+GYAH6k_(4z*INER z{txeJjDJB~hggWryPwRaP6Md`9nL+3{p8vkYodb)Qbwzpp^R$t;;PDuZ(ZyaHFsn5 z7Q&Rqvh$Kb#YfRiT1$XSQt$Oh?k|>?w-JO8k(RH3Fol3X+Rnfu7kEC}qx32g1-IML zx(S{ z2W#54j7xOer?yRZ^XMb(v{8@BL}xyDPui5 zulC08htx(CN0k6)09#aqW2?omYb)Jfj_tS;i{LD}x_73jH6sju> zJG0D>@k||9iWKK_7zTp)E3lSQ+Noc4w?i2FXzJ5g6$_vWg~&A#%!zVURUaSJti1Gk zN)k1_AxN_LK72@svN#BMBog8{jRa7yM`EF$Og|u5AEb8I*hzf%9CHF`qY;^$ZtV{y%<`L74TYKt?xz!ztb8e9Du-`iwTvb@v3vV+;0U2QV8U%NO8qjTg zx2pcK?9xS^g_wc;l|GpR*&BQh-mSkrDRQkE{0)ijpJloUAeA}54HiKj3EW zBnnRDyUA?}0{am6=`kmG3IohE7z6~|alAt$CJbmCmY%=SSle?b{ez!F9~SRg&h0=q z20v0UZ;dLgqq+-bMaD~$8S8z&owJr7-oCJpXoJibC9D8?du25z*a`*F1u9 z`3>y5a=Lg)E@(3zrj=L(HQtqRIQLY^*y1tMjLs~gCZW(57SZx_R!v^$o|L-ddZW8# zH~mk}aTT);VTVl6=yiMrhabpV<-v@cIybkQwo8UZzdThGf4y3!E`rqK_*o%0G>&9x z0zZuQQ7$plz7FZ{qw#0Kxnu0mklR4#Ixg9V$Mf^K2}id)1e;vRp8?9oL0HLQ9jA=A z_xicrHWiDzwH3r@UUJC3uu-^I)1?WO5lFPZ5daKD@Dj645~R`>S}329ON#eEC+dw> zG%1tTm)((o5#)S6aI!T3%XT_1Q?P(=W3CifqSYe-w43p8Z=J+z(J5ys;$Mk5la6d0 zMW=kkfkJ;KO?j+F9s2$CTT23X^g6z@e(h4Xd7s3l-35okUG7v6=}e2+)Q^{( z25~@S%ytQ9m3Ty{Su!f4&>;;EiGIynJ_23`T{H;xvly;}Qu$V|$ z&0$Z}Y;48N`M8}(0d_9Q_|g%lbv|~ly6E9Vn4z*qd}`lMIf}ff=*zyHxpbIm61r`u zPwc3`Ss*86LZMG>kVIHyr@Reb2g*k-NjWJPTg?`FF|1+Sg z$`d45vMUcCBrA&;~rn*|Ja(}2Dx@<=B ztP^Nf4Ok3r^37R3C1y-vgjq1GRCLtC`|o3i(!y+l;{YJL+iHLgPMA^F?(7-MCqubG z$h)5Fmnp@p^cH1r`(7yFx%z@cIau2CJAz>GU1F>`eVYEGi$V0NVU#cwh56&X1+$7F zEip`hW-z6y3@jF8z<%*{>eaw2RPZWez@M8~dE~DaJ|*7+b5j*96(eDMMAZQoj?6cJ zyTA()p54l>jtl6A65fwvTOpKyV;z2YGl9^M#pQ@GWfX(S|Harj1!n?8X*;%U+qRR5 zZQItwwryu(+qUgYY&-el{PWk=R_)gA#a{MZS9SHN>OSXvp5Md77oUe%uBv7qhWo|r z+^!i?ZKll&!NrzLpSmC0hJunl<>7JKX}jjQ8=6F2T3qZ1Jku@^$kV$0+Qz$!1?kZwa!L~DzX1KQ< zY+1{5&HOlF=V&TT^}yjiR)_h`FoT*6|VJK|-oxx=Iz# zJDb>S6O1ds}a$W&(vcg&|c;n=#eLN|0%)ZIM?o-Ja-yjhX?*Sv%FgiyAvn zKw(PtB3pz~(mkRymwL1fLa@~762AA52 zVqbIX!bK*P&jhwW&DKdz&^nHmEXeZTOuY_CGWXCr^}M{`wDgHpsx69Bt`x54lu&K- zKNg4Vp|l?>1Au$)j?~U=UipB7XhPl0(W#vYA`%!ioIagaoM@TLa)7&>o(FDcWD%d;ufO+DJGKTDP8_Uk`!uJ$Dyc0(C_sM2 z;Yvt8;YN7#=VCCJ(c$9|wR5Z%SKkMoYd~SxjXpiokUToqEatje4zF;F`%FjmnXHX; z{2Jn)Ei6v`sGW2w{2lyduODR=F*mqx2e(vKFo%%2V9)(-mBVqggXR1}V6r5Fj0>{17P^q- zwkMUChpOzZ3b%f@)`DEX#00oLSElaubNK`y(*cvb0$hQrC#Jl9b0Pv;RgX3(-c#xQ{d(7H zry=dcG+$n<);gR0w*3v9cGw4_9uxYnAad7KYFLYP&kdYrR#vY;TA#A99pdj1@>06K zi@RA74GAA+iQ0iQ)<;m6EAVv>kX{Bby1d+=%*Lsju$~Y82$fN!5o6HqK<&!yiP`7P zxKU7xlUkf^P*f3<&n!f;#Ivc#@T_-XG=PvPSy^aXpg?NlW^(SlAks4?xCI>`5r`-z zJ@EGu(P0kSlCU=m2kEkuGv|f2t9nf&z9-HET9#zR`atEh@;gI%ZNHt#w;_Tv{7R#O zP}<$;J1I+F{x3Df+ZO+}I?mBm1HCN(gg{M=b_%iB`7xf&ds@oO{ea+Pn|?~d3sR59 z-g>M2cO@^9mg975Ds!@&gz%W|a!LJtV%x{n_>N66R*Xr5sc8|cH>X=)-ZFsdbj-cQ z_cYLuN-x)#ckFy6;5^;ptp#-jDzF;U*v$Z3nju+M z5oYsEpUu8V_|tYIH{BdJcL4@(1H((*H=updmzX=X5G!(C!V2V0=(8@riL3W5$>&6@ z?q|LMrQyb`?nPZaale$)0Xua~HC9!9gM(jpB{*Ve*)y+Tsiba#(cDZXZk5}=@-izj zfYGjg%+f#zW88V&%ix5LFDPI1?s`Y2_Or7kWgz>~FFf~|3+2yO5G}EDOi);3p~_HG zptm9yL&;d+b3!^twnMksg;1^OZf3ipN0e#Uctp)Xt5KhVF?U*;_5>=`a<`YJtyd*W zRbF4FDfB7EQK8HBiFGyzX=}>pteVT{Yhmn3Ic|@R0en8j`UhHj5I&>BfW`r|<{KQk z3dS4g2-B8=i!lGBQ^uUjHB-j$5L+5IdnUcWK4n~@A*FJ@unMMd<7Za<8If@B*ovDfeC7jMjxdYRl&&vHjO1R*2 zB-|I#Pu-}Me)MJXH)L{t_*7|ckjr*ox{C2`X{FaxT+o-2f(%C;I@8Y&GtGvqkXED* z6)r{eRljMwt==_@#n_5)`0xRfOc?r95^(g$>Lw=&>B^C=T&HYd?_f_Y z&FXeMB=@znYG9?_Dr{VT(%Jg_G_Z|*MuX#%jWcuWAJ4W07WWq8vb+`*&{)9%H_+4} zC!u8qut{K`*3|a>yH?p(fG?E`Vgibg_ldV=Uzz&a(>@GsF$IwPGR@s^^jHNb)8@)|C6D!8Bw7reSS=K9>5D-?I`A=3K?D z7I5~~EVhRL92wbz^(=&{zS|IK0egNZieN7+*!KsIlgQv&;GT-S;0^oHuU{L5@dyJd zOHHI0BijMg9HKV))20w>F=21H1I28ExnhM6PJ3p%jH2(KCsvVpccT|i?akN)6bOiT zj2U@!1@GFSGk<~}WF-HJ2IjKObp4^?O-}9pCmEkkbTZdk0H{M#>;5rax0091nIg=? z-^rB~+k%?OeFy3?p5>!0;6Gk+R~9{FW5s@lH`9E<-z`!ed3=e9e9(396^}moMjp4Y zOR}SBU;J(Ek`pc<$@RmQBCS410Oir-PohbR&$q04>d=?fHQCjs^ax%`hO7w~Y+Df4 zm1mJ))EoIUVZ3Ov4GOh70Uh9wV)bS;9fPZV3kureEi_QWU3TOh z54j%w3E1AcO}60@k;g1FOYRi*LZR%tkcinv#XUGC8W#S>@I-FG$yKaYUO0!)DT3dJ zFWL9X0D84?M@I3eljw!L-ue|fsKWqZa{~dL-YA3wiaM83=E7?>ItM{D5O(V@eYLb` zS^Bcm{}q+~8iet!<40YOd0I@pbt_^&ZBKIZmG)Rrxvs}@Qn}(DUyk^|$ky*B(J7#F zvq_HHt5_bGUbevMHpctNP1I*mqu3;C zh9_>P@L@pIpodj(d0&-pdvJ+aTwI70^qs~P;gh&A3OOj^OCp|@7ZydxOX?xufkD8g z<;~n{C8Q8ECJ%8Fko4?`oPnF=D*w$DMlj)9Hx3qCiz5`>up}#qMky*I6s6eobpLmZ zx3I2#S;wiw?$<~Wk?>>@Z^_cwMVJ%-4+-$<#t7TUWsuc zIhZp4eI-26BX2@m?#w+AJ^J%{Je{@wfefD7{mxg#1zl-7XL1hkuHA7{OXe;qvBUszuATK`_*1QoC}jSmFFCg5a>tFD zh7}LN?cPhs+6ryoOO6bs))!sk`J63%$zNA8*4Re3AV&NMPA)}Z-)7isz5AKVRhLN@ zZxIS8rl4o;B|5S_lS}pOCto7)#(QI`KlvG$?(+U(#2P_90fmj$KSo!3ZoMpPywH$Q zETGQ6xwlmxY(CBK8-uB-PL<$gr{d>^%+1L@?vy-B zdfw$bO*;3&%lJ{WRG+AOVt>U4M!ze~!p}`6p{{VLy~KK#kGX?~YzUqtzq1$QXVL8s zGB+lD?SO?{5?_p3VkaHHiBtxr1=JLkBJPcSbtQ`#A4aeD#y68}0()R#Isc`Bv-o|x zMm$nuQj@Ape)T1DOku^izO=wZnWHJjruql$%aXG!dy@%D*IjKkF`gyBcCDC5hNgjIL`vUPx-3TM3Dzffc(|7 zX`ANa_jRGd+>Jek5zY&1K5n{|ze-7ye0pFM`p2^6m;x9+{YC$NcH2ymDEjrn&b0~S z#G8|8o^XEe+(RR~2R)&2d=K(7E@&j4ehj4AqyKY)HL*vlvK6>~ttcYHR^rvro_R9L7XLGsT^WKUZ(|~ugMx` zfu*(K6g}ui;Byhh7uSj%`uwj{X`eca;>|5V6eeOpJUYABhtO5n3HhYcC{Zfp_Sp%~ ztl0J?H8Y(fQexX%krhnwoIYFMDdxa^jF`R2xxwEj){%T}+34vaA1Pxp6+M#~VS_ug z1+DLj5}WfuVv+_0=I6|;MI*7)yuN`Uh{X2QW@y9enH_s`t}gGzS}g~ogEg>muaTeI zUca}``iHAWnYxhf%uA-aRK`brU=~9NOHh+<;#W`_T{NUDNs&y?3`KZ1A?LIwZ?MCL zPCKcX*Mr;F9BaZpS+!Y(3GesBOxncG=bIhVM!uMa-RZ4e9*#^+B(^X`y?eCWQ%>D~ z%#JK=>t?jqLxPAq;R{o7eIL2UK!@3!?%)rP1If+8@RJExU`@(w?;}ueI~mV)arHC< zM^1|6FKij1p{Jp>z!_<;w@pkiJ8^#fAhF9;7ea(Qpk6do@3)Pt4K!86tIXYVaTZa6 zvVS(4!va6&kExT3;5TO!8=KgiJvpz{Hh;iZyq(${serMLJRP>W&PX4D%T19#W7jq0 z=xGH~nrb7vE{9f^bM z+r7g1cpUynS->6Fyt67-qN~?t`ml2|?8EwvKG)&yZt3n`Pxx_QXC3&>O(ey;5st#9 zQ0}zLFFzRKZ$Ft@&4kvy5j;Ve+E~@j`9fLks(cL$T!?{;?GA1lFe>MwTr94eR8i2e zZ8N9w^U96FV7AvKi(1`S`u`y3Cj>My$fu|o+BG|19NO~OFin18j+HuWL7vP%@mMux zx0T^z-^k%Tp$x%kp3N;Mla@rtzR9^v;!=o6=FbbFv|Uv!Bw0aKJnG7}**OlUTVrSi z`H4D#m%kU(yNFMRK?eKb@3m+|#{!f4Q3w$>A&atKiKm8*P^m1imtmuJsA-AY9e9rv ziLdl8pAO6>xYPCX!ln8grB_l)fL+=267`G675aU29JYPpmd$g}p9ZT%M7TRD#lwBA z&VM%B)zd+wtUyc<7zi6m+GSEZOh>cuMzV=W#55F~1R<&_B?*@WC(#VpJ6xIQ3)mL3 zqYcw~!M`zkk=Sk^Db707_pu4J{D8MCVH8x8Rm$MhlgILk3&(Wo%Xd{%R3$B1{IIz# zMfcab1nZubj+98E_@I5%a=A)yFrVoEZq|o9`Yn8#D>gM_V}KuBU}pSM6(-{~@$d6E zK?%qLjquS0N|a7|_T5>4R(_HBC(_}7-M}cuzDv6Fa^e_ZvC|tt&-q~g_heni`a9c` zu?5r6;wBP3)AVBccZ$VMZ8+HlNdE3O%kz|^3fO>I1lGAKvg@r?#t_qiVTqhGp=tTx zo~@Ib4Lu4Xc!&O|yr;$Z#+mrJZ`aITDo_k$t88Fxd&Xu?R@%-4#gByqshT=ThW4Vs z`Os9U5Gw%}d$AS>aZRKBRhU_<-g=uOS< zk8Lav>CLzCvhb)%2QTU`4W+fJFtLLBJScdYjle|H?(!AICL{8m!CajzDREF}KkI?4 z`L|2ZidT<74D@t56HgAr9%_AHs`bS#SjK3fv^`>hOI}(h-3c^$*+>8bhA;pPy#Q-# zUh+6No@!_yC3J_%^W?9AWU_3d&t=xfEgH#4&Tfh1x^}J)JbVfgVrUBiOg`kVBhDfx zqYE=wmn%G?M&81-h!x6nemrEsmN8xp=a6+3Uep>7n7+F9*@85U;J|bP^iOOw{RZ}q zAv~HJGq<>fFiqQDz`9vSLjCL2pSrm%;?FANE%$f>Ym`7o+2`p_W|eSYLtY%}(_>gH zOUBZ^pM9~{)d0T*kZTq|5l7&%rR)RZ#}eed7>!rYB!~c*cFqmnjv{lVW?*WzMc#$} zYd(sgvi(b6!ZL-zn|p0`i(HTGx_qhsVbf^u*9)tFi3My;)ITW=YpExYLA99&a{rh&@BN0vOT zKEUQ=vf=U0v6Bj2d7n59)I|s#(NPNnPu`R+Y<oEEf&UFms$&!MDtp^C7TWU_j=&6Fi7lOyh_uNXYhDozW3c)(RTY6hpRg` zyq&9F$vns} zE;ZfYMwmuzIwQ5!K=J7nu%|orcMpzuW2ZHy=8O93(l!)*f^8zw*v*OLhBn^dR-~vQ zFyAd}Cht0S$xpEN_;(xE8Vn#rT)-P=BK(9D@_)ladwq^YP-a zAchC4pvp)%bY>KZ#1HSnY#(G-ne6c{1Yr#HWu4mrm!41 zA)2gha}TDqgV1!gFa8>Sf;)P5d|Zsqx!U5*l{#kSCuK=dceyYVdZMxvpUd`JH{K8x z`m;f(nYlY!-weBtX?<}Sm2ja);lV?H7(PoGVV!H@3If)`;3)`Pl!ixml z^l64F)CQ2gKrG2+_FSd1`d6vN@_-y@Tz`o)_0jQ)T{59wf;&iQWo^hQZ^jvz*FICa zAjJMy;rocH;#>H0vx~3kSU;Yt>ffkzJ|PCy{{FClqFrKRkYHeNtb8j(7XV-beCw(1 z*xeZNM}i^!ULiZJ;YlmiwkuHz(QjeyX1E{7`%z?_rVYcp_NxTzVU3`uR(@^8_C02b z?MRw8Q;oj;9u7al*kqWAsGh5ho`IZu12qQ6Idq}Q1^046+^C((E>N#`>!suKeS#u{ zQ_RNHB>%^KG~vPdmX5{8&BF2BcQNy0?54+D^heAGjRAj^wAnTf7vDkbTKV^b@colBg2o6-04D63Exy8Z~B=I#Y=d&l(6cF{s$CFnus#jQso1g zalfb~_woX^FJ+n`ni*OT@3f8EJ#|^fW-Bx#=;690>=HMj{W{Zh&P!aWEZSvD_~^@8 zzw-x#O%=PNC8}=Qul+j?1BQEE^ZpYgF%}Yr@nZkdrWzv@e}?U82+-|d zr?G=7z&HfyR=q`Pm6kL27(+Hdv&2vseu<3tWj0VxmYHbe^G5ZnU>L3k!IR1t4~ zBQZjVE6?`*{swmp>Hrdwl5*PFy#e~AL4^VVF#xmRz8 z;v`nMRSX8!-P7|XTubl?RUC|m$=Ht@<_v}<#9tuENCkFRWg37mj{aW8<_E$NkVrax z$k>l$6#oE0To`~G3=0Pr>b=$OF-WXPwrB1hP*{o~v<46J6J7m`8Hjmz>Ifv{x930j zb^nbH1@UtY2NH~2Yfse92zLWiAKoDZ+-a@-Nkxdp2m}`XNfM;Xhs60!#E3KvZt5=j zn#%)KP+E=%w5|GDCV_r6x`dPP7+UbJyE1Z&_^M+e%CiR3`ZZ`15w zo)(eP$vjn<_yJB$K@tFB%TIs`P>@uXMFK)YMhA|Fh6M)s#+O6{`$!)5=e8NVMh2Sb zd+6aV?{j&1Ck2@mL>&Zwb*IB0j&&^rn)OeyC#Rx;>h%Qv$$$R-d;Ftt()Z`nAoaTs zyTY@x{d1K2hvd`WF@bh^1b}!b-kDdP%{(u@1qb@+Ur{>WXRd(@6X@Cb%~%-;vK%i&gMvM;RSKT*wbTE1?_{|W^K2pCb}U(QN{ z1ngx01mxih677=_3H(|3OZ+>Pc^x&f8+&`VvXlDs_W9Nu1m-y~2-=(i+3?)4Z1Zk) z$$F$~$EQlPF@IfMj^>85O&;Tq#3Yn+B8*}BLS12$*`a!_q$zb zhWefU^c#~y0Zv>)2dY%U@;xlN4b1?+vbTH4s;v3g=L+D2cIsUT*|-m&-`!RT601vi zSpKN#oV(o7Fc1)zuf3>Ki{vNk_Fx}PH^g&5e=yGZr^>SkiUWrn84DPbYd96<@pJu* zByo7nIv+qK2nx6c+ec|0`J;HS5wfe>k(eMs`Q_^c%M+#}fkr5?u^@eUj%ZmnUqb%) z>u@^q#eVJLA#F^Yn95?#7C{L|kAxrSZmfXZzhu$7q}h%<#PEXXUIGdWF$cT!Sm+`*PI`nzSbdhL}F{EhEkI{Q0T-L=YKYArA0m`qa%SJK7iqO60XjZ-p0CaEBy`R1Yqy6|0BhYt-PfU##&Z9A zO;wvt78aIRE#h>}?H;cQrLvsuQxr&rnltL3)AM&a!3>fu-84d{8=v%2f=2|sB<7xF z_H6PY#u6u34u1%!u{V)Jy?Mcw;sj^dockovWG`3BXA8(*g$^c?a*S);HD%_=9mbnf zwV=k?@Bpa1-uH~u>!3IpnYv2l2#WXEZP;u(o=doP=-byh)Jbn6JNdN3Wt^77IysW& zo%OJ=(JLHTn=P%ukJ#IHtG>10M`kUgZ;mnslF16_E0TOgtu19% zN4$cZKF+B`DjOOYteZ61$!kGgjz{8-O-3ZnhtkJ}7rxT4L5iy?A%YigU*I`VidCdE z--o%p4SM}NH1sn)73DVv603ZJB=MJ@@C{IEf0C?fRVY*g-Ru}y!jqGvPFT%dMOO9v z^CW8npnG}|l~hHp7;T7R&Tne>qQO_qUwxyiT^o zf1jZ+sWkW0X#__~@9!Qu~ zX63}2C%4c`VFH=hIkd)H$%l<2LI)_3skwO_t!#j=GZ; zg;{v&7q}qb_hOsKdl~8|Hq1VB$a0zH1pzO{l3_m`&ms!tLiBG;0FSF{3886;dt8>t}(~Kgc#&$>2s)P>2y(d>jp%C;`E#MZ|%0-M}7N-9uRC@qc5D0WTcQ<;PZMtc_d zy)DcjbZMp%x+kBs2;X115w!Bh8J37*2^pb{0>KE#7>%jR8K-)RW>HY0^e-{mz_V@D z#U=V1M+wEO=@)(9C(?4n3i=EaNy>8|v}g67eddT;$ifu7#DrYZtKU@B z-^5xnz$(Dln{&4%b2WP#{x@Wt^K%xa|rx-KQHpX~HEqs%YcJNH$G2 zyNa)@rl!YRy3E_8U_`j7^}+r)g7_Zn))EHEc~-J?zTeT^U(Q3Py5*2df4a7dOBuoX zUdJ0*}{&ozv8I;0~+)2Ps62ON7JyeQ}_8rwD$2mWvj~STx4S4-X0T_!rNOC z&)bB?k8J)&TYQHM#EbYy~Zu9&Zpm`!+egY+*m zF?E5amv4@I@0612R~pXPp@~kRm(R~a$){`4Fg>*qf{lYL;tIsg&clLUW&+eEK-$#Y zwZ|!zt}yGCT!ZUGuyGPLM#IV~=m>qyg3-5HYYgbngDRU7Rh@6kv&ii^aWRs{E)=K= z++lG)%P$81T82u|?JNS5F9_)Z)^6s#Alh3`dP6^# z2-!o?)qCny_U+X^#FnMW&Jg{J##`zq21{EwYl?kA`3u0 zL9-BW8*~Mqr2M}7UHv7C6s?l*ml&Fe$ka^QXUR1J&xv^(rqs%g1HHJz=ElLyULoo*Tqbve0@RW_6~ zh0^7XhaY?M=UB_~&T!gfCN)CoAU#@T`To9Yl?yKayt2!~p#ncgQq2ZUmQtZJ1GTEe z1`Fa^dFZCc+nKU8S)WEOchcwWj-~r8{M|;j4?hO0xdJ?lc;5Ng4zw3rhT5}z;S~7d zJzqH?j+1?Qp5l6Iz9P3WkcN@omUQs+3C#*${fKrz>Zun53%3a}o8l%JN<|R%ZcS(b z=;XOfoNY#~?)Sz0y=t-nxja%~TpsH@xXNNs94SNz~kfIf+ZP|yyUe%_|!U+K;DQX4f|(sK9g`3W3m z)ctme1bDKWNj!VnJAmNY(NN6i*2aGL~4J{ku z2fE3?JAwQ84_)iI*<#^iwz-$l2fRO>c1 z_2b{ba7|ewmnBZ4kX98dw`uPm5c%rlWw-zG5SyfP-MmW>)qMlq)RgCaQM;fQEqbf< zA}qg&@-GElC)134j3p8XITn`7mpeH0^I!O(WsGkV#(fafS zwO{%q>MzFC+d+;V8)3>#h#b@@F=v{_e$(f1n2LQF4o`9rv-j9DU-kIBZ8-o#9^-| zF-vAnSflBy5a`IQM;oD(#^&)%Maigptd;z@*pHCS>Ht+Yn$_5vzD2YJiZ}qth={mf zz3$2Vo2#W^Cnewk2pS^s$V=8HXY;(Q*|bOc8D!a}0^HZa7-UWDuws*1y#jx16Uhtrsg@exU4x=JvCXM4OqibVDPY%Vi{0rpbTK z|ClV_V;%)PgydBNmdc7U;q25K)mx48fO?qEhfm+n!F3)3DfqA7&)%K zU_%R(jw)xp8Jn~V($4A`iq>T20amC08&Rt-JMKZw(2^#HLLZxg_{~w@GMPZMrtQM~ z!jMy0gcOPY9#ar03r2HOgJy_;N#svhNpM>{FJSNE)apC-EBJ340;WX9GIH8jZ;C#< z!YjKAoQ`MGJNZO;ZdlA^GZEjyGxbYeMGc|!4n*e#=JGo0i%0pb4dO|r#CIVhL!+qD;7B#0Cl2xqS z${aAopJxPHkG}9$^5^wBIyJeP7V|%9L~$X;P0@SvqgP)~^U^XO7>miGP6IQj(i4yS zaW&kvIo@RbPvMzfRai&fPf}grS}aau0&>{UDO}#EEEhP8Y|oZI7OhH4R{I~hw;W2y z+w$=TudCwRbo(QY2G)AfB-GofRZgCV!^;}Nj7giJU&Sj41tl7$>x>{tV73uWuNV@l z4_rts(*ReEC+-6X>*laHbe2ec`A1gVkC;y=vQQkZ37jc})bjSa6+WNdgz3CX>JFzk z{6DSzWAP%hdn$gWWYdIT37G#lL=6;qw^5GIJQo}kHiy=tI|xba zHROyre{rX_=Q$ngXp@}qs(-UpT8s&kCsZpOw)&TqJMe@c^>B+DVTs$xnJ5|p|(95TNwohM$jahfNzSg|Fk`_EY{%o zmAY_z$TKbR_4<6DT~4pk%hzDShX^U{V^h{q^@)zHH+ZAsCgH|bq&C=KyN^&()5oRE z#5*x*pz1?%`YvB<`;d=JZDsga$)XqfV;+9GdcG@2q@zN?ZI7oM5O-1Ac z0uy$iU3#<9w<0|1UJMokXqXckVf3dwbD|$6C#hOQie^3!5-h_J&G+ULv*I`^jJ-lk z{Z+Hjy*Rs#Z#!2KXJj5CKz{}ET1=OVsVQsx+07m$cu~3Dta0x?n&PSpvD&&&7azJ$ z(_X6A)|WJwrp)(isIv2c+Er|ToWi}ow!=C{0LwI>pHqlK`)dmbe+u2w@>KJ=mRShKLb~2K` z+4@JGZ750)k|pky`rXd=%>PbSC9D*xLr2nxmwt_JS18kZsYOlDhkTn-X$7FmoIP%m zz5O)^v#-CIV|n1JL)Z^dh31AJHQJ6S$iwyLu;3ywR>SQ0hM0++nb>-2O?P=Ief!Bmg%+G$k;Nq?I5$}5k*J0w6qNW48;Do z*&X*}GJ=Spf3}Ar3_I9Xd`i?Q5K{L zazAm~EKcQ$ygC<2`)ywXCO;11^ zoOu>I9p7g1%YV7n3}N5)MZx#Tdnm3F496Jbq-OwdA;hfc*zKMm4jgqfxr;sPnA@Ao zFRt(w8oX7)*f!9_K+GN|l2Vb(5iS}Equ+vHJ|doF<%zG19RDh67N%q%gkqlVU-RjD z&@=S1fJq|fZz!t~MroB@8zNEkg=^h%cbJ7yw=I*anbc$lSp4&L7LBbltga2Pm+@By|Z^OYUy#-tSdQ z8m_2hSwV7b#h|R4Xt5H88;f zrA~r9i+`sdq>mY#T1Qd&M-{m-bz~A40a~c~V*W-pcooY0R5jt5y6z_iywAQgHP&8< zl^STH<%cG3R~dI7<1(*CNF6)N7DS*`)He|tQfYsNeZnSuVdb^NK35{LmSsBilTpFv`L|ct3Q_tj98VZTblNZ=NgWj1 z->YBME^_D^w!?Ny$6h6!beuXnM6^Ui`{@TXn~y>lYuCR5W9~6orW+!8;isa%8Y>o~ zjaD349`H@&eX z5<+lsG^&|Y5#D1*L#w#{qV^M0^PEuA>z76{PR2DSIkK5M2AHeeow{N+rBX|^Jdzt;-=jmU_Sv~q-82IwJbWUV3AFu#b9 zjGesCXeB*F@aAw4wA~ZXh2^AhJEX_JkBSppo4Vy7H5y z%uZPb$i3qBSj6qfDFLV?(JY^Q!p#Ugx<|~cPrGF%D)kt;9!GowOv2K?B77dn+emof z%^f2?$G_fBeSi^bFx``-uF#(Ka$*0x%g-6G+0U5oKkt_)QHqxXAdp4}`qS&{Pqgb|QIZD9I4A zQIXBrb6w$g`oz2?Dymm6&E!iw2?gd{4+BGa_>Hc1SY}mYpEHA4ofeEDIK!@tv3wWl zkLJp7UAiv?e>ub`hQInsbIeuWyIQBDdZAv0qipqTRILVuMXxzys9s&I zo$wFaaQb!fze6EU(MoBg(@_kx4p0{BA#k2!OMas`$S+31T}a6QtMZZTb35t!B5^5&>>Lux-B***MIKW@PVoHP46oQt}zwIWN~5YG3SR2aNgI7`N~-0YbV zv?^ld-I~Q?e7tgT|BkoPF#jVi*Z!1A%en%ytfULdQMqD217TrASEPw~=dZygC(VT@`my|wd#^QCsC$(u;^EehUwqPr z1rACvm74EvYC4<8KU`XsNA=4C8^eebD*cD>^V2~0f9b+<{GYq994!B(3(LjL{BOGC zf6_;}xw-zkOCz@JKf16nDJjjaF)6O@?%`|^!$6>L>_gL%q}#;XY0HJ;R8mvp%{bLn5LBVG2YsJ}hgY9N@}2d|*BwAOc|} z0%9e5dmu*6w(;FCqzoz{f-{&_2unv0RpMD9E{q~PunS<&znjDa51(I9hONfHcM%a# z4L|z`2~Hpb{pvy%0T4(=kj`G?mf)^nXCl@8L?L7Tp@tZ3qC^FMban0R?Q?`ExhTQR zX(t8|96?F1fOv?wpiW>KAwKP~3!q&=zE*H3F-V2x5a51P3Sk?B+kuUU`h)wCZNZ(x z1lzmaS|J925I2B3X)b{1sm9+FOr8bd*Ma@vA^V3W9`hajJ%13u+`fmfEzQ84fSV7{Ry97L$;7p&H+!1U05Y`5;4^FP0IU9j_ zb^dV3R{G`tWLtPSP(nA3w?O|XXpke?8=mHVB)AH8tLO<~p6bPp9 z^^G9%zj_E0D+bJn;t~YLQ<-Ie%1v z_YrCTjTsX8oBUIye7WPp%&H?@?*1L4C4vGPG!#Ot4j=Lt0s&&o3ukYE==d412f{34 z1-st^@i^OnGz1Ma`Vz1d1_nx>c32>kjKJ(K`6MJGf!k~RL`3nK-}vr*CV+Tpy9zV~ zV(9W0CI(6$>MMW>m^#k~LTptef&+%&(GIq={U*iqkOcK5f*O7&RLFz;>%VvhBS6GE zE|};6r0Xa_^l6akNub>E1?t%Wtb6klgxKQ!4g6!{pJC(cWMcAn`T4G_k zS59U1n8bU3tYOU>{+bf;n-xKOL{3M0YJK9PN#YP%|5VjA*#lnk7B1P$N-WxFTavMy z^!_h%NwrUR*f{%%4EeztgG*3VK(iT^BU-!1pc|V z^Cu2R@(VSOD080NERRca^==*TZ)FGnT|8mT=X6PbwY7j2(J&;iz#vV+RKA}>nBWe+ zt?V4*wOm&bMj3LFbNtJj_-MKb%$2OZD|P?t3;`2)Tg=8L$>zv|jpy!Sihx<E_Y@I)Pb|MMcc^VX`)im{qrj52A>tH9(OkCzOxy+F9xDQ!SWt;4mQW!IlVC-+$ z$anYrPT*x}mxsbiwrkggT3?0rPg=Nvi(1fzT{JQ8#sIp?3sB>y<-AZV$ zQcBUdS8*!DSOJGCk%AL#1d^;MglRUB{>v+Ir`HJ1JVL0j?-QukL(yf%5Jh&aK|P+^ z>*GmFR{)75Icjac%1?Qgt>88upWn%`)x*B}HUGQ=a#bNDU{eEoYc@kTkyYA@9&Q47 zVolS`3Lp_JA0TZ9yW;Fqbh&INVvR9sN^!UQZ0VA(CXP|vyW?Bj`%NXqT(c?tCG1x0 zWj$@(;TeMbDJ3jan%x)BSRVf{9SL!6@pzss475ci(62VI56Z~3=wm1;n*APzGapq8 z^wN(m8ySs972R{^#G|(Ax@}G<_K!PdGz1^%$APWn?Pqp;X*IE#m4pF17&UGSBWb;K z23s+ph}E(g?boP?Rj~;ndbn$}`u8An;lP9w(sgWCjkitG2WN}Rq;H_0OK zHSbb@3>v|YH0{6;-PuhnxQ9Eb8D4TqM>!ppd22yhzf!yuLD3Fnt3cuhl>=Djwdzfs(XP- z4OZCFU3y?K|1R0gA@M+q4c6rl{PnV};Rpr}7S1dh#>tBa|B6wgHrt-RK3|1d_%% zon{B;ZmmvI(gRtB#&=OF*E0C}s)H1s7TPdW@i+j>AAN`K0T{cDqLL3m(F2F>RsT!m zBjLD5&*MM{&4%^|3o>my3FC4YMA7ACOeV<(d=iw|V84TAxdlcmT{!Cj zGwV^0%G_m?t|JnTKhw!tn)kXhkPU4kJVWXik8qq)mfia%Vgq!T0vPveQ!+hg@>oSa zhS8fL4X_|u*s*Ce60OUU2K)|v-iFG{KMmW_j7xc!Rv9~qN;pY~9gHlM)hSyLQv6wOrFaz@syrun9gK<*>2e~y zsDM!)BvAxRozlRzMc4_~HfHJUe}YbAA!^G}G1|OG{JiNL_`hLOUe=e5S_WpKo+BGJ zoReQG6Dbbu*$OnFqO-kuT~{`0Ak+ZyX5d2zMT(L+oCEt#kO)?lpu0`>cLO|W7f`SO^{5th^6$X}~{PnC7*@U%4F9O&3(`AQyZj6m@dE!|7XrB}>) zJk1alLKp2WI{5*^rwC+EM)`w0&ck_RE&x$VFRHFm@L+$RvP`BYkRv6NK6w;b39+{e z#|?XmDgUv7r}89aL}~swmvbm5C}jVsLv(i2m?$23`Zv4ySPmtxdQxFv(v{IH?I>Q> z#!&O%-{x1_NVhBJFk8D~BO&5(tT1^XO}U(8Q-_(SDJJU_J|ns*b`AhD!$NSMh211k z{XiuBZcsSDX=f-z8&D-6KEO6Iu;%^LgTvQ1*eAOr*#+-ZD@v|;O^=_W`F#Afi6R3O2(_V_d{v7{$Hy!`T# zXgQHwduf>^;}1`oGbK*CkMsnS8&Z zG3`uW zG5f19@rj&j+@qtvqISDBNMPS-%Z9@9G(b zOk7|$V1^o++#AEJex9yMLcqs$nSWS*Mr-Nr*}ddM{;M?ZfkQxd)w60{fN=XM^R9H~ zPSHi?iA&&du3AvLymTV?>sPY%tvm7T${x%;M6AxuaEUfpth zJE0+)Ft)LTEMOuuU)om^d81gEyDqe2<^auC{efIU*J378TBZ1#6Ix_?E1XHC9R~zX z1|OU0D=`-eZLYSTY9WPNL{_RUJzbnf&rjjE$)Y+J0T@>h9K@o9_6|rfbq5dDhv{D3 z7d;O4wmGf9iRzlfh|`BN5%O|}ic*v<%QY?&^|1wTd)B|ZSTFG8HESZR zM#PT6f8)?c;LA0A`0-vBI&xXnOM%wfSg|OT#qRs&_9+rWqZWihPX>2&yoQc!YAF2G zuD1KHp?|?z>U;C6b-N2;;Cdek^xgx|GWmcCP8X*&8cD^N1nV&yL#P?O7-yJ|P^Qnd&bld?llH)&rCCx-E; zS{zZz%^$W3u!{3kST}hvfJH>!I*eQ7pn))Vkz;c*;uMjE5Fp+r#i4>3EcU_pfXw;r z{q<_?jI!LZmC$#DQ8T-IIBtxg+F1xU6vk)IFy%x-n!7TpFCpGMe;+l$LF(j^oAL+2u=Oil}v+#ay2n1Xd4NoZY5RT<;#_iGR^_yG!c=qzJ0evVG@d(4h_F(+k$4WdXcbnY}yp$mlm0^jw#Ou+^(P9M)uXLhG6BFQ_>QGq`As zs9w3B;wurE1ZR{fAi%1opXivkA z$;U3&LffbGiD=1qQ4A+}Oa^IH6yt32s%Rl1*X$58`Io~xNb+A=Fq!~R87_#@=`ucS6g%&EFrrD@Tu1(;c4EsFf zrgm&?z3;!PQ*UfB=VQK{?88?(3W~6!AAof}x+}@wbjKywNE=-ot4S(!NohbLhAxhZ zb#ocRU{*Z`I+UvUxYBnmngygaz8zfM&#QaZ96<>6y&*d+21n+!i%(ltL|E)XWTZ$;v%r zy#wC~Z8&l6pjn;ZMjg`Sw{l)lyJ*n0`zh2b#ht-Y!%;CuvxNXY9c=pKFke@KXy2OL z%_OES@=?Hu$aHSru=ZC;_h}3%FNBEZ)<~-sXuza zkH$GQ^sUV}K#Yh|g>&+N_^OmaC3@UqaTfPgO^->1q)7(G3aECyD`DJnJPy81AF>KD zx~?8VfjPnTaHz-noT&Nvs2sLPZkEzzXK>NoK4_jI+e9c1w#(?~MpWhLI%JdK(+|!f zc%%|Uc4RPhY-pd1&rBXddaPSRj6BjCN{^v6nd&New6Vy*pP+7@7QVr{&?!GqAeVc1 zM{Ln>zM#`SCtDsZ=mEreChZ4LcpwWwdaC?U^8_{0-I?^08=;m8pU2{O;bsIg zlA`^-Uil@^WDJ~pHyy)lc2%I=EH-)7oke!rqaZqFRy*6u5QzFa3Hy6Q}? z0ax19{Q}%P{+JrIouyYV?+oibMfez6QACMMF>D%lNmK zOURQExy%-8>=4iL`|*@FNk8u`lm7p9fq5G*R+i>*=Tl z<@)7$(JUTKv-9E(%A^cre;&dYZDO-wBB#y|X@~+|$9HV0K`7Cr+)c9e@#nDDfbI78 zl&2Sh7Ve+N#hI$T#9Oc8zi^=U1jXP*ZRJAkv%5v2;?PjN~^6scqP*Cr$zRRC4v!sH8D(f;8qJm_Ygyjepc!%43(C}Wcx z9O6wLiT=z{wKyb09mJv5KO!Ov8W%ZHe11AY71|tojlIzqLef@ow~^+K@Z^Om5u5hD zMT>O7EKg&`;x2fMK88YKprKR4iYQp8H`&UmI5x^|1t^<1U}Shi1yL)mKMzuu1k0(ENz|LF9=v+xG)pG+Uku%sL zcV%AHt(AGLTz3`SXS{gAs3o?iRojRp{!Ua_p+PH})E?Q@iE9N<+4lnsoz2`)i1PXv zQ-<45Y*O-5HJ-FX$ssLR3!ys=B?8z_hW8wmOC0I*q?v4C=suD*vxg`{F1U|=GJZLi~J6o zuCUJFi{zFKP>2E37Qb>b`fw~PF=v+2VL(-DK9r>jEh*8EFv3cn8FxaTX|{VyJvAle zHyz$_C#|LG0udOWa?q4z2VAL<_)AQ2u9I$-Hx(?*y6QY6qzN)}WX(8wS^JO|PN+#7Sz6F;3?Y z4$X#tB~%2{)h>^@qv`>QyN}3_m&mWjaR9W)!dHrojcymMDYn?zcVv*U1k0%iVDvzs zzbt4}_y$Y==DDlT6nC9bSR`|(T|TyDU^Z%otc5mhOwr=A6>j1*K|S5?s-&Q?4qui! zTp?tZ>bbGB>G{T6RvDZn`N-fe(YHKJ+ZuyeP`rxonrg&~@A>Znzcoc}p@qz!w&TP` zoX>m*h>nfP+Z?`k`X*>MlcwS=T<^0DPrJ;GzL(HRQm=8208yY(*n+`zk+#ZaN;shFpA;ThwD6!v#S_N;}y z7m^UP)1!B9DXlHWn^FvrdQ$%btmd0R6ZhgneR0w%%pr7;*peiZD4C`-J`R~shJ`2S zU9p-Gr`V`*2P}IrYvR6~%k1WQ@{H(R|Doy1({G(_ipO#gakf{9D&K|Dg9?yHgq#x= zc@3&(=75IeL(&3=D0eKPoz`sFV}Bm;~?B7%^S zUyb^d3oV>G{b5%(?1Rp>9@B_wWYWx3*ADEwuEl*_j2+{ml^EfvTxJZA%2-xW7ICwE zFJ;F>Oy)%7#Ms;V)=QAlM{?i+yz>ZvR`-h;Qi1I5O=`GYI5McpVRk34lDb0|jVs#l z)?AMpGJfm!vLWZ6k2ncKcj}Oy-Gm|ZaPX=(MjZ*(e9Dz|}OBXp5twvJpi8Kr6 zKD86~gtRMER+M0Ct%l7MO)rrEsmazLpVG+{j?kz7=kuypQh=|k5z^8O`=q$(3%SAk{A$s^HBpu5Rm z{B0KgW#p}dFdKZVgs{_V=xeozZ9(_)xi!F})#$Rb&-8#-t?yVz+x_6~rwGQC6`Qk{ zN4EPE?aA9t>B7_~yxu#5O|3dfv{N5ow>@c=le^;f4#*E8uXO4A^kAS**$Qm8)4%hq zRSCIOBa(wt3JL;kA%@+|J76WOV_@4FZpSHp<=hkTrww?Rn1*yg3%?)ApN9P#?lhAR z?PKE2t#mhN<@rKq5acsLwaJpk)x=CnhZXYvZviEv}gQ;DsGxT@^-qut;E$4o_PNU9Ul|XS#-Wo7Hv12Fn3-d zm-*IUiA)p$Y{N-dG~e9 z*vImQBN~!Qi~qMCf-@4Sb&3A1P(@o^uk7|1!sFAL)soW2DxvS33fI^y7Gc6PH(-#Y zIZh`gVY%|fi}u!dta=kQwmMpy9kHCq!~=eboij`k!Dn47JGm|>hgPqs-8;g#oEnmI zP6PeoQ#SrJn<7kILqQ4d{2YSfFrg7D8I_8?giM@!=To<^G;QOSM9P&(>hEsAm&R+H z!)oY)Ll)wS%AJ*#&-6Uw`^=P2$TzW51k0Q$!j?CDzMt29-~enmBA7r>GY^^kDg6i5 zh9T90p>_x2L!qlX`@SdxsFI;GKjOKG6!fjcDheuxiv)4v3gUG<4AX;;dswW9=eFOrdsnH6Pr7@hJ>z%qYhI$>9M;3%VFoZ5TD8OC6$uVz;~8{6 zr9^e&$i{tgE&dT{iu!eRB||4y-yDy}X&qcGjBONPO?DSzdSMNI3Cj||$Ws;iT_hwJe9 z7B^Ieo8!!|T(Ho*UR(L-uh!RI%(#{X2x4K2z4$UneUnEla-LZ4z(Q`8(uNJ0+IE@> zUaxbHaf52J21$lDBij47a^{}|Ki|vvWA;WKy@G~7IIdSgp$26CIMQD(3M+HbGHhgC z_|cJp<8XxxzKlO2N7t!~-SF(Bx#wz*riOGjVyrljV3;J?>a)=F5F`Wt(jY+zRx;mi zI+=$|B9=QXtn^Ows*32xhEbgmb55ZTw~HJHFw>Spx&!beM27{VTaD38YX9L<>7iYIdzjw0d*3@f3`_(~|c4ps=Uvh=?=sZ7Yi10`3A4 z6W~2ni@k7NRshYtD9zkpURQRLAT+TtU8999@vSVa9)NW0lD*e5I@|($n>}nEVD{i9 zQSVGFTsz%A!}c~G!@f91?#pC}HZ?6LrH8Yv30_#$cxMAZ>HX?joco>C5A0lCZ4xRcyV%?+(|>~t*yKV9k@uZ=1oiD zv<{Qrk`qp0`03)^M=B_gbh-z|E+<;1@)J`^pR<~xCcd#Vy$5lx?cVk8f10u0kDxUc z1%{ZTDI01S%S|HC zw6Sxsi57i7eEys~XKjBaez-wwD`|g@eOi2#4tUeBF_H_-OD#~e^99si$-)$vf>ew8 zfuw{QHQpHyFWsJCQ5Z?krGLy3j##$zPG>J_Tm6lDtpcG?W#EUI5^Y_h_IXf0)q^-1 zs=^?I9;>6OMy7;-fTcRcDt*W_;{@?0J;^YTjOW7HMxZlqF0a4f&8UJ3F9#-2;~ewa zwJddJzeEUl=hAg8RDYtvfPY%ggiS0!M_%wqaMlMuT^Vc2)=8QHVWN?~cm_ikVUHI{ z&NHY$nE)WCmAI*%oH=BwL48t+`8(Te5A8As(H+hV|5SWyw7D2kx6ZrCUo%n+@5Bd? z{7JrtEuv;G+UYZOce$h4Fo3u_;_j!kv-+{Wr2y(Hp5%6pn^phHaS+~3+J=#7@xGn% z83B95oaJw^0|}6l|7|P`TZbDXoHvsZC^)DX@Lk`KqwD8X<*ZJ%S-~p z${Z?ZApVr^+`IJF;zEqVIT(fM%O?N zo#bN%-O` zJn2SSbdcyB^kkw@QulK}L`l$BDMooR=?Y4Dl+NS07BYe2+<%Tl3B-^xqViteQRG$& zd|5MMs~EGpqkfM0QeR|sd6_P+J3SJuB>np&0}WRmRg|og>El7GkxOdQdp0AHj6B14 zATM*0?yZ2@q{y1@AJL$aHgJ^I?sTu1ADiMu;YP zO2*I5?<9KVIUqpbb71`VkClIoI^VDLmW6)X;Oa(`NWV_FAjB>GQ@2aUjhpuVwyop7 zBbRLy_oR;3f;!5_4hHhLL*EdN%v8D%44V5Q0eV!eG>f5k_FDLN0wh3g5IK5 zFdgw6e6e1%U9VJ)8%cT|wo|_8I<om#aItx{ zkPIF0T_q(Vl1Pi@l;|s#=5D9Rh1UVHW)9MkOXoogM)Uhbfz!dOa}xBRrob|ourlu- zlSfa?H~y)dtNA){qKazX-azy$FH&A3<$0}2xLBO#Zc!hcYj})OjAAKsKaF7SWVWW0 zkqZ|~9a>|{rJEU3MZ zNSC1ldB?x0L0D*zgNV)-^f>+S5dy$X+t~p65&-I=f2gV8fdGm5@!S144C@{MT++ay z0R4dgH!zqNq9gQR4-cY6*4GaqOnzKIAo@c9^*J~+=6Cl2P|b+ZK*RC@N%_3+>;>Fhj@Kzz%5vUMt9o^XEd)!JmO9gYwTu?8PyV zwZ#zRo&pYa3|vRR@pXd(=2wORpdaw}8+8gYQlMpL%fp^HU;TT~yMSP;0URwq$j(JH z&(2n%_g!9CC(gdV(LMZYy@D8hFZ}s~YOP=%d|gX`a6@}AVxCmVr6~1X3oRh>jF*jz z1Re*r9hck%2!^i%C{EYb{Z{)VxV*pWvH-RScR`}o&GJh<(Fdpt z0i!AL)o;u1R!tkYpvG%d_-Je+5?z9{@!t5AdT`M<(7+99o1>{$}Ra zW_h3=LRem46S0pPECndA=;utq79j~8>0gDd|N58zBzETweK||syoh%M_W9C=KsbQ^ z*M#T}`bONHZwsRB%P6oNaV+$+dqj^hfxp!6B|jk42%*=VjDQB%-=Ln}j&k4vGJzQo z5+sl?PPaE676H6~fn5;7pS}^V4=t$pquG>R91B0@qqy)xOt*~-O^W;r8!ouuH^DCv zJN!v-pxm^S!9D~b>>@7Z@Raf@$FOoR0^M~nW}0{?G?zE8@7X*`i-rut)NJ~EkDzf| ze+)Rxl}BauFzeN>_uaQ@zvelG6Xh_}dd*>TNG2B#Nsjd6kArq*i4Fb)n~cJ70$u+L z!nu>Eu7`*Rw85&;nB1p)U56FvypsPurm!kklSu9L@}rqXhcu2O=_Zw%Lp1BRXyw8u zbznQyOnpCI0rjBLGh@v;c}uoDiMy(f#s&6SZtuqQIwEG-HDc38$SuQ7MW`TOSOQ3U(TEP(q>`>9Q&^S#r*H)g+Qv#?)H9)% zH2+2TKREkc^wQS2mE0AfH(~^ITqmGSv|TPt6cgUGt~%D+neew|lLmR@YrfBWW4G9k zoiYp&?gHihi6Q?Y_Yt#?FWa_@9Q)soG6m$UinHX!M`yZf8s(ie-MI&D^x5q(d-UOP zj>1dlKvg>N3IAD-soCtE)i&v*#cl) zxS*JgVydL_yY$OsO5z=Bpp>LFjLZ4ZEMf4X96NW9Cj%Bybpg1) zJ3d~h4Ze7k5&C(1eH!I?vCbr>(Lea#k`ZhwF-6&GSa=U}U+@OFUTw!DDB{geTl;Tc_lyqZ2M=y2gEs4K?a33(JxpC+;&49H( z4$omNyTH7S8KtO|$@uQhrS{uNK!+(St`=P)5;b% zQkiRXa-RWA;l2}mhwW1T7%z5pnj0W`KU`VxVQXBFY0aJLMRCZXDP&10Y3ShPG1mk+ zGr^5~U{He7HVA;0QE@7yteOw#TxHt!ue(LdWiY4VQwGm5?jvHCH z%XSB^&S;js3Ua!fc5T1qltsg`VJgX4x5<84tF4M0_<&>9mq?-H$ZpaGQTRb+%8>Nm zJ;yb%=rB&QEOTS>laxU_bcf&6Y4JSPyjxe9))K^4gQVrX9&=SeXNQ(*lOr>@!L>4u zU>=wT&$S}aSg>@8|FZqOF{#CW12Z6{^Cz+e9Aw#{?OP(9Dt!0ymEy%}_g zRE5eJGTeG+B1{(_Oz~<){B{RB=bvR`D-M}O zZ>AkZfp=AK(p{pMomHIY#v+MRR-US`S_-npg_A_nmwAT|p{r?dC8ufPjoIi}%p!dd^t(`sj>WRMRt z+9GC&-N7o|&9P-}pj_AihfbOd&}v)vJ{{VJBl!{>p||WxW%}vb8Yw9sdiN0=LT_>q zI|5g7MeKvaZ28Tp)++AO7HW4MMk^JP?bp>h$S{mwMpM31-zp&A@C;d$TUk9|sa%3= zn^SNn9b`*OdQX|oM^qK9s|jbOgwR~JyNk;OuJZVqbi+o&jius)U~Bx(c=7b>L^+$v zC>I8<*ez_55-G>Yj^oo;QdD-#)eUK`;oH34xxBYbsE0%tTA<-x@AJR&@nbHz^ufC9 z*|m!G;54KfZ(lQSA7p!cEnOr?yQywfEh*u3Zerny^?#hJP;1e>N` zC+YEcKu$1g%~;uM-TYb>d*`ABOmA> z83`@6?jlO;FGLJT--_;gg@BxSZ;dC7pD)Rm>rm?J`F*f}salp^*X59ehu3C`ScV+% zthYOuo%hV0JT}vAb7HQC4kfnH({Or85Fxq)0vCr^>z0N?_W_ET%H;!wL7^OceC#oj z={_-}0TAmogNStrC}z*S$jH?fsMrW??26JUY+20jE+e7N8Q%Ls_6 z)sb%1*@*mlB7UtW3pEuRuwl01Z(>83^V{E0SeMyw7LV&JF9JhIm7(Toui>u&;hlbU z*mG7(?$OpM3(v)y{>iGlY51 zN^2dWwxQRl?av|4JhW)`iJNHGkf7D+;MGEhMGQJS+};)H-CbkW%6|j$2O#pW0Je>6 zwC_1#Rz9o8Q)!;0jae0-eM%zQP(~f2CUuN{&Vo29N|VzTh;C-sNQngn1LNRP3*Ng3 zx7*{;naFfR<*=(^@@Jzu|Logt1fp25T)QK@@ZN9^)D?iy^WcnI&41dVU{*3#*0AZx z`C5Pz3Oh5Fldjz*@qDoFFgRCN^zARDt748cL(Nb2rUFApg>9u#juv=*yF%oAb!eV5 z(z_bC|MK2rW^$YIlEHuddl&iKUewK&gGf|~@L7FK%T>P#hT6~#E<~fkv3MYFB@Khu z(44@}Y=zp8_u}P#5{U<3L3pQ6BWh_RO2~n{TY|?bpTo?pUu3^__SImGD7}Z&cov>I zlyOUp=zjzoOL!dG4>I=*OZAQNVdOVDx^${`bY&eG+!oJ{T2)2jpy{o&e3X5x^Ux=I z4|TCro$ELo7yIj7pbPLI>$QvIPeHuH-E_kZ$7sVNrNGfb=X8B%?bEVAU1OeUV1EHs zNUvY5O_M44**M7btMO`GdS*js5OzPG@|$DW>zcPpipF)ZS`W1!f0aAU`x+JkX1)gr z%A1rKW#e9=|00c-Ne&6kCl`2$^)p-Vo~=?QF!gB0`lg=E)ya;()rk*@d2bnRw80&_ z#psmIb&Lo2a(=yR%C`|PIm~3Mkuc8=Q>K&aMB(r1Op+S$Qnxxcje&H*w58C8Z$r%G zW9`gv7s}ML%%IRHBbhZs8Q%A<$t}Y_olRH}EAe7-ORpHQ^+)&CYzc~9P z_V^y|z7!Zlrz+FxnTiqGuOL!Sd<3qE&-#f3?Sj;8eaZ1-fR9kEK%fzIublfM=gPfR zbTE>xD8@>-gr>k0UD}>Oc~2}l#6!?odVlF_S5m!%#UN`ySD?UTx9ex(oYDjZ$$&$* zCV05-{Q3%e$>o0JLckZ|9hM&BYI^;|*M0($z^GAvv zw2<&3z)1Hkk@7%Jtsuw>8qg6MqvU~7O{{bka-TC^(M)McNJYScgK}K2p$s{W&m_?8 z(+e}6Z99n4yD5Zl+Gjm5{Twix&q`1CDhDfim!Hu~3AGG;hE@uHh!TdE z)|+sXbOTlSK-%j`Fb2A9zkiUKnY#0f(E8&8F}v0Oc4RZPMD3Wdr{2Sk1n*Q}5j-5l z4kzbv@b!I1=L1pWDPY*UiAE*I__t`sENPMf`2cUi@S!+5`_73;_u>&ZyrzU(6iAaUTm9*qep+!O(_$idI<~W8pfBWk;E=jqt$4dN1xu?f!}c!n zi95ogVO<`Q?%S1t#m;K`)c7r|&kI5YzRWzXROLy`!jD_k6bl>)W5G7~+p=P0^q(x3 zaG3$%LB@9Oh_K>{TXH<;HZCTYWvGb1(Ri_uIsX>5OvxK`gZ#;E06fj#(LT_` zlzxC%Qg}~Sd)R6nnn{_=eyPjn`Y2i}K)K!nx5L(Q_hqGYdR;M?#3*eqWDt2oI(Kyc zm}^?rP^_sP-kIWmzZZC-jyK`m%yRn#kLn~ zvkhMsTe_Rl5LZt5aV69rH}B+j z8~-zSg8edZvy#piVKFApSSdPR!8>WS4o1q{eDkCCQmwnqD|3%2WC&Pa^rRmyF_&=idN!fmGeFtkg#j}g!$l*V$Qz5!O5J}Zz60^dIPA=- zN0aE2*sQ^ljrv`n<9o8xrnnn-6@T)*l6=UR_c&q^92{}ogy-lX)0p@&(O`2o8n&gv zhrWu6!qVIh%xY!{EAW+AI9Reu9JmDuJR^T6V*hf6nI6~+^tc#PP6asdWckd59s9eJbq@>JND9%hY_ZLO5^t0wV^b(uwCVM3qLAFKG@ox%3Q{fQjP zv9=>ktNEEkJzy$i$N(%u=>GF5avge#pP`@Bj^+zAL@P%_FL-Gh}dHu zkWocg0nSkxC6*LfjGhU093hvf)*8@aJexUf$b)z? zmR|0!k(EZRdFrNRnB!~8@cZy!mC zW!oDIgPD>D&77PZ9x=7a++;bar0I#em8<2HwiQW52X^djFQMNzKU*kr5+q}|-QPKL_c=EQO>X7>+v zW0BK%5Rxk&D-qolpq>0Ee8gm8t0Yn`WBXq3j7LNhRfGj?)?RO>#}Vh6 zb+}p;r}ZLar_yybube6TEf?&r^DKl_T-v74Ij zcFmkG_vMAeY-tUkeCV*b7e{rGQAPBHW@V}7?mNGLSHv3BJRvAfE z1Yg?RC_f0LlPzMYBe`BKYvAHk(dQ(~%GC;nkGmF)_cWBPOvU$>mN)SHLwX6ATewkt zjlHK2X9;XXmukEPM{Cqh;AKU;=|^n{i}0xB3m?8#LAhL7%F`rbJ*uU&uoNYM$Ix<_ zJA6fM5HGAZ1JwTEY!=)5_GdscdDaZ;#wNmv{6(|yJ)c%w0@|5PTN+L^+%Enu3#O9W zddPEhzY8G+jd!sJdQ$0n+i9U|I2;F%O7e=A=$v7BROr zr6ZNYCW*6cC7H}i@wQt8gIHkBJ`d87JU?si%4?Y{|9eYx~ zL2j3R0BWRzv;QF{WdA?sgv@OJPl>>Y&&I;Q{@G}bEN z*c^~~(c3BgCt( z*J=%`ldJCB?%ADF?paJ$QX3v#4Xq*;Wyo;;$AGs0BmfUsSQQ2U1o9zx5GbUE`t!j# z`?FnJK~|wMY^YFS@h@=x9at!V-47J}Gp#HzBtZ8AIB@@90DMHqxH1p~2m}zI;a^bU z4haAh{6F+s{$PB2kVt?chz;XJI$hiPFK}m@Hb2cE_8azq{09dGU49FI4Kwm=X|N!G zbN+d_c{8nC8~l3!JVmfD5idWrNLh+-=1q~o{{H`>LcSr);aKNJzo}v9yWo6WfDU<- zrDwH`P&1pc- zihq0#bn*kbx(_`7-M(EjV1WCeADx@qtKAU&zkK5e*w{sl&>;J;LTkWR`u61fQWDvC z*C8jM{0J?*0SN3+9+~j>{(XB0ms)+fGXwx68n^&Qu6@0uLhEh)+H>T-C@?=>!U4M` zwsIPX22`=muAzi;5WBswTo?l@H?IgSH?%-t5NVZM z$}0PIW7Uy&c)2_%umHfr!XZP!0P<=8OOqo4du|>+cIaoh_-C!3u0VWx=taA}HY3O?t zcPU=@0C%sayHt-_p6i5&_P2g}em83T3JPjc3W=w+;lH?vi9()$-tQnGfZl=n_y8b4 zfPe+9(7nI3g|GqN+hBLO+A6`gNcNGxi#OLC-<2k@y_kLPt(1ms&Sg?`&dc3GcP<$kxr2nWC{ zKDFEf^$`JvreP0c+`XP#(J=O)J5>-DS-YPP=_2UeRJ$FVRc2M7Gkj!}}gH=c&Y^ zTL#Cdgd+^%h%HWrrgNfkO~@jfYp&-t@mz-`@0^%d<6gBY;t%2?iN^Nk3U-}u!0fjD zSX7-S@XJ5nEO!hnVk;3&)^n}ojj7`qeVW zp#|fpBwlAI!S|G~r%n>Srl=m)rHXHwR7w+kbBkjJ3&o^Y@v|~-bz(LziJ-G<4By2< z-21F7=cQXqx1exi{zuRR_Fi%7jw|d=X+FWV)k}d1w)~G_<#jy@6^)qx#n?H-=)y#6 zw{4xaZR50Uzir#LZQHhO+jjS9+qU(8qd&RH9o%_McBOVwse1NW*(JRy9155ABxYPw zEMbiYL#IFAjh+dyRA_9a-d|$t^OBR<2r#yCID`x9kS6kt$!ex%KL%1x;lTl*doouE zvnk=84+U*#K@>VnwzO0PHC>fUTpiWos#?un&AQ7E80zM+;jT=0y#>Og+uwEuV`Qjs z3>19}67@6y2boDn^pJ=d^iNewvF?}KZthq&#aVl~>_4Ip5@buMJ1eW6qM`RVA(8^< zqd-wO&Q!X8_+PRUQZ^x(2Gm|U95!O&;06@m)SakFjSk7EvyIr}@y67z$`kN|vOnHV zaaC1jD(1(slaF3O=;%~e9{xiTip0V1Px}BjWz_)~svV@r%l{T^JTY6wxQDW3bPgE8 zAQ&EyZK_dptkd)DHY%;WE+#YQX315T{$=IlFJXQ6$ZT?8QZW1B+=sJw#y0Rc(>G@= zf!XkI?DYILDJ_oIsvIJlS{44ds>RYNa+Gd-e?Kw(FaiexhW~&~5G0za<85G27VJiA zQk$3Sz?t+0s+ElYiea1zeVY{N$@X)U91ImIu4MhGL(!Hd{)_*a$ql{P^yPmzo#19iF12PGzSKOPPUGi}?fDNVulqg4Ak>ait7NTNMyt=t4RcGh zQWj7@u~-)5YGY&XXAOE}aNRVKxR!xriiNaz>~J^sG>QtMrlws71zQQ;SA$r|?V`J> z$@s8eHq)YKF*z7{VY?arM16?ZmwOIRNOxtb*wSRK1`A5wA zgG+}t?eHv12=&FtT>;I;AyHp8;`=oL6&K_C86C?T9(cDb=3kd3p={CgrQB0<8oHAC zBv1(Phwi@);fdo|O5L5y_=g%#P87U)d6-(gs#tRtDUA8GUzv3L#e1TM$O7iCgtcWY zdBfI;ohUA#u>w+W#qf|F(d*-(zgG!itrC-I4M2jPyKL9==Mx@fQN5REZpM~3co5d= zO|MaT?13hLkeQz(IilvYvH;~w%!=+_qvupz!Og+W7i^OF3h`2x~O?ns;aR~ zRaW6zVbmdygY7gBngY0qXq6re$g4Y}&bI^Yis?GwJ%cRn_o*K=Nl|Q^V=SK!Q}LC} z#QatNc}RB`t8mpT6jwErjGk4v-YGeX`8Ktvu|6d@>T=<;bz16&`DXGH%c{20r8q~~1*+G# za;|4bs9&^=`@~Xk<^K$!1XWH;lZ_^3$_jKEJUA7@zX9r2_miZr5*R9nK2{TdpcAi- zOw;N(q5sk6`_!Ho8z@V%bGv$Mr4;h8q=-oxFWz3`l*2Llz zoI9)fkr39rp2qwAvz&voP1+vN$~Z9k?ns?BFbYpQ5vbK8ZHtC&#t= z*4LTG`T)ad72>F0IJ34ciXEE`EKiLKJBUAkwwC4=kPx?-x|ku)e+U)X2SuIo;bAS5 z`z(+kL!&2^8utvCp^4oIDQ9D*Yl0lXm~pIpa8uResq;L+B5T#Qif8+m>62VXqeM5v zkan!*T}CKH%1(I~qOX_hTd(SH%CLd)7anr>31jOxs59mu8c&&vWODi4O?B%TzNyP=S9EbSg zgM&P#%mz}Fnj?`Gfk51_htH>`Yx%;K<9Ng|{by~H^Wo4K`xE&lVpV*rx@R0LTkRZf z>}_Yg0D$p4!+r?Rr7kKIN=?{YVxZX30CJMi>t4h$)RM@g^GUu6zXWGvV^)xu+wM1l z;rCz|!Ey)Aaekvk{${?-5f*m+PS*ZTf!p!PtiN&*toiTF=rda;YuWO(z3PMp%dl2y zha#W^lmHw0QW!M00vLA(=Om4UKp^xfP}< z)sKF7z&1An?h0fY-mUb1TsXaf#CykslmX9^l};{(csw2!=6`8_M@m?!$Z!?`!nWSl z90r&!;>4t=wl{0^aH}qb?WE5z&ORv_cC8+=5T_Y1i-k6w$*NL}79)X}KI>r9!{+Lp-#f_expOs5vnQoik-$Q+1?o z85Wa)I99OTQ0K(|9jdshw9@r8MoPLA?Oap~e(Hgrc~Ay2_$);2jg$22!UiAN*~e!K z8;J!M$@t)-KVoKm&Huy+?ml{0m}?B^lVMy|b#e^SAg$W_XlJ>wk%BH-WH7-wTbFJ4 zoE4#kqOX~j*a`(dXLi>mppKt&dwJ5SMCU23QEwkTBAGl;%2jb?;e&RV?|GCO3E?%lW*l8zrA(8?ABvC0A z3G=UMstRp)zm;W;z51MkoF=agmpsAwsv9~zg>Qx#N{Tp*!RA7VC6zT`*IADJVv$l}WkytX9A#sN-{9STpEdQ_Ucu;1%ZbM?-dLC?jz3^Yhxt}2kF_RN zaB+Y$&T@}EemmqGEN`*C>Yp!th_9O{afetOF z-N_r*nZ9FCyJ?KMqUdnf`F3W>{Y=mfTji~&-_~E}(Xy98z2jvI2UObBNmq0KqJN&B zAt)4H<2Cv!!pya@@f-%X2OdAo8<2EqlT=l4${BHqraUOKFq@dpb1GH8j;SDpfzMcw^e55o zYDUR{vou9`C-d~L84RqouaBjBV-Tz>Jimti;IJ}X^EkB(vadhMt`IHN!y@Rqc)hb( zm@TRW|B(};X>kHdovga`5Ncg&eb4_Hry7&^{{JOcEZibOq%dqdGW{u*m5pX_f0J;Uc;cpP#)m{)e)`A z?fTkO*rs8-BvKg*S7d5vOjPoX)u|pxE3c1!h)J5+sI+#+Kw);Ef-3&Sz^$J-_YQBh zm&Ccau=fjKmMdRD0icwZlw?M@*d>f@R`VjCL=4AtmYHGib>14XDhejG5nuwVm8(l( z`hcRIEIntNfs;#VE6Lck>=JyBFdsGTq7O*dRR4(L5$vMeo|*$HGe?R~?5AZTo&||l z6{W920Wi!Bh}uqHGkYGPXHm~~?8e{wTf&W#BZJq3ZECYjS?t5ydW!@a@N?i5Qg{gt zIH~*xR~S>gX8W9{8jtAP$zl?SO;qC$`7p^-7)qoe%(o1`AVymD+%Lsd)_RyC{&$Q> za5*4U#wxk$EvlZ+77j0D%+2x42+Nc?k>W`h0S6zar5doc!*TQsH_@Z9cqO+OP7S)` ztFDVmHkqDBloLM66bbkea5&)nU`p!w4KcSB za|KZ)HjdYky04Xc8)_8e6xW!fX^6uNPxp`Ow*ypwNw1|J7^=Ng&^wL?rqt+;YRjgk zV{;#GtO4CIdL0wriKMSejB$cL=x&~e**Kv>Sn&xn35xVy?g4Vq#(c_f`t>g447A2v z286dAmtnQDaiWm(2iaglC%388Fi*>(-Fn;=NUkE)A(zeh+qQ3Lh3 zJ{*j5+IZbPryu9p6yVQFnNSIOGWQewm8U{Pu{@%@l@Ia#6aZfc`CNRD7Gw;RV;$PM zwcpFViPf!hgSy3q$z_W2roW|yLos>TLr)QhRB>vi*9s?QL55GNi595shsTI;O!z%| z;V$--&=cWtD`Q@czLwR3138pz`b>vSHlRKzvI;E7h2tuPS?+BiR2oNsGP7?%!1yFE ziOoj4Jn}mQ0>U3tWxJ+FQ>32C6_R}Ttnd0&llX1E6)Qo2*F3^HL$(W^Yvm{HQJii~AZ}|&X2q^4pOYBcK%Z-% z6!np(8Cp5rblPL4_Z_0g#&SrNz(hd@DwiD`r8aaCrWD|Ys%&&hf#vTu(%cx%q~p=m zMGoq>GaiXt_vKlG>kj%b+GBpIkbB#Ozj3rNM`J`N)Q5E-!oPJP*fvKBMC5R7xqd;m zPX5;H+Lf_`#`z(veIqDA_Ya*%4mQ)S4(zpVK8i-%f^Q=h(_J zH)zb>E90InFFMQzQ8m%bNP_r7WX1H6#nB?ke}EM44j`XupY&5PUbo_np%d92A0j8n zL%P7a=F0p+BT>0_&(a>>tu_OD=FWcOUn7oZu?RHol+8L-i(D}@|9mESdipP7FHP9ipilY4+`AU!aeHz#P zsuFSw1<kLX;g)7LPOKqgNG6Q;`dUi^mjXTLe#Pjv6N!abkEU=E9{2 z`eLd2lfCQ_h!sSZdQVZ(`1lQghG2tWpS`j54RA15vRjl4ePR3TK1grh;AhM6n|bq) zl0#sVEAq~%gl$Ot!cJpa;UEC))z^n_1>gSrP(Ss}RL{1YI&NIe)&_Vq)|t}84wmDM zeo;Kx8qwsybtgC`5oFC9ihOM6OUl%h_s%q`S^{P{*a9e{_xZ(Y_{&Y%3o!DF$U+(h z$ScjFg{7jL9}@MbmqS*u!d}ibS`(nI#f=`dm0mpV7~S;N82_4&0eTyh%-_zld}#)M zmjRdCrQA>hGKLafB+Eo|B9(jJ3K^9~~smSW@d;94E_m)Unv2LuccrLL?AR z8qtOUi+k6!u14AU==h><$c}wTqqU-%lN#TcdQ#4m%&o|J{-o+|fAWz4&g%*L7K6xj zadAus5T5bhTuz?zs->ts*($2Z>XxeuHZZ{Ky}1`Z7bUG_!NT-@7`+Ny38<($&cB#d z44z1@S?~f?96m}BN3-#Pl#^iMbfAC4ct8AZSeOjljrFaS?phw=DeRQ~v(psV=jleQ zGTKM*r|{BvNUt+2JcC*@ZRw_^@$o3;t~mmJ77N{*fyEvhq5NaPZL5VHHG_JMq(FH2 zFIxTIT+1V?x><<;td*ADasXqt#>FW;f0{GGi;*h#)_F5IMhdQ#5-e@=-Ol=U1%Awy zuQ-QSvW*E%#YBNfu_x*L=(-A_%?@5)xzp0|X| zr^opRlSM^(@%?f`GCMQ=pw#YiLohWfTKGm^zG zGkCzl>bKEjj{L8|0$b;lg{45c+lTsuQUFnCaPgby0cQ4;q!su!aDr4Vvh1k;zUI}| zo(cgt%*hew(~7*+c5CwBi#fMas}R;EjXq0*Oaf7aWHc2$nk6<8K*)UI=_K~~8eDP{ZCrw9(??~t=ZBEtAvq^IkZ$+Kr|NRjq{2$c~@b!?po(V_GbJf+p-Qc*RdGn(TyJu z)rj464_}Piy#rHlvl{aAmf-~z4yIj%_?}h5-P6+Q>6LD`cq{lC((HtfnDPrug>KI^ zdF01(KG4TkW8%VZ!S;)>8EFM2i5j=82dIqOF_;UYwYf&t3@>u1J2w)bKVwe50MR#6 zBRcuAq}Pka62iJ68q>5w?rM&utx!`D3qDcz!a}QFmerXp$=L@ee$GApI%#HT`GPHc z0ajABjB{RCDA5`&r45O@+$@@kq9U3`WKe1xW)c&DU3s6^*9M0~zUtz27xkW3^HNo- zdgmD&O^o?N9TXex^ici~d?tP9H5RJyD$!Y+UM1ddQi*&o2)n^*ntZ6>XiRY0Ad8;r zluI}8YCw^fggpiAI1!jg(xs84M1RIUjQgV2nPFyj52_tlL`!MSZ_lqZHFEP5c977H z@;hmq%XJ;vbTK1+QP*z>wJ25oJ)lScGj4!vq;2v);!HZ zeWNLKks{`#O~dpGqQlZ+^@v{z^iK<`BA|#Eo|f(X+QtBeHO374KNR;F^RZLoCqDvW zsENF#wM>Ag0T|AwqG6t0V>^rx2tSggGOD$elTr9E-eiLU5<|1$Qz^Ic{@DDM%L}u& zm-+U)#l}H#TkAxW9Hd0Y^>VFO8!x#dIRKun&?#jS4zcvke--~X zIlYA8=epbog@QhkaU=B6$MaUHj@MC7uqW%Qf*AFRlUfe9UL2%^KWpvGn9~IhR#kP8 zn0NHrxm$K&8fzGc6ps7oP-I@uBeh|)+O!HMn=|ZA(-ss5bKcU7MpV&1XeOG}IHDTX z*vzGkM1#IM_62@Qq0CJnb@a!9pAD|&voBp{ERx&cWvdDm<4;I#n~G`Eccf$UH&RUo z=*bWd|IO*g(jB|Cu#&r_Y;ZL}!_A#iO7RnewJS**iR$*@$%*+zlxpd5aoyc4ESJsJ zkXOTb#zG>PttHvVI^x}sU=O9GoT#(X#5>u=lk^tJnJ?_BOTSt`!8PubL#J~g!LOmW zhO`@J*%pYxT0cRQn+jz~=Ct<2o5l$ql(lHL^;9zBtrS+v)JUWvx*6IanE}oN>sm?7 z^2!QcaZzR!pzV=K4ay}(?SLd=2yL_P8??YJh|gHSp*YU?lve1aP1tvFE-U>Jg3As0J)_KV zwU0!zkS&Zd{>N}PGh?c+^R`$-OcK++9Z_UfjXr{NkVq$uQt36IJ2 z1NXQU*jB@6P`SPk_Lrpay`{50C)dd`>1O(iJ8=JU;ajdkxjoan%A`$>1%9yRJkGgg zpJ-fEdDzx6M5_!@keeMSlOg8lKe+h4J{$Ilz%zrume_Vr^ zkeP{*>F@uR-e6|_%gX#e;v3Oz;PToU&GgZbh&PKIU~d1JRgko?%N*Qb(Fp|z+q=4w z_HJ&FdE5!xyJx4jBu{?)R=ieJp59aITKZb#ghfjWXDKaB?Ld+nAv+iwnH%nahtXEl zHGpVouViRxt;3a-u~q3?`~8N)l{Ez@%xJujb_pO300KrB^)iEN;MQg4h#=z~8zAcI zz}4E`)mz@Qv_Nd==sUkm&29&v5|~{Y8NjF+K#nhj`7FdK?L9$dNhu*EupBeLJRs(> z=Rnon-CJ;e9iSrD{s7g|Q9}R1hA6UmgzSaoHS~O2J4S{ni z0zzNY%m5Lb)kjo|$C`%*0wBnzsQ^)O0}1-!(0tkS1HGBC0jZMz^Bej;{HBRVJ7X|2 zQd08bhBS&VLmLOtw>5zUqm-s%>~L>q1d0|k?SqT4$+;f*8MPf%Z5<`o59*_4hmeS< z1c@Gi|5?gysz^!+iegD>O1Z8>&+rQYmeW8sCbzXSg9Pi~Ao;138=QnThr#cnc-*D1 z0&R4I^!Npxt`RUj>C0qva?$?>roq_>VnX)A1RRCrH%04D4+KC*N4M2=1)Bc@^u*X= z{DY=Dv;_Q?miU~8xfM{?7SsdUkGlmnzdDHv^&|A;%H|3RqMfZB(7WSD{S$?xp#f~F zT1pRuk{^Nwb?@d}k7@qH4nfeHlmaP`20qQJ3N%$W*C+R(@0qb4WX!zop*lp=(}?fj^?$v!95DLG zi`@Pp0=nj(5`=uSqb2iVvbIpv4YU+nDk#}HV+?}o_#wW);v^0Gh+FjcK}{netmG=$RyQ-}|_ z?lWq3Ol^Ds%B)cDNZ0(CN$oq%>}#F=2LqzZ&7_0Fo~17x5#u1!Q`^8xGk|d(U794w_#Rb#KSY;IHwZH#`GEzGny4n)(y7 z1~kpw_lMhGPu|zsi~ z*!T6o+kKb({!nnFSM<=Oga4B3@4b;Vd=@q9J?XQ3f(9yq_=y9xfqcn9sIuAHG8#nZ z(D}W7PK_;~b({7L`Hva>-~_@?|N8eOtM(<;{|4IjH8uVqe<6&%Pi^h2oX4H%gGTWa zwpZ=0*!xeIouBJNgMAwSr)qoy57=n@0uPAmKSF}VUC*iZv$T8`q1|=+il2aW1@?14 zhv9Ekecu}P&%XRB1Z6qA)j&Wx0rgP}{&MOf{PQdR<<&;8UqRTLn)!KkaPWuR*T1~@ z68EkjzSkQ^0NkEgBKCUxc!gK*MSL^KsouH!j_rMg_}ltT$Dvr?!1+3TWub4iG+pPR z>YIRLymAA-NtwDfID`BQklL5g-@N#7_#3tV01pVe{kI9QZoff{`gU>rgdE+c1V}te zb$xq&woFQD6nAhsKb~{`SfBiFb$aju`H=Id4i-B*$^65eY{lQLn#uDy4sP1^p_Xdg z8LHS7avk;V!Ly< zl{YF56C}K;02VPT-+5Tt%#ul_iS!|oFed}jP`@CDn|sff(`Pubf5Wg9+PJ)hw+?^3 z0$#ghThqHZ>slP)*-io8QeSTF!}I)1VrAt$BM6B{_88q!u&SRJyqaJz5>4`$e09u) zOnCJrDjF4{0hykbTViRw^*6>8AVTI)pG{C4OJU(MT|O@Yc~GFkb2W2 z|2FDcI;U&+QRp54t35!b3eL1~Aemj=1Q&R#p`o8xb~}EyJ$RPbJ2ww2^vE|Ti@QrF#geX~N7ZACs;J)_wni3P@75y@Dfq(Md=8umNYm;HUGj? z-kEyULJkBUhzL)|OxIGqw6uoqeZQ!i?H6$iS5$+c$qpnM=6w|iq|YV(6p9EU`nvc- z0fy&Ffm$~Zj;gj`}awPEUH!*fH<8*CaADr}_e zHeq^*V|Pq}_)o)7%{MtL8$+)Bm#5$bHxLu%P7-D=Gj9r?r$ksSn!fvE4hIx4nIhHj zu4vVT4#$}NzmPMZTtYxRtJB_tWiIV>v4~%b8)gDiW<6Uj)%n4Nrof)LTnMSyNrQ)2 z`$%MNcpb@1WxXU$%L5@Mp_EAO-Ks0gPxws|>12qg>jn4zotc&v>e*ntEhYFcBKqKf z*?IcogCjQ3F^UJVs^eri7lc*}(q{;x500w^0fKtpd8i_(UpphAT`SsDwQX^QW=l{5 zJIAtcZb;PNiAD4O8P6G?E^KvA;~ET_pgK)3RxSsIaCe}dmZ`tOKHE#>Ri+7esRZ1A z-_J=%D2e&TfMAhU(~|MsQ89qngt?kM%eqCKUkaz5Uak}2poIb7!NaetSPTlki4CT0 zNs4nwgchyWcSh*Zd+;cOaj2h$Gl1)m+nNxj>J{BNl{EkTPm%=e7yz?>Om*D@A5DhS44HlU%@5Lo(M)9rx-JUK<6h z=Bd83$)Wv~lkRK^Neta^3PWdE%ro|XdOQ;i-JaE%<1XIR z-%wD#2@K-y{k{Nh$wnO|N3No4!0uS|Mg>><;v0Ev-Q%u%S$j{lZqTG{r?|O;TKMEr zlq}nG=ZnX%gLE^K^c!p>6~@l&&{X1Pn{ccsNT=P1$Fkt{3>3J;;dm>tW>q%LrnHD+ z2bdzzQ|-;oL!z2DeI(@Fb0Ae>%&OfYZ{~m4G*~hGVWcFdRCIFj6B-p^s(}ZlHKiXHUpKncq65?;(XY6CKR8(QHDWCs|!Fw^JSWV>ouNF zx+E`m^1u_I4N=4mECV`F{@n-Y47&eS(n+DZ{*Sx+i6>_tPwpG$`c$FwvY>e0>$~G6 zjs@zUISo^@XUb(325+?@zb45mQS1J-U8`0s>2>qp2fA;_b|p00lp^z0mRHeoky;NY zG!FFi3BMP!HFvo(>AK^aM6<~G@(61BE0~l6fRjmjghlj`&6e5vou)^eE5V#f6JvKU zuz2raV!wzmkx0nBdj4A}k!t((#zGcjqxP$0 z#p)m^nI9J<)aG0V%cCt@o(#!UL7G-oD|*~bFY1P5y7FT$5{*xIR%6d|Ap;u%zyc5y z&r*H@a<&MQf>;s^1DRI#AN#L4a|>?Xv}){~w*sbUR<5W~;ZxG`YzNle!ut(E-NQ~z z0`)2Urh-3Dz|^v%;)n>M&un_2_w4*D*&hkuMW-D))}W2ql%uyxyYE=X>fx)JM(aOz zQyLPxskX7gN6RBsiU}AUpxozfdsMk1k<<$&W1aF#M*7m1_|W-+A_EmFri-&XEJo&M zhm_dlkiEAa`Id>L<>l;^g0(Flb#*UPNyd(dIB%j<^`q%(YD7)cMjI!bMW3)W9tF>} z7q`N9{w?J&g;CSkK9>{ZN55tjsR}wRm;)2;toNUguCCLP!v|lWt%Cnn65H|T+2u+Q zEy3#XLwt8HLsK;p{s+sJl{}D6F8s^RP*NSZ!r~HmRtUb2KAt*-!YqS8q$<_1ALh?9 zc#|-x-s>1$PPtRR`3d&>Y_X|*@g1s_vmN4@S>gb7eLS(Pe=)0_D&W!2!sklegci86 z*h~{BNiNvNK|Ci=msTz_ppDK=T1c^kxNRMmYG*}XU091&f;Em%h$7R8>v0ifO@5Pi zCJRhY_Fg6>0Ky|p9I>#$TFm!=%8cBX!|dy63)$oChUg8KW49O%VU_(K*}Mu8dJR)V zBeaT6auJ?g>og3wnY3`cRW@CztXiy!r&cDd_Ni=B`sg)H=<5{jM_2e+Njdz*Mg?ab ze?EwIVpj0%G3X6*qgoLkrK|}uj~xho&edT79$zz;A18I8jCuT-s{8AX4}-J)`%Gwp z(3c?1v1d(f`iOKCM=%23^5362B(t7d7b;eif_AEt|BMX^Fj+B)b)nO_`*W9Hd|CQ9 zlrD0xVa;!X=gf^riGEI1{Z}2`pZj3Uy&%^Phq7M90)7U716Kl5C{wCtCo`ftfgoqv z$o67|@_z=k$EIWQ3}~&EgYC)zJyPPgZB$SCev^xFct=WCSJ&*+-LTzbw}m+#LxdL5 ztuzwyu{o(Nw{OXOXt;=6b6>b`%OcbuX86(BwgS~X=u$JI`>_g!mm$sKoKvMfp&FOH z=o^03(^e0OZPK;c=^>mvrQ45UFv5N@9rNQ&PeGROLT~dFyeq@DLKW;KRjSw=7z>aP zQvOyfLp-8Idta{?%GfSaH4j@2DtAwoRF7kw0C0=AATIt-MmcBPfZl7?D3Nh+1@}J!-zzZ~mT{zHD7v!vpdc{0EYd*rt~_4mj7ar` ze32_UhL!pTM_c_Q)5ab6kDD+j!(#cAGQ>W^?79rl^~KX~%-H>xYZ(Kh78iyzlKn{5 zj75T_3Bc3wGUuPFuHOg9vu%i{tYo%<#4Ll;ywev8b#mezhulYrJL7|cVuhXd(mR=r zpIhv>If)l_dqIgTa)bi(S?USXBmBi{aRrQ@esnB`V|u$E|Q) z%g7ROMmzTfPui&QaenAov={V5q@ZD_NPMjsoC7%y& zH~tr>%T9Ns-hN2sf@*M>YKh?0VdG#C&J$zPoYzfp*RNvE?}R#6^*zLrj(5GWLO3E( zDLPs?9V|rXYkRCNZnEr;bH?FnzUlo(AFFt#g2Fc9}Pp9UtB&nSRZ=H z0TEh2gRXuL@0-E#-SD*_M!J$jG4fz&aCxfTzcX5^vRK(}DpDW^*{Y|4cd&z!eEcyt z@6u~G-EKwsHh??xD}|Q_v7UcSu^S5;tsT=c?nWEe*r_k6iGFVIbFX@ZrXpURo){p< zhW(fBG{gKW1B3t%S}=;cHh{hr=Aatd&I>r(2rTap-XXdtUKuP%h+83fkNU{UId{Z^ zvbxuoguk%-g|(5ym5HNd|@HiZE`4 zbeOl)w%~Z;y|OYJI%_UvsFn^eNH@+e!4aLanLTu7x$vo1hLSGt*F=iwldxur*o*;N7_V+IClYI3mHAoYuyiY1XqT{LZ=@}-by~Li- zEK(qxYX`+)b3(#pHAF%PTo*#9(!s+Ah(tBAywBq3Q&`K(X53SBgP_44fFvu5N+SlF zM2Kg1iALf|phd}kAXTJ_t+9DU@jHXvxcxDfoyS7GJv6qH=eSQ=l{g1Bh8K+p7Y~9# z7nf|4AH$ppSZc+yy-lET*XC8D%JC(w(IM|7&iu^edYN}}_4r8OtvR1F*+SWI#V@jC zRu=Gem?+(BI!Jm?_!i}Cb_;1;L@LL1m!K_qK3;b~Mi4LGde(1BQ^;iSzARj&;b8eI zdy<2%QhgG!X-EMEJz2ck3cPa?uHHc0Q#$+%bU18@Y-5f)|?#Y*U;6Sl=M11*`jZs&1 z*2HbiXkMM@di*yT;N`MeKdkw7w-NF_M7#KC`gGRjG%On%j{OftzI{I^IKB=P_dD04 z0=$ll?B2(LptyHD;~;0DaKJgL`HPj`3`@KBvtI#cI<`9LFvFawtHXRg6rnT4%0u9F z127jCThVlA0f$G?ENmE&x9Z)nFl9N^2T|$6Wf7aWAopyrQqUoEp zw~|BW=o6r}J9d~7H-;#9yAsd9s5UyfV-2|q~^IqyKoF^3|S%649|jUA&@ zP_Ep%)I6{{mROv`JS%;GQ+guuD*norWBw6a_Tc7yX!hBI^6qn9t>^c5?SlcB8yb=@ zM%zv_AIe*QGETDLRBZ_HLg^DewF62ngN3&YKRSBOi4g`;f!L*Llw={gv@cr9^u(nL z#d!c9Ckcu8)csoHTb>bNVC1d^zjlWJ*<(Cv>-qZe)xF29bQ|iE+5`jj1UG3K#53q3 zM$?4mt9JO3nc4x9M5^2)?=*NhK*1o=lkpb#LuN+;N?%z|X2m8s*{k!#WxPYVeZ{7@ zW>?^r=|Gm}ND**UdGEY_^gCjHrTbULOSXe-Ds4Xi9qMFq_Ip9 z%#(3<$E%h#EmclvyU!vFySd$WAIW#BboV=>y_Wx%Srp=l38k{7T_`#0YhLT1CliPzYbwcbw|^z)(bk|p2)^!Wv&#Lk zJMoF?%#Hy?4)G~nI>e4FE-G;zBBR$X!3FRV- znKxdzlwlM0cViJEt|6M}jYX2mEG==WMm0x37?L;85WG%t{}Fb~ec`;<9(x#U=J{TB zE~gK*HY2rpkO%aeFP6o%_ATN?CHH0 zB7Xi7UMRsK=h#!>+ACA0bVA;Q;P3uxzIiN>Ngt^S!7)t>n;^eNfu(Cgl-CID-|V6< z$4tOgaSQ%h%x!_*HpnWy$m=z2Rh1xrKieTf=F$&r=8f-cF)BZH5V8vse5s0Lv2IMF zW!e>D#(G1QJrv#%|?ZU3>pSmU3;#iV>o^O51qn_`((a0C?T)rq$D{>m|?dm?(OR zxj8PaY_W!RMc+^he4T}X`OFMHg}-)(I1qzE#iF`avqcUQ#ODd6!B=&xs1S=Da zC9Nt;Bi_fJa~E_-?67MqZU}O+4WB!En&uWeN??Mm{Yg8-vw9MKQtL2meX0abm8Uaz zG$_>WvQd|hX$DJj8i4sQF8*26xH-K4(ZeE6!}q=C6BV;gZqVM0dOi=y&tRr&z(=jr zvU-Vm#a~%_2EgqFukH5HQ~43r=0R~Zj2nh6+C;=`>aOJVzDEx7=-(be zU6Nkyi;uKG>d;LJj(|V#*#536@Q^DYWUSkT<2WXtUlcYbwTk3TKQ%BQe;U6-<{%3p zz*5>jA0$$$4rITS>8pw!3v8zAy)K?+HgqUEXVN)=l1YrS9I%*RlCaQ46#37&NhN>M z6%z+gF-zu_6tCBE)VNJw+T2ookfU}v^ z_~z!)`iDHzV)me55Jo8@C-3MIEAQ+|9t{^l%g!BbpaTvdhb0LpBaEx(9OvY4PQ=P; z_2y__`^o-@Sy)G@v!AkHuUGoY?=SpF!BKGSy%bPkUFZlq5;C*5_2^VUQ-kfyw&2>t z3K{9UAbz{EjUgt`J;3)2kCxjY%Y|bk8Zsf-fM73}vVDRw^9p68AXO*_a-G@i6yB zvo{0S7+rxxblRAN0mLUs;l?slx&qp-#w091HEi-wo_Je5lB~?;9MY)0VON2OEqwVT z)WCJa;5?9y0ppt^UjG>kh;_TUv!-U5S-0YMR`n)yt|a$TS4vxB`b1RsmJUi=*VlcW zex+3k1ALagjpLS$4#P#zbCm#XAIaz~rC<9~_O^bukj}Afn?5F;)WyRF-a(K3~61PC9$w>-jLK&SXYEP-le6ne`5s7 zK~+x0#3&7!z#(A#DO8JxJ1kFAwxi@ttoyrahP8@Os(Eln4m9HgUL{d0(+EXKjn@Z{ zyx#1e*I35{|2#TWP#IZA4g--3*31Pm9iVrcaN}~QLQkk$u8yD%&5Mx^m?XS7;YPcd zbx9j&B9njHSv3K>Q_PPTb^GrW*B`Fp0W%lwu^?)$PY{SdD zfMulF!C$w6CovxZs8lTETK{43dYR=T=aH%=;ailVLAXf;Xu7j(Je`?YLX~I`M)!+G zIY^DD5PW5w4t&6HE%u;d7A>f*O&e!XoyubMn%=I{bJ24ZrQ1|LSw)S37Bb>^S;9KMve2yLNgQule703R*Q^JS7j4NQvoGAGHO!US^dqtwbk!a{gL) z?$YbmYVs5MJxoh{P-FGp2zd4?(Ed55*&g!B8-hX7&ZHoC8vMv&OIDOxGWrGUB@?Uj zKdqr2_)jLbI;;dcg^g|*r9~TEHRDnJ-0dXBiuFfYZ7W0!{Ei@~*2o=&IvzQ7wy-ca znEk6vLjtOBk&yzlr|5vy1yl+kqSUu4uP8HymM$04u+%+t3Oz=fEwr;^OE1v8NB`m@ zaL&AK_9AsDufpRIv%;RLv2^i4NKp%mbJR2wd_Y$0fbvC4I>*Vm%sjX1+^H(#r#Kb0 zP$e#n;(ZN7f#l|3({>8S5-!V(tRfY`zv^Ri44Nb4KY43-G z57H#k-|xOIkGq@LZQ)dwE>@z|7)%U{aqNVL?RamBcFxyE2L z_w9V&2bW;sa6Gk78u|sSCKENj9}CK1I=!l5e6v$#CH~xWxu1jH-q6OThd(X^>PZ#9 zJ#hjTiDJ=Y{`=3VWln}S+DU08uS@=NSzrNaK%Ek2rDtV8XDX_CZ;4qw=?W75m(to@ z%-JH3C0q&5fNE6My)S@z7p-(mR!e<8SXpsSEj)ID0^bho@4t^;VA818HgvVZX!ILs zm>By|4o6Evs8dQGiYsMw#N|9yU@yc~T|on(XEJ;j=&B1-I*eO z){8RIgeQicgtD>>&23>E!r#3FyA!-rA45L_?bk%-f={W(WgQWJ`qDv|3fQ^G&W9p)wO|O{ z233qa_*I)>teB*HJ#`EqtscAY{q5hYJq{6?KIRi$7#=?=%R^)Hi9`HJ$(|=gxjX`F z28hD_1xQ!!T`Kh#nDp(4`L7SHxs0d>kC1gP+!w5=NQE*~;%gq7&AK$3lD1wok;j+R zHJ=h^8;4W2SRv;&3A7ucqW+#s6OgLXa>9Z{#5qx25OfDs<|(DLENrxa%J3GQfvEo1 z8=DISOu;tPc3Z`W@f+0FPo;5t)3vsGDWp6G$25GBb=660HPy}cZ_1T$R9-*j?-z19 zqW@&0L%r9Grov?ZBi@6%kwX6cS08*mtPB+oNe8s^}h?O<$KB2T~ z5uNVZQ$Oeo#rfue0jc93pLjj5$LSkCho1vs)YkLgz$vM;%j?E63Iy@F)=6)P=M(|p zP%r}5v-UnDRQ^@v)M@l=F4TkD$Y9K5w>f1J-rl<;a}~$OCNwjIVRF*duCZYOq8ZK^AyRWGq_soLIq@m-qlMswdh}SW-ALS;O*-omJK9 z8v2EjSj~f^2IiDpFA??XV_>ZR$Jjl@2&05u0&ae7+qP}nwr$(CZQHhO+qUiQ|IT8P znapOEwXUR6mAB4$2!lN>vO=a!%{Xa|7*dpuc`FiZcg9dEBN5RRq>ARGFI^bWORn0| zwxDR#+)rRMfp;}06hQ}|tL%(=U(xSrAH%kVLL=iwtv^t~!S{(P&q+NK?emTV zwG&{2C(Qq~OyfiLq(MXpvRe8U_Y4X-rcP1}vJV>8uB$`qs!)4Em>>3|{2mW{^{3Qn zfIs#X6~gIF{O+Fd@s;u`W>D%sH;@zEVDL#OlF_#x%eZQzo@gAXDApD~>W00eW@3x7 zRJnto3g(YbuBT6TNhp=voR&f@;=(B_2}^$UR-${a5*L4c{1$&l{@M_bnTy{He+9pp zHOhKgv#-K*-#dRj?X*CvKVltp$5!7;R7#9t>CSEEmOICR^mI^ibNqrbW4@KBl9js+^Hoyv0lqPY~1hNYsBYU&MJ*^5D8eu)qP4XyPiaU7dE zbMD?gB*h(zjebGE^9x<_^FA<`D`j$)r7`U`QnOgn!SijIgX{39+KT9+xW+VGMnSRL zM2Dob>Ts!(R6SX)ND|h<95C(=HE}-k4 z>6|3(VJZ=!pp=x|A#J#v*Tdrl{&&na$wTf`*iM%qN|bmY4vVo)&SY5JA@!zpSCtnC zTj7n~X-9FP)|c8vnbeN4s-mY(BY6qD0(I!Rr`(pb3k-09adkwMmyU7vE*_?E%%Z%G z7z5wY|9+H84-u^bGgGXumlqj33?bJ(HI>|s%0(4I{Kh;SDPk6BpHD<+QYDGg& zavV-c8Q;T37xeD~MZ+=&$`KqSRJh(hS*U%p%T?ycVQDtQT$bFY+*wu8PooY4j;TGX z7Bn(qEoy#&h5)atm+nc7=aN+d^*+RWI_n{eTlR8mRd3wuk6f)`j@NE3vq=Ht!avQT z8BS8OCP-letS;>9f`fw2+a~u0q5n^^HOi?k$w3-XX%%-x-=JL=U`{?Cm%wgYxM7ir(Kztcp9eJ?qqsmHsYysm2WK`;xpOHVA53q!6mjyVk8~t2 zBgbGOqwVA4p9s&Zo{COLTU8gd8%mJ$H3rbe8ab?+*m4F}#<`)q!V{E+3Zk3#|_!P}H3bDPYEP9#m^5Lb!)}OXY6ousN2vFs-Wd zA>4}shOacGFBexRJl(CrJ>|{l%<$6sc6VL{-7v19V?rC1D3Xwx@E81V!~tvs{$Bg0 zWyDMlMi!;?E*$0<$EROuQEJE|%A`orVXeQ6uo zksvoec$J(o$?0UK@Yu*Ta4K4~WUmd3LG4}aW%@f|>0^x#J*p&iTESYUw;2l!M0Z~+ z66_efpzDR~zz-14x(+Lsd0!Ns*smwU`aYnrn@%mc@Xv7?RT-}mCZvVIm&e&RNymh6`g3EbxUdU_)T=}|e|I{& zn3vn9A)k0L`r%4CHJU#N?L2G3SelxS7X3u2 z;j)N8)4)1!jZ;(ij%mX?W66Ybu+9DKz^`7^3eit*2B;Zw6O|yV+7iP(T=p1;%wUnLgLZ%YlI_RY^f+*M~HH+lNrT z6I>H$DLGq0x{Q7miHy=C5M*F<(^mM2Fukl!h^YN4!oAleH>uF7iBWKxsv05XalJKD z)cYCcgV_M0yL6JGsvM0|D3sHEZM9RxuKF3l?Tf~1Zt-iJs8GoR^lP@@R$(I0JjG*S zp%(|oJCj*0L05p}R5Hz?#K@3w>p6|tMU>LV6g?D$O~w)3v~F9I1L>qv9XwXBzh?@B zJ=qW^3xwCG+Rgg2bv5Rlk`jMJgnIA~GOD zg#4GIMHHfz-xrIX*4qYi1p2W~b#L_^10DI^K4(CY3#Q#1PI0VTE`$!{-B;ek@=BQK z`|_A&Oy;uQ^y3kzHtqq*O6oK1l?`Rf*WC9$?w)C2?ixo1f{7=ri}?AzEq7sAL>fYD ze)wi0x!Ru4h>>_pW;rg@q$SaH$Y;!Wq(By##54D;T3lF*b~L(G(|6v{9|B+3#t4N46Z$c%jV^ts{uM@p20)9A* zw3*^nivsxY+-ha{io&y6(KK3g0*2-ARwdpJ^qN8Kn`TlJm?mou?P)zO;>-t40CovV zbW!RL>S_uec^P>(e0Ul;h^Ak~zk8M-0XA`8OpL?wY%l$5_yP4)X^&~OGuln;ASV~C zPAM4;+9 z7ynplBGo+O zvoLc^bEBd{&kZnWr1IMt(Y3JQ8Po&2RVpHdRLn-TFG!+DhI9jaZHPqcLX41X6!rhehd9>b#w2Nrv2+>P3`)PN2I4?*fusQSjLQdIH8tsMZb1 zz?R!N{hbULKorcF*&9r@#;WrxW*cLYTEFmTRoC&yO}1%Kv8${&OOQ@ZpWnwA8&)Z~ zY!+QohM|LnYNQMJ2{TH`9mECAy=v3qpdDLSz0T&nfO5Ek%)@%?(&I$<*0R>qNqk#% zXa%MZ5Vv{>NwA&7Wkc>)g%eS1Zudp^ZKbAS@@tR8G=|u{cq}J_<3``&X9#Scmh{&) zwpSag)sC0J0m>>3p~lJEMGbYNf6?`>$K?|^5BNSV%!c)zy~)Tfp4$xjm%akxE55H) z1_jh$Zb?4gQtopl3>%z*tOv_z3%hKhbvex(z4hIO7QYv>3F|4?B9zi~2(&IiLnfy0 z`ggu_`$~t#5Jeo4o*342=03oR{38g4Qf^V-qkWPMl$R-!BFhL@njr6~m6ott9xCFD6 zzPXpUc49hB>on=R*ap-WyIGS*Bl<~xY@l%~W~CdG2p;kh}&laH2Q!NJE`g#Zq#)aoZXrLIhmW^aH}mI8EN3HRT4 zhuRn}vGPEL0dq2* z3Lr*9gGL}yS3@uFjTnQh+4;#SES+P&A7==ltBYUUleR|&M=x5n;9>^ak($8JxW^gb zQ*IQwPl0h826)yZu*Gd8h{d^;9+>6gO+*v-(Nge>d5Ue*$xNvm6{N=qweRJ4TJci>Y=`T)1MU2=ltTK?@(e198tk$}o;Uyq}LDbEL zSSwa=t!O5UUh>YKL;H3tDFA$2$+GVuQ{>hhi5r>qJnIIrx z7CC(k2mf30=~?aSWG}Kymrr}FjT9g6?$&t~UKcA=yj6JCzK_DGoq%k z5sedWlU_oM^!b!z&t+#|oL~GQ+VgO(lTP?pF*`IKOp(a&rYr5$r!_WtNl;>6HKHJI8~(riwhD z*3(7eUb*uD-crd)CYp06?CT#t#_GA0y2s#PBOTf-o3XEb9xIof9VJM=jMw6J*D&Pp z?4d<3N%5{ZB=k5~w<>JBstLtIIpZN3RPL%Iq{lTXU?1tXFEP5>0K-&-5?bmMRzw+% zKAIBD9sxZzs%Vtfcz2EE;)h$IyEOb|bT;pc-`^N13skMg`K~ zjk+==8u^5R)7_YL@kaw?NEiCx)6*;yVD?(7N6%oM$m?i&$XjfR?X4gFpmK!&@$4c z6u7jIa7VVs8q%QA&fLd*KVYMpgidG^{pjJ*N)p|kf~b23^bEJTO@u& zryot_J@QNxW7v*cn24!jR6shQd?){$YfT3GxxTa`ce|M*iACg7IW>?ka1TYg0xvLr-#I_`TGDSe86?XD0#++w2Y%=xkF*A+Ux3s98$qfm{P@n z8b?L1m1+iLZEnS)u?MaUVc8=(*GyN#*FG;^`(6asBEeuEK@=NGgk;Q ziLee>%OfN<1j~nAFKayYa)F1z?J2uqRV=m?R7c{WRMTh4S@q~>Rt(rw(P`?=zIzew zeVLBp6^G2TGk*J&$bTH}K7s~tMR$fz&6L*ALG7-J9%QA1_A|R)zgSE+TRBVU8xe!& zXOKI|2r7@7iyhWvEz|r)?k!N(dep8F3Ro;hl_eoJO%5SOCGCdl3?QdaMU)YtA1@VK z$X($r+nHL#MgB?bUGKZKS?)eo?HVa>Z{zum0!lnH+V6ytrut?kD-w}#lpQv`9;h(m= zYF`SIz7CvKfB8xXWZpZkCrM2B@)xbBn}KSX?;#8EQ?dT&T6CPN816=34ai#jDZx5m zWf!^g6AjET%_&2LtjeAv?pWnFC;X_yECpj|;&4jTe*q>-!O$r+#MDHRzDWB>O;85{ z`2u=BoMO&Rf+On~q`{n#T6qFRN5&ypHgRvA5+&&pfp~dGCWY2yL(C-xUct*~*-h^F zkvVw8Xyu56xxwoFgEaRestJCFHvJq-kMLXyKVCDf$VprkUw?Z_4E#9|WceOQSwVKG zMWTh+Wdf(H7{;y@*AcZz(%fm3I+b@0&o5gWw-Sup=Iu*z(wU-mPF6(PGpbK|ng52I zLN+15UeDm(#RjfLiG80s1|IE+Dn?XBg5z>dATCyrq;yX`5@FSl(XYmlvaBrrn0S5I zSv-m30;;f_T!RwHu67K)-M!iX$Vd;c7kGPO)?WY2XIidoTD&pR2$0?^}Q18c-7 zxpPRbK1MI)+uWqnmwD+!-lIcR)iUM_>D@ls{QAyMt##XKyUy*sl@~*Pb=NFF|IzbQrrtw-igTpq>Qz!t`kb+g1sc4vpW|xveJ%^9 zGL{Tj{)JqaKToI4?nY_5xq0D~RcGO#{2T!s1PozM^jCl?r{$vmr_V>5#VOI^l1j*^Dg7sj~Gdo)9P zQ=$)b^1%i7^oYzfy16?dLorBkVz*(aC~{_zk9ei6*IKG6<2h{C7}nh0t!A@|DfY&s;iewi0Mw9^J{1YbX63 zSFvHP{yr;tBm}CSJ|!_<+P^IBT32VwYx}A!9P!qMGH0mA<|q3pu2G+oFG~794nZ3QHjcE;>Xdk0AX>%9%-wzj4VIu#*&or{}NB0IhX|e??|+BCR)Ec zgd#;iYttX!>(OyqRGgqwP3*^=bMuR>j}RwBoDUnP$aUsWv%CudKTE45DMFb@sX zIo&?v#Yu7Rvb{3i$q=C&xoK!6nD7wNJK0a=q-oil@T`(-Zs-MC2XzOOmlf$we%YRw zgf*`Mg_nk8!6)8OAkUR~MytG@TJ#H>lFGP^K=pkP;9*F}d3}sSqkF@7rwr2P_g+=A z+z5>!*gNm4lYValzD*QZlUXNGDvZj<4f9k2uW`3EAm1ckmwFOa zsaM2@YujVMaU?dozB|g|o4xAxQc3HD3*Y3;ugYQ8{7L0kt=TLlXnXp2ofMW_H(G7) z-UE;rrUgQ;HX2}KWW$i6;52+fyZWx_HxRW3^1ZW`QM9%Cp9?qjl%afKF1k>_X#xExldyj{!g}>u; zmexW0bP*jCDLw!$0-`@Mhp0VE8ms$HwQP6pR3~tV|4?R%aMR}(L#E~~3bm5&=1dDm zDE`SQH5qrIR%me*sl=N@7DcY&aotWWPJ+qGm0`QWWOITBmRP(l9f>mTx;iVi5j->E zGV(PxWt8-cq&0-4E+#rbI<;Elskgu0R>Z8*S-w9upNo&AGqOJiR=#jUCJg%FCWbYh z)*0=kTctP@91g9FYjPqEgv?`2n&&HY+YE3LChQfQ8lrS9`MdW9Y+CnLpoy0qpIeNSl2`yYfIyvffRu3dZLwBwvDiJ&!0peoQz*2UDApl;iS4Uk; zZIVaYFtd5S7_@8N1tCeQAV12B9{SQry8*AR{HF=a4NBjpDvZcBnQElX{0zJPT|W%E zFwQHDg5Qu11u|iH?pe!KH668=auD0n`|(}WxlY3Q?ODlkOsxC!2l9dfdFl1~cqMpK zk1Q+la?0s`-^xDNDrE@8yr^^?9hm5Y`JOjn`t_~xs zkIp|b)P`s$Ab!?h-s?ri^syvy)LmARdW1 zy@|Hp{7=%^cy%%}7~^`bh9md|t<{w9IH3m6#2QAjA|B?Sr$#7TVd4g@o6zt*XVTPV z3oTantW@96SfHp6$*NCV+exJsM-xP>9R@u?d#)z@&*3K=M=&O;&VYxcDFb1|HV2h( z_M%%oK`F8&Nxv_qzB^m@l<9;9r-j-zJJP-82Gf{RGXi za-jjjebG6-VLtel91xR|-Rc4DW*(;^dz~Vbg=yg>=uClha-(F$VT2Kw|DVNUo z502!2AF>xsB`hkG%~BS+0;YtPjys`NLq(b8ezW%Cos!G2D*-5x=|nR=M^n0SB`D-I zoHLB%APszFH6g)D101=99Xg7&j-n)i4n8J05A92CyPR=0m&O~!@QbH3#r%^9y>f01D z+Ez3cQe{-(bpj|6TmX$>^}Al0F%oY5Evse(7pGFWdnUG(`F9^B%mQQdr=y|K63w*? zsWgSVvmslVlvL23x{iH)g;d(i5%_!&KReKF69Lb7t2$!oT={!fJ+@7=0gbyzMc;mB z315RG%__#;;@!C@!XMj36%cB**S*O?##!*KjmDl%o-e;7Lrvw=Xt>lE0hS2~yYNrP59K~w9YN*qjH0phte+6xq+W7F5U3Cx z8vKiRxL-KCFBrFCw>m)%50Y5Dd8)AddGN3~KlNY|5F11MyXmC5Is8wnqIP)=cfT{W z?R~x|Z#05MHFmUXqFJ2FKgG@JD=520?xLQ8AXN}(19W@@wr$viGtnWxQzXP0b^@cN zg)kX;BjYckDblTw=YhoRSuIMlpx_>G%e1A-M~Bd7j-R#RJIn8kS?K-o8-tT^Jh-an zA@4~6J#xtL9385~peV3!?aH9veMQ!;eHk|??jm6~eT!au2edppA|cur_4FNW-1ym zqKqpCKRhdqMI@}ZoKB1|VvPZxg2cI$7h~)K*Mpr~Fw!JuHk!}g6bg6WF%kwKEe`Pt zqOv@kxur;)1L(9Wo9>+f2&|p^$fCL|IkBg$kkDWHy(6F%y;^ku3fMhbY>%mh_EZ0~ z8ICAVrb?H-r#i{;;M8^$(Eu`J;pY6tnZTJK-Z6-{mQChGyGdim7vdhb{XA}eu9{0f z#U=%^&4J;+stWC`q%JoL>ZtW2m~6h&O$hKta$cCCZPga{DF+rK>NM*l%Q$2rp#*X7 z19nx_h&XsO1GQz|BBkwbz$Ta&61wFoTt@Fyj(YD?Z#Bw1RJ_S8d(j8@dw ziMkH_)r0>VjJRnwGGy)pKEo6vfhh!rb}3BVyS_3tV!#t`Ap?XfRl%RQ*~8gr$;^7m zlC1e^E3t{D;3RHR5`9l5|WcS4b88nRYQ7`r2x1~NQ;igC( zEZpMd;vt`oB4pMKKU>i`SluysTEbF45SFEzi)IYGI6fb*R?yc=B9v+2x#Pi7vQ0h? zXw8}PI*yC&582LNsfpYo%G-pUtsy$5!f+1`(Fj_01O8Wh*^>sJYH*EjVMtr743eMP z=oc2svx5^O!-ZbLI>d>Y_=j3Ggi8taXB!4{b6L7y;|z1d=*N5f^9ST6^iue8xQU z#3}vZGU(ps;A9Dc5D$@{P!ZjwdqHh3rsb`SxcwbT^xx5zC#w<0_dfDXDPh7>s#y-} zjA48S2Brai_~vF{C6g!!+Eo|xMILE7teQ6ZcvG4#*0U=fmo8EuDLCR}094s^(majS#u*2E&;Smv8RwsSZOa)Wa41DM8sP#1 zG3-rY2W`mdW$mLW9~T%BLsO7V)?4kWdH?lbnqT-eX;4q8(o^653fj^67)<+l)`MOh zSWfqUp(sV${L^Mym~W&OE_tj!K~6Xy07k!|i8d+C1I9UFi-RgTSV%_;$A}NG-X2Kn zlaenZJ8BW-yu1XITbl+>M`t`C6RD!{Q(#JSZ2X)lag{rF3l0*|EJ+6qszULoZeJ}quz)jx6VAdnd=1|V8qkZR{sPpj zWv<$@fcywD%F-m~Kb~OkKMmV`1O?Wud%=frFd)5-)f9t{CXy{MFbh-^WJP0mTX!PH zmQ^XBG2BBeyt)t!Zc5ye!b3v(A0U7oNn)l!}!rPSk!+1p-f)m@}hAS3mZ00{BW=zX(*miCH3; zp^JT4jA*ERffn!jYAU?hhjj3jY$zf@UEFjeF9H#oE^X+CWm}ac|~F+u3Sy#g*UuKQY%%x>r6(_;N?KO0UFq-oCX- z#X6jU8Mt*u`ZyW-RC*e5;K9#FtYE7A|C&$_v|+(>-fBBzkE6#m@tDj3LR4~C0{dB_ zK7`U`s;uEccsuso5FO0i z(*m?ao!GGzzp2YpmDR~gBb@Uz5YlR73#QEVp&0%`q*wS9Pv?^A^utE}NG}GG;D7$9 z6g_cZ>ZJN&Mouy#^(^*CO4fd8E#dTDyAa7r_5?q!JnAwljD1F?}4`Y_$FZtBs`%ld6;|)}W>7G6~1Pe0ekN+>b*+!pL%!%UUxp%%JG0@9$e7 z+T@fBerRmwZ=rZKf`b|BZ0<|Q6-~@RP1ai5l4u_Ll|rA11WVl?&IjA^UX zE4?&{&Ln%Q1$=?qMx;gxYIAUUmxS-eHlnyX-p<4pZ|K_@Lk>8I<6t?{YG)8J^McB& z#ap`@Qrwb4bt};<`WHShQ2mZ95(!AFlcLKp0Z4aJoxx(KGClImQ$}Pi`}G{nNA=oS z>68q)#+7WK=q7=fA9=Q4qI83e>KcrmOAkfa6tK-2c9)NnxJMjIQ+g}UHC7bT$-5p8 zPOsk#N1XgDNg9(24T}(DQMFEq-Hc!f*r~tVS@0q8ok=XpHF@M2t0y8Z9LKzmY zvX+x*ySnzqq#Wz`(Ej3UNyrHqKDEYi@PVIbOT-eax}K2U{3Fa7m_cu?NUtrbTWJbx zamqA$ToTgE{BpamG&e@Ai|S!LQjCk5CHHByTldp+8HS08sWRO~W3~3HW3#UK0O-4# z;I)T&9AP2w(yt+9sg8S6QtT~C=og}H88ZtWzvBfJbi2@XM7z6G|~l|I=JWh=0Ery?Xqn6hDr~JihDl(B;V) zjxm`uv(^MB-M!-OqZ;cgD0fhhf7cA{Ue)n%En?GH>6Gld^_cF36M!_8e`xW2a6wl*H&BOt&j-yaz4&pW0yTJbxDAUX~ z%DD?~LxG;T*(lg*e9nC`UGk5zy*sGOmh^HJL?3QJwed8=l>!KAW;Rk$#DKxMrs7gt zFBL2}`JNh55fDI#qQ#A9igH91ED9-HpcooRCO@JT#PNDCz%vA?r3EpFxwG;jZSDvY z=H>;8h>x?bz=kX^?`-TOPxwB~0B%spAiF0BFy|IfF>`Tg@I}ge@PGLf^9L8oeCwX= z&WOHjn>=_1MqyPiAN5J+>o0N5{P&p|obBG1>ig7N^pOJC83^V@H7S|j5 z%<()i~XaE7J-|5)_F(<8G)x;J`hoU1zXtUo}?0?U_}+f`P?0241srW#SCe@ zDJKVDX8FCw)?cIp7IH#t{g`W?al6Wk8XeqvRZGe?T_-_-w3mI%Q&3G zj^XnmZ=*9izugxnYtIUs4g3NZVr~-X;2-u)pC)xhdKcKF9?Pd(ChRXND9~X5xcAgU zU89^{_dVcsb-^hsf?T?$HNkZGNRU1y-89Y_YithyFgk%tvVVwd&WXp)cp5Uq@>_ud zbN;&`&=b;u0yd`jgias7ZA1kJKq4`Z>kvnJ!cCtFi{f&U{}HTuqTt)I{8CU*he*uc zRF4QhUwrH&biUVie0Ku?yzEdpW;^4DK1dG|PCc%>FyxnC-rFQGDP+9(rqBtSi+XRx zs#T%Y4Ic&^7c39WMRi*4+2X>Lul2FbK$f94czwMo%g?cECzSU8je7(eipLD65TF-0 z3ZXq9rE}P1d810Gf2|r+7LB3FwiyN_N2C*tT@VczB9{$YWPovgUpXa^Jm1((7W`7( zVQ4lS+T8koYl4~R|9@+O8U9!OFP*fBt(mhqBR(rD6U+Zz{h!7&8!H3r|5Xwk;|!|2 zY_&!w9^@>}l{pcglzZ3x zR_k(?+4B2zy%%eCXZH7MYO=a;meLZm;h(H8PfQmt#}9;GS3&j<9^QSN3?DyyZqgD! zRFL0K-dmLj9vd)JfaEt#7ZCKK^eT z0W>Y3eEloH79jHnfF(USc)%PboYPBa5Ds=ixz;Z)5W6)8AislyLhjxzfCd^owzU-u zsJSK)jsR^rmQ4)-fKNINdhqkF8hET&tax!12w&fSymMX)R3O|xH}~lY;Cm1v96(Qe z5b#^TM&NHsw0x5rpidoiJYK5)euU_E;H#nQgxpnocmPoT{#JZ)pp$*r7T^KE@-D#7 zN=yJ7HTdVahEY6V+e8nHLG$q^hb8xk1a zVzfjs{r`Am6LT1We)->3+*SSX7MRI>x5L%{cxN4dmdf6~N}=_^fm(48JRs-~6@tGy z`f@SV;LV94ZEb#eVxT`YUr2rSanzT~-S57wOXv^}L7%_un*n*QFFlg=j;=>6!2#P_ ze3g(sYI*oyzI0%42zXR@cz6^rAbwkb__P|LzqEfYL4F@pLNH4pYtkbd2>`_Uf!osJ zQ|m{40{rz^{BE86jo#`h{NjQ9-FYW(6U6Un#_C=E30d6$g}VQhh&`;}L>%^#LbCwQ z|FQZ2eKOT%;&at^P5D`=B&?QW#D{S5|2~E52P3XS8J7WzZgTz>OyX_dulfJC9r3Wx zfWIyB0Nwn60e_1HrIV`|EzI!byuYde@rq7s7u zdia*mH~hMN7|{D?L4)z+XaJSme*Qerv42&0gaE!i^+8cDbkA(~#IXBfHx+)yfB=0| zmR$S<_+H0+EkDs%HT03;%_KNIOP5;ROa>h#kc;mf4 zD#snDnZ}%NzG@m!$+{^t+CCQVCMgx{ta~v2p2#Y97ufcUtvu21&plv_S-)#{zM}(k z7%&&MR@9w#wnxI9AIImoyHa{AJtfb=220mm*eFGoA!;SZJd9wBrh}qLHT1TO<^-wRuhOFosF7yb(Ej-|+PWYRK0flW{zNJ2lnms~zr!)W(* zs7jE1YqDck{gY0?F=!HB%jQFZPnQh4DO-v?$P_Fwsgl{aZxwWHKYxGE(N0mgTcbsl z1s)q7RFLveG_2#ItKfL<^(?!0#%J$PNi8Jl>&*Ar?TLgF2+Le;9F7`=09 z537ce#l6~0RYJ5;I%k_PkJ$Z{UwDvzK@KQwB?I(dba%YwPFEX3;V@YIooQE&{2fS?QQU>XbGV6ICLxbzi8V1B9LxKXgq{p2+kO9k0(vrBavS5bs=%R7yt@9w<>s)G}kfh$ILOL*J#UtyC)BK$R zx(q3d9V%kqAuIICd5%*;pR)t;8`}vd*X8@`wI!#=^avw2~-T3 z$AWJjj+zq36V{_6cToBV*l2iQ&oue7n`+-FFrOn2P-><#J2Hj`SRd1`@#@)Hp+~pS zROZD9Fg&o)YtSN0$A5m|xw*o-aF3fz!dsV?E*6niJieF8`ds_kU;R3TfLe9QhOEqx z)$JDR!i(H5p25c}MLVf0ofN!MNUd%bPX^Br^&*@O!$)kvXF)nMHW4yc?UvwlWn!2!yC*Fhz(#P^guo&FWSvXh2DzlQbo0*$a zpP~)d)VyjuID!t~kF!N2J+!BHXlJJfEgt6^PugJvQCq|VDI*??`Fp#thHwvbk8XT`5Y-bLR zjb_@D<<&8ksOVx!ThGTI0NwyaqvB1g8X7ue1f3xtqEU+&)RI`Y3;UXU->2&s|_}GuCl}raZbV$t(#@ zZHiJ$n_1*v7`P{wjTV!^jFs7OLn&zfW3tQ)?j+(Kv96uswmigXJo;aK@2rJWGU&C5 zw)bGx_WOrMBz!%4rbU~wqz4JiOzN7bzCr4?#J{jW-HnZyJZh8E8xDK-(%Yse>gMU` z=Jw;LfxhHRkm|_Lgd1v1YVM455MV~98whQ?ALdvhHr^)c^xlT&Xc_>%JUw8u;B|rT zR9>Ex7?`@6X2+v#HK^aRh1c**DSV&l2W92X`lp%dx7GL#X8!XtKN#+Lj0hv_L>6b$ zoGeFB)Mg)WY1`yKRJ*$fZ~@g^Hdb>`BB0WafhNSDtHaIi(mfuaRKbR$nZi1BHiBid z7b(`vFJ+r)wEXWNp|yDoQ3Pp}kjOi`9MTOLPa)#Eaf^HQj#|U8YdlCu7Q1)hZ>p0u zO8_sUxJ$YGm2}M)L%sllQ`11GZ6TDN!eW+$PN2}h`sfqxoDU%uK@4A5H3)1&c2Fj1 z=+;a6Xb*I_0=CO%TkSdNVx#JBRa@-i_l9hE^2BpjRGiz)UOwwb4h93GVrj+t4S?O4 z9Eu#o+R!PK4D8RdZbXZGk0>*oMZ0sA`wr%Uiwr$(CZQaD9f~H|Rf5 z)8#V|@(&bq4^F+=X$@%9a+^3myCEmYj#q8YIvotBtSyFrjp*Y7YXpmy+XEzOS` z7^!t9N)9^?*H7|kfWhdM!S31HBoSjJtBx>3eIH&6SA?juLU_-BEYp!H^)KT2= zs-LTi6z5~A3W`vx^3-_z;BHV{_$Tz@a+!wuT9>9+%MGhUTi=T!Zc}mg3S;*6+i7>@ zwL`i}DuB8Rdv(u--)b0GuUewi{0oXp4?yN&G^AoWP=O=OePn_#5=r3V3P-Lfp;jy% zmqFnZ$%T}>esCXKUYpiAsz9O!hs5grpjJ4cUMTS-%@XW!294LHHE%R~QT9Cb+5bL0TcU_*~1YZ|L3@+Eg&7ft{Bo=e7-%uN+(b*q7 zHU7qZvknA(ups zR|j1~P8zh@Dw(#dQbjV-o)hQv73}U;BE9n)Or=w+s(wBa`=g49MN(D&M~RKC)B+I; zzqTzYPl+$>lR|*KsD$UFZY97+m3Gq-5y?M?*-@3Y5?P!kn_FxL2Aiky?)&4y)~>pF zVYonzKfY=h7y6 zXE&K+h^eK}a9N{rZip{;L#B3?i1c6d79fHVej^b*326mn;9>c=P zr^26^7v)1BqD8Qp1WM_Oy*Ex=Rwkq4Psxh}%s^R;4P=p1_=|)~mQUWstsy*dOd_Ai zb&_^+!o6UQplQSEJLtVDJp_03<$kP;@%b|Zq?BLC{~|W_R&U{a_PX26zF3`%cNG}MV_fj)IUp8kk8qUl<{kG>P0Lt z39mR&fEiZBx7;+~8;}&n$%Cf%yZ3YVb8)OO=Lb9Q(Q>wT#OsP7Hlkc_QpFEyX;akt zp*J7@Q@&hboew*#b88tVhr}WO-b?aWNamb;F}uwzArI!8YbpcLLkxOamSw#f=8o%r zv*JS>-mAroY_i%|wybir%T-RX47v;hKNhYjU|)C%JF&$5Ir-vQ(Lfs3DpCZsw%3%=;Ab4C_- zV(d~(nHJ+Zyh_^{L6GMT|cX8jjZ@>-Yt{~xw%&L%Q{fDi+uGEK|*N}BxU{p4N zTHGGF0SvRGY^U2(Ar{ZsKs?_hzn;C3qv!KMcodH5CI;Pu`nY=4hj8duO~1!TYihVgm${YPz;8w29MEF$&e$0mt@TtXYac}6+UrxSRdfwkXlY@)J8 zwIjzRv2KyH_Hc6ax*OZ4NTJ?dQ)yB_q6uJZ! ztl(?lXfs`)a`0nJ{9lFAm6A;pGbl!X4Hua2e3yjcx$U`a%_l9K&KSoCCO;~!7A_Zw zZh8skh5RcEr({F6^jNMQe_Fg0xYGoJ2`WQHk}1W$(mEl-!GWB+jdFf_OD=J6@r=rV zO#Jq>8u^1P@2k8dvz2w90*JRryQ$QgaNY+-oJdD*7tXyK#WD-DfTKQ97UDK;`gs%@ z)wkd+4lZ(Gx&fh8rTZIeaiQp6TeV9(0`1{xw$|! zpCY$PrIwys`-{d)&_xaBe+3M>blO6XAslz4=nI9wj8&I1{I#Ei9j0ar8P*gBtGLZ@ zZKr?_Y=tKV;S)=CC+t=RhBI6+cJ&xChj>sP367AC%x;1#=n_4cw4UxCn%EhZ+8+mS z0%tNkw?UcAO`R2#+<#B5)tT%Oj9zjH=};N;D7(|K>j%dNp5t?DzXri$yeNC9^_YP$ z@CC|c{E7kJyW67<{cy$@)k~|^n}sBYDC%|jJhhEj-QaP0R=y+-$Iq(_1N+6ZNj+v!*P@pR=V!|P-AzamFJ;6%x9?8fp{3)hTvYEEF8DW7LOE>3#uS59eTDaT782?dqO~X- z*XKzejz0|-pJ`1#xSVD(#oweS{68aqx+$``?Y%?%isV5(X(KOpEmbnJjnBUY?|3d@ zrGU!u3o3nRW#38ou?~;t^c5N&-qRuskfi&2hWDBIu73ywd+xzCnEF!4L;lGO9=4ZVG`3+=8F2FpDseAq1Niurx>a zDM};z9)_+B?8%vX{qQv}hcj(Mzk+YJbaOP`-DSio5h))uk?ZK-L1*oj zl1tK5QQ205ZZQDjDGHbRcw-x46G1eCO2E45&d3;Bj_8kzU+OApwTJ4o-|HlW+yvP( z@lFx(!+vzMP&(lJznIX#pv_Xn2wQ@|m~5j(0$r&qI8E`e<*|&{DodtN5OYSTY}U5l zWOt{r#=VX(scNANmJOC8xc{e&O=7o_8B5V|`UUbC+fYI*iuj$SI9^!19i!LF?8NL& z8yv#{#~LpTE7ros9kX02`^ny9p`9n1@p&*EFDkoQKjcV}Xs3AgFFRWawS6(eHb*E3 zu2@ZOioG=NLYaP857ue`+`jD$s#(pGbqj1f?oMVs~|$qK4Jdbj6L!A2%G4>q)h~cV{B;3L_aol z&kASvQXM-qBK^4Dyq;=gTYwQ)H<2ld%jzb?I4`)F6C+U!iy&4yJX|u)X>-8`%SO#8 zo}+*bZUd!fiXrUsEc44k?RcZbww6v}1%5)8AZ1m*PD&I?Jo#e?QRO}5?xr4io^60z zRp@mncR!-krWL?s&uG2K=VskW1w(QdEgT|2gQGq<9Ob#03geI^muQ)H^!F1pz}+=f zUQ4+|6Fw}WQm8%R%V`=4OD{^Z+_|A%Ew)E@5&tT1N@$LGHZ76&waihF1K+NJ#!eAcnid0_oC@-4 zN6H_DTkdpc?8@i@T94fn>uN}gig+Z?lq;sS-rRhX3vBAc4tarLxuxDJm1mAD+}4%G zeE_3eQ2C8K%AiB_kDN`l0wkF6_Jlo}0$3S$&UgBvogk*_f=++6>x$z$gTvqnk5)sQ znUo7IPZ7=p7mg`|e318LYQzYgoCL#hqQ~UKRx}I?Va1%Y?c3rS`o|HGBrDBQ(t7uv zM1f9$aDU_3b;&mF18-m{8CYZQ$zxGHaQuw{2c82=Ml5?@#lb+s1yJMzBa6P~92_z4 z=4dNjPqf+v!%MYViLYEi)YqoOhA!Ry90h)gSfgy5tu4aQ#UUkCq+N^t1#rJG=fR)h zB!7x(zD)_p@4Ncmy`rsSru0zj3Z_w`jA?&+o#=bA-^8v2&>J!K3CBTlS& zSwC~t8ty{`xJo4JQ}|3s4wmp}OBJI7APWg|)g@U##=!Uu7iaA@21fx_rh2=Tgac__ zSIgwwKkM!!FOcLFH}3Sn#Hy_ z>h9budw5%ueD+3oeBLhBWCdk%U%Qm0YH7Xv%43^4(wmL_HyrJiWY}N7EQWe0= zB%6~|GTrj8Qq?lN>v!Y0BOw;?SeO-rAF>t{9wXdco1eSfKfWJm?tC&Y4J2}U2@dD| z$=L6qWpgbr+!{NFyU1+Ag9$w1|EZHFFL7{eCmI&Zjij8h5-25!=MP#*ql3m1SenYY zVndpwjsZ1wEFJ zJZ!pJjcq0aO}8d`DL<@)T*bXS(Xvv$f}ufYrsZVK=JzaW?Pqa;^W92dk~#8IKh#?e zb&+F70^{ToT8^0Xn~}GuX!>?BJBEDo9iuz!Da0eQpZW05*v?j+@jv|iC3I8&wX_Zx zbWq;Fy-r^BwDS?zl6r2e^>t;(|6gG20m-_(v)X%(#HO_j zw{S)11?X`viebVWjbY?o@CLAjoRdZD@(4XyAc_8szz0J*&OV;;2KWMg`&M6TG_6nF z^S-ZrU-&;a%+3C=1jq5WRnrYZ6omwkbi8{67y)_8`YQ7i0zskf1B1NZXJq~mT_ECIY|!6DekZKt&Q;5$^-Bxnl;%1NBpoj#AJkdpdbc-KA;#;gPwjQpxB`yNf*Up($|)jk|B?;M}r+&(v8kQJcJYBf%qbDhF3t1 zVBb`k1!0fj-j%Tt@LBr%fiGXug$NA8pTIhVfhd6>z(w}$C^6jI>4wn)Ht`DTDuL(S z0{ef7t-r+fLB6K4*Va^Q1NUaQA;_YD@rX(HLt z#5=f!^(WeS^gSpCbPD&EJHMWOFX>Ql4x-$CzD~l!w6%PyhShYz))C=;EaMeb-h~GT z-TlOFh$H|B6_h6=5E1}ApaR{4@Z9}u_V;grKWx3>h_CDeu7VtZ*9#{D-b8K)%Mp0> zIT9ej0$g0f-#&lJ4)SSu`S}CrP-DQ>1+NPoy8R_21`xaYR?C07gnNKa1yjD>fco|8 z{P{EsP|czPhPr=ce|L=ZxImRPS;%Gu$bP3NDZ=kS-kctzLE6Pa1AzGX`H2GR>k0dR z^Br9T=LI~!!t1EF;eipqX>^ylzH=ML2>#T6VHyxfyjbcq3{37vW0!I zb!H)Imv=q-YpW&_F0+mg-Y7<$o_bG%`g~!)yDA5H3E8+7NY)SOSH8n?e6iUxQsNc` zI|To98Y<`s?)z^jh(Ndr?-1KjTK=#LDX=`v`Jx>dgxu5_9$}z@1nB4r?Ru2!{Zk79 z(&t}R*%a>fi^l4o0+k?Cqz6)o{Q=?$q1mk)eSih=5Td8Ag<=?2c2_}B7~SI}P=M;U z26g&I5Pah>uzs{h7C`KW6)}C4S4TaE3+?LqhWJUOUEf(jW9#Ts4Xr!|JOivjK<gZUkYyoBz!Pa<8GP_q9U4>3^CmU7)C4f6<~3;% z^7CH*9dLH%+<7f#<1}a0CdG>?<8G($oYG^y`)yhy6t;;eY{|ozi`pjPl3gq!X=WQ| zHI-t{>4!tVLfiCx=(sGMwAzw)LOMXCiL$JSPNPvBusBXUxy0P2t`;VDXp9~F(qaisA}iRC9% zt=&Y76H$268RVr+imBb;%{52r(e=KWv^kgaSZVinE$YY!T;xADw#Z+-LiW2&^!6^H zYgW|a2Hf?6An7I);dNTDWSpkiS}o50WlFGt)PMQOz<2?<`K~?4&uEHTZiH4qe0-K_ zu8OcQrzEb7ylg;4HM{1L0Jr3=!)6E>g!9B1Wiz4Nxm#MvS8w@?TY6+ zJbZs~Le#Q+Ud9B`48;73WZSj_CH?(XCP(tTOM$*kOl3_$9q-G@4WSn0YpIYv;rbZ{n;gptHOe$Q@|~WHwW!Pin4RnCSBz9e_~k;_ zZ^-ljCBh(0JC@<3Tu zaHsjaK{XEX0 zeBQ>bi|C$4wb2)J-QR5Nw+7#+VukC?Xxxe~j#?I%?$DEjmqI$)Ldm(K#;`fQvemw7 zUMsbykf<$tJ$zF1SX4|%x~g~ZZdLqlpn|3zX^d;aUA#7;Dk#VxHEW=o&dmihlsH%n z5mNn>c%kPBh1Q(+y~XNM%pY5dy%zIXK*S0CErBVi^lpuZ{**k|XN!b5Y|8SFuWa*p zXaM|ylS{#!tHqh|)wChbRef8_9pLwf{UHC72iDEwXGWSU^k95?y*$U?K<+(B+SMd9 zjUH<5*!P*icTLsvRSG(F(~;%&n7( zle(9^*hp3O3}4Utbi9Nf&E)KghI>~IWo}yC{t!kr>J-VHd#gOWu|Cjhs>yFhc< z#GBsuSK3BZLd7R%y&nUFNKXLy;-5s&%d^BESCy+9pB0M9v7PdvJA^S=Yi<~Lk5@h~ z6!IBZEq~g@HVZ~;jPYyJija`9?R1S5!&r51u2$UrMAk93;pP5w1C2^5U$s7pp1i|B zCIaefp>{#4j_RSa)4mFs6k_G#R9Xv9+5~jdy9&MGS~^_8n;LCoq{Ye^{7pdxaMZkS z-XR%GHx3o7zH@5Lxihkhi;5kLy$C94WbkkVb7bw%UQJCLCrjh5#~*b*5ou4mFSqK4 zvfV127PX-|GyMsTfD19D%l+j+c}6e#Y~XIO{PY5zRBwTCMt>-)Y&doqe}=_wRlY4kV**^izV? zb!nL1uVC06AGV6As}!GdnGiMenoBzhG(MMIj(9w6zN*NXRV8Y#rNW<+$9B?q?knt( zHQw0}%jPndopV<&C*K(|ep%|#_BxiWO@x8cjx|oD%sF~J>afhXbh7L)AVjfh-1WGiZp6ZDzn?;}zO%oQcp38pbOP_U;i z*>|PcR;^gvUTHNuX`;z+YV5>~W=xx}uW3V1MYH&c26@=D)4gP8Fyd$9| z*hP4jmF8!`{x&Q0t5Jk;KM%)uM)B2$q{eS&6;sZ>&~M3^gs+oOIS^m%(=5}nN!*dL zy}1z`?7Spbv4fdjfD7v0CTE4c7<4J(#MToeJb@;2Bh$6WlLL_8&+Av-HNYOFkqKfQ zm43trWd^uJw+a18{T5%G|L;Ee&quCJEDYkiGrGjapW6$^WDNY71DgxMe^#T+OY37* z&o71gg7w0pp^WY`t{g$_lOkC1eFbP2__(RHcwpM0S_uqqOeoCaI^pU#$4UlxuwnF0 z@H=ODs-YnEj2`3VjjZgC{>|4_-P?C17bAEqi7pFVU_mrFo*n05^-*!Ms?lV#^B={oTI(n^B{dGF`rXDGhju5Z}ligUBOU){Yf>`$+A#5p<~-lq#I@GtrRj3=f{`WWyqQak#a*lD}E%ihZNs7&G%x+w%OCK znr*-_DcTM1wOJm%Y%+2CP)obz`_z3qct7s>;0lgYN&2ZCHjRyB6K?7Gm&}j`GvA2w zm}Jbv5qUuJe9UP$Dq+LvMlFY0hDb+4HGFG5&k#H7fsLZo_{0DwAK( znlC5t5~tmIzNYly@mnKLh3nyx^FrSksMDg;ljIkd`V~a_Kr%4MwRd`#9KUFd&4O+j z3F^^%N1eJbAJZHM47-%*)p2FJaLyakoQLQGX;o<_oZF9)P~&Nyo-EP=B^oSayCd#3 zFJE<}yO9YLxcEo+fnmq#N!)xcBTftrc8d}jkL=!vwiq~-XU>J& z>xw`ieQI-KawDCts=IIZ{ptDm9&_P8&+y8{SS;tl6Ove@a=1^O%Qb#?m$vI9Tb)1# zgG=j1pxEbNOZhUdWy#vm2Z^7A@lHJFWYaBB9qfO-z<1Wdk*;LkAMhHK*WFU~bVa|6 zYbESCDe$#bQwnft{_@)v7?M14kx{;#G zoW!;VrOA+kSZD0xtMX~En4tMLildms?#bB`=R|k86z9Jh$h+wsTDM>YDmgocjk7{| zNrfaX#cCq=f}}COY>v^%)sC$ATCkcC+R76K%}g2#d0fK zf{+u$IQvXl98Hmpa{L=&Oi^lWvRyH)y^q|0-joZ@hP^#Wzh(Wm1=IY~3?SW!GI+u@SbWK_GSKG9Fw~VfG~Kcat1|u9X~?sohf+ z7}sTw9I7p`WpYy@rw2#z`gr*OGL#X+U1A@W&K+}eiE?m|lZwYus*7l-WNARAy~#zt zoEAo|{ZD9n7h0nEl|Q?J+TDnD`eUU{#PN#j;byK;xt-eRPn}+McIEuWT?wmQa~0fY zt4A2zm1dTlxiXT|L63nFwRd`LQN4?iDBX=y&=Ftmf>deKWHspq{x%0MDMp}guZvzm zb#M8R!mmu#KsUIu>#`LGvjYC>dcdH$>*($6i*Dq`)AIUN0nci@;@)JG&!bf}9>*1p z%<7MqdqZT9<1QpG6)fq-{Godz4OlMm_DTqN9wZ`wJ;$RO;Fb?w&VciIYBgI6BgsHI zoNAq?;e)|aicCRr?~#Eio)c->NEC-g{mS@mr&0lJ2@*fsS=sKwA1tIu8gQo9gfqfF z+EF;NT9sfjVVQis<;^h>^oMUDur@GDlFEJ}%OP%t5XUp7);tX?cU%ZtbFC8u(|YN| z;P2-1MJ|OoM)W&LGq%vVHxW2D744uTDbhzrS7Us8=l9WT*^=Ya;mqxIjQ-_F9shY* z$*ZSJ9G<>^vcDR`P7V6vYN+k}VhK^UHBeApa_C(hBo{ggdT{5teJnwUB?Gyl1UJgVaBoZ#=gHQvZ8G*^wio+Uq_ zrXL1!i+UeyiIp*q8GG;}g3a zr@ON={Ag6r(V`uj_?)QdXzWJvn<))pKYS$Ah7hMmbjuIcKRpMnHby`Ut~zem1}X$_ z3d0CoA^mw?d$J_0`kO`9L0MMhu+y-L&Tf}xTO9!?82MZ6eC50gRp~9FANjb6aX1le zTftXuB(pHoAiFeYPvAwYBRSV=!el}Pf6j}cmL$%bf$OkLguKI9VK#lyBA*!ThtI>* zUhItNPfl-MkzJshM|{_lEpnSD=o`V)jTcCB}n* z`^!0SSNI)rprXg`_`yGNrNm@bk#zj7<^XGg0KP zM7WJh#B=n>>&^8>Afmbv>vzd|4&w&=OZozft(vqR1WebA&Ri8}kjV@G%{6hRF+#Hb z>MwlKtIC{T4rXLEuU)Z(^tCf?`h*U_M6p89$hKw>C!1>J_ptKy(nAPRjSyqfwSuj^ zunF~g(UujX0{MrvtPWmOI*LgrAnV`e??nSs-K30bgyL?P(v8;w%5ZngN!5inJrREc zZY#dG^7G?5_whq%S0U|GYColwS&3NU)AR41{oc?k7azGW)!vT(XOA|&i0?Zy>|@ZbSfNR4L6O@|G19+ zUtIcRA$|fUVl~#@B6Y0*I5#d1U(3npscTwK@m?-;(({Vt%+6S%I{>v?e6_aHe_> zvSvKvi4=)$9;u;|R=R$jTbI2}-=I~FxSvcWmi?fWZ-?dh93d;seaL#ExW>Mtl9TPK zWyou1&F$WqP3W4I%}4dGVJ}nPKcaf}ZZ8f5;+OD;d7hIS@?^Fy+vj`DXD5vGD*aA2 zadW=I+E>h~J!g58^ajsyH{u=bXGX^>x#!Lg>l| zaC*Q?78kt?+!qLw=>6ID7@ZcWynPgn{;x0V^6B*$B*Gc~Ek>#(MjOSoHIB%Vp6R-Zr1WmUll*S;E1pglg(} zGkj#^?_$We?gZb#XGJMOBlaxA9xlLX0%lM`buFc6$-}v%Zcp6221O%a+XK7V!~W!K za{)Rrg}_c_Fa_i(joWb+HPJ+z>ps&{|dCBCXYD z+AE{WSebv3|Ghq3RmOL8a|xW+QZOs8|ITpZlH#XBid^=_)Wv#R%Ee>xf-cwogK)(A zS3A|toQ0J5+4%6X_Rhj|O-rfQZr8ziE$NTSrATe2nLLce*?sfcaEpT&YK$4XZAG4 zzUJV%f2OTBE{++XND~i`L+=O`;4DQ5PZRsgV!X1YsL#4~JrK~aU#$U-06Zk;W_y-B zr1VfLGCR?Y^X+qkivH58=VkYjqp^iRk^Gg^9196m+Dl^p*;$%X4N^rN)uTtQd8=Cu zQe~(s^vNhA#=E8-$Kj;c2DrD`(5hA7X2KA?_<-To^cXb`*w!^fdSH zG!d8^M}Ke7ZWUL*<3C)w-gcYzydlJOl9R*bX2Zc?y>UupEcBUnIbx0W?-Ut2KjluL z7&9VIHy-us3*~Dv%08>!&1CGmvW&_%Cazc_SC*oUa;2x$?d?3qk68C|Yq&DMkB_sa zVkq?z&=9j3dGapQ2X-aXqOokG1}u5Z{;-zoK^JWwA$9n)i8!|_pW9rXoi|MCQ>yNb zFuuw%Tze3yNKwe6S$s?&2G34&gl1!&m%A=s{A&VR{2BkU(x)9>dWRIts5_Zz=P(~X zezSKH7}JZ#VNAeFirA2V$gB;3uS!1|zOmNxqF=VVIx{}p4$t6<6)<`zdRciSXb+;K zWniROgD^FjnyW(IXJu(n61P+4Mb=!C0rb{8^zb_MC{qKTHmNvnSb$&q*`7-yf%}EX zdlqK(1*%Sr7o?4U19thcW4}RTsfU_U7H9Jc^9n37IcWT5?M)-~3S8}*krXa0kas!ur~~ zKE{A4xVTY51<8$HF$J+9A`RS9h=D^7FG^B{ttB){VhGg46tu)7@Zi8AgZk;d2+C$! zg+GU(0l?3Kg0`s0alj50Mccj$P!bfhcG>=XAfAOjf=F0cR0De#f~Fjt*ubHLfnJE! zDBFM9NKg-9SjB~q9I62VQg@R)h7GrkgM+)fyMz%q5Fx@m)OXMzJxCf91xUD{65a!b z{raGw0O9R@e{xXZ_5gA@sA+<2%#(oUuz~|Y-2JG4!9+}*FbZS{2~fvu(AXB2z>iyp zV}iz8f*`^>zy^?*An`B#E61lg5!iz}GZ>6mM~6s4FH|wfJn#Vw@pfY-Lb$=_wTQvK$$dFZJZR%!3KI1s`TnKHMU>1Ksv|PUyB#c*3<;;uk-lL7hXno! z<{E4egszV%E^dcIyaf*V6wD3rPvy9G4gZCY`U-MH0sH9sw;c%IPP88g1<82}xgQ_s zF%YQHOu;+<>ks+U0TK}bWC%rxZh_z~N(lU05f^*_@4wnUB|+j7uxgO=A{wx-pYJcQ zad-?aLZs{aEAs2xH+cD9)xY!u#Gm}fT}BN21oR0585A_sgp@RZn0OIckctY+U|(Pg zQxMUA3+R_Z9rhvsWb*3*-CgGQa{a0f$m2IF7~ySB%UzN4zm<~iU!;yd8X#~ZzL8)4 z(%t+i%b!T%a- z@o~Z(T)gZl($RvMgP9hS$W03q9}?ET5#R=P1m6V?!69mtFA+?94aoXy&Y%T`;1n=M z=mXGo&@sRCnR5CH=-Xc*AJ`*m`kpL&Aek%M=wjAUPmVOJIV7syD#=6)i9kFIuWQj8WRo~e26Wdn*g!=p57_+0u8OYm#!pksk(6+csL`lL(Qh(VsWI;b z+V!7>r`TLfuR~6H+U`Lg(rs`G81HFrDv&Gvt6|}jZI%gVfI38ql%S@Aj-lw4UX9cQ zoSyBSzPy-3+@PPksQy(GU0_`NuxvW{Q~boV$Tz)WH@xpyC5cG@qn|DV^H4u|P|K4s~h z?#6W&BB@R)fPG>(z|XO#XgIA$%n_0$EgZ(T61DjFUB;;?SeAbVZ&ti!GOiwzj3{nj zX`}HcDn62{f!1$QS3-}U4U!afg;nuBN*vuGxx5mD+V1oeA)zAXA=B+FOGrHFs@Dlp zt)T0Z|BtE4h1o*q!!5oYEu;bH_?Rz>cY7JFqT4s(E8qEU1as6J({Cmsy=#80{!JRFu5t@cUfI&?=Cb! zMn1ju5~Rtd-bOSP2V9rbiH3FAdI#ciCznTT7rLoQJKP)m5TL9G&xI6!=R`{;K%fM*Sx#PyB3%g{^DEjEO0yPF0UQR z&hsq!0T&Vdm%))rz^73=o|;6`M+$!PJi}Vg*&a9f9M^6{B(n#`c+h+9i=hgk7kb0E zM?nA(+S<`7wy}(^7&+Lxwkn`u_6naJfnMsjuGh>2+F!#|r25l%*8oGir32lyhGPOp$49 zYMuuowOd82^&MlP2N21W6Wg!PR3IuvDh?%W;^W*ow7>pg(zyjRlamC4DOi%agnU?(d?x`EG3wjwYxr1 zOhm9$hyWRqJ8WoNzC%~=aDRk5M>O!}49~kG2qqxfOvsv^{mk0*6C=M0Hf=|-t2+(Q za-bl%3hg+f zE&&_Uf-n5$+nRfh1OkH{R#@7QKwNxWq6L&cOiep707XL^nJd1{hmM(-=?uyTZ$%Yime zSQa(cAE|yJcG>8FaBd2Zuo3a3b89t%BhJ}Rh~CfVyeyZSrU{A1&&91unX|qpE*zkA zjcqHUr~PItZ~y5m$Q_DY8u|(bsgJM0t4cG;Rw#dDAqnP>E3v0CsJ!~Q5VxA7wO;Sq-G!XhYW=o{8T>2-RXpk47{>zO?#qtv`w8PB=fM)P zpJE363B+5p&PxlywnU@#Mu|#{R#%fxp-Z;r`{#c)$$W8lr&N~@$!d2_n}kcD#)>_8 zH|q4i*>SA4WSMF5m;$1y!o$6Yr}G(Sz1Zj4>#E)#Mp6k~tC2PCVogHKRPVPo<< z27j0WI)u(*bUZJx91~JD`iDj3JEgMbkSy0V1QPSI%8x0hHk^=>?b)cWQf>5(5w%@F z(7HB}72-x?jolf#k|FE3rgYHy4UVD@dbtjnF)dWFtE(H@Q0L~4zwSw0-p3w{RKgYv zDXmpcUTE5EZ;LlK^|k;DbBU)1h8!OS|4HRZ+qG+@8}+|(yxRTB*;PF~ApHDT`Lv8X z9z(L4+&leineEkM^#;60&v}~}hN-b1xZ_`{TwayJflE!~(g2)+-xZz5-hboNcXP?& z=!C{Ra{`@{&a^O3k)7J`Et5I8k#=%OeW;?1a}T=H*J#@!ds2H{S|YhL-Lp$y*jw~Y zBCPh}IZ35k!_C-0-Zs|-qdBrOSNUVIB-nRWa(Tu&6EI8?R^=}>1@5n%IRDly`R84=_B11VB z-1-O{fY$_fqlsNwzT~P9d(@htlFStno%}J!%9gW_ub_}Wt;mbPr6=&}?@=b!R3p^X zhNdpSy404wHt`YH%^|jbNE;Ry>o9ZsFz5Ye zW+c3~jWjB8BOIhjk{-n4+KOa2eZd6qOpibn?S`{+jP68l7{2LTindzVTkaTFKgfJs zg#wsH_3lN;tw?Eal*wW@@Nd!XEV=&lceP$f3mVBo*2!?3{Qy$CIq+fwvI@h z)z)V^iPw#}2r5)Q0h=FK98!vzN2*b9EErn)&Lu)kO*>aoNC8{C(P1{tCSoyi?()mD>;=uN7VvVK6_}aqwn{45|7ry{o|y< z^F+c6v-+T`G=W^(SIGFwC4BQ{u@ z@O|PUP~5$|E>x~25E6b0(S{#v8n^Jylkx6px&w^kyc>^HB61*W)ruKZpchXVha8Px z$Sxl{CW|my4=dk_$Riqr2W7{bBGxk<2P6t?OyXpL2`)1(kKf1BcQ4z`;{=rlv1;?? z6f@)5^+v*9^38u!NghCXp-^k}_A|E~^+4%rfxM*&VfsEO@)xucz!DC)c;cjfEXiyP z3Y+1Xf4;G|h{NN%;8R^O)E!FAChsPJxy&phoHzl(O3W?7_jUlWk- z=nZkGQM%^CE9+B7b%~MXG4m`q#Rud1!k4zw zHx?Y`myk~RN7~zrENRi^bmf{xU}H!5Apy}S3fz1RB-an;E7@In_!BBzQ~+miQWYX1j zhC?QPBD>Yg7^4<5xkt>=NW(bteV_|R_(DDI$|{GgwD)d4TwkXhUrumbyvch z`L}M-)^s`@t#l&M<)E>)v~48wd0L$RI}w6jD%+}2h`=R6^A?!w(S>B6r2*wHYS{5R zwcmG6CldoN2%F3iGj4i<{Ty&U&fF?I`m!whaT`SUtX&nakR0G&H0TB}m?90tLvfve zsW1QJvr0?`VDE^ffTtNx!`m+Zv9b~Eo$HilXvRF!81iizR+*2l>u{Zd0<@clO@?&SYE6zpsXcrBaeOHder!BlZ{=zj#;MDpX$$P1RGzk)97MR z+fiu1s1%f5AxUbo)+nO7NbUn(cZx*OH33*Z2abhvT}!Sgr3soWUNUwK{gkptd8q@2*7RAj1eYs9`N}f?>N92UByFw#<;cWl zx9IwegMlt@Pj>;A8P}l6k@+19Oo#=X{DG|u53DzDA}_GzL|Rcz!}O`GhY^6NJS87%s?J&V&C01a*Gs7u^ z98TC$>0E0t;%b?+O2Gz9b{uC3?m$1=tlUDMb)|j zP=$otn?(4IodN%>yksUECQL#i8oT#)OSSe3K`X_2a1iUl9lEOZA4b701FcIb8=a&8x1NeH%SP7Ew`Rn=VIpQk*g zWdu;TMJZiFBX@+~t`ygY4Ay?7Q_pu!y~F)p^xVH!*dhS~c{4BFqp`1q#eCH$P!8>; zN3UBHPQP$;zRb_Xr4>i4ufT#Ryh==F0)^KfY^DT^ikP|EdE(fqUF(z3%4k{uuDi=a zy=@~G#K3Q7>?PT|F^Z`nCW=Vw8@!+Y8gNLsMwRX*nY4s@V83clw{t+r=#l6MT?b(_ z(BpD_rD}O0*-?2huIFSnER$q9NK(iLZFJ?%%!ftvHzE;&^mb~Um-CeLo9ei1A}KrW zQeAiJ@1-J_(=%>mq$JXnH1?agyP~#Frw%-9EtNeRG>FK`UPNlo z;dDnGBUg>0!WfYWuhEBV8bgsL!NPP04lh zB|62>BOT7jq$M~s;D35_?Z!a+r&qx^FfF^u>&KY98$kUTuX{;&lD_}pP9O=z2ZtQV z^f!r%eZAH&5EYVu4mX?3R5x17(>E|eWqkH9Y&kh(X?p!kC#?1$A6m=Hz7+!%v;nGJ z><}xq=LZs`Fho92h)9u5qk6rK_z)@Pt%Ww7Sd*WW8{qctT4o}OZzt$HXYeI5V> z@GMmTs(xsD#GarU)OO!lg*U4IBU(Kn99Z&X-`7$)fijNgPxK4*z$XO9sFDxXc} zBHNoRsn_6L_tEK}?~aPMo^CoDC`;_q*7GBjI9fxH0v_i|s)qh}W4SsVla2%(e%^Z7 ze&<1UD~se)`1tR(k~>?qUzwT zAKfTexK`W7W5TOU5cZJ7QWbV3kibz;ArlzyQffT5^XJj^o1J#sPCgdDF_*Hp0LT#( zu>Xiub~d~}M}?;^Y#MF*dNaMmF?*-dgb?ge`%?WXRr>`iO7gC;mNHbkxv}`m`oelQ z=Q#=!JA+;he=LL3eMVV}zUsEgWJOU0Ot@rMBhQW3i^1#q9oAB-XvDzw9rt%;5xd9e zy$wy4ZjIDWM1ZoqEwyi+LxXblj>YZUc)< zW#T@>e>kQA-AP5g)8;c}yw7KYfxXn<{ss8AdsSNFdt{<(`qfwTvQYoypLXD#Q?y?x z#2t9~Hoszz(osq-3qP(e%H!SC6x>&Q=A!yfBA4ngEq#WBreMJebufieen1;&9Jxl@ z#>{hB9v|^ye3?Dgjz^%2WWGA?yzG&*MkP<@zJNo$^v(u8Z|uj4z|43dGkjN-&|Y4` zTX*fgAw^o5?T;78$%9wk=sijbj-X%Yy|P(gR5nh}5QcKv>MD&7dx;@O#%b|i;>Nk;2=3yn&Zj{0V73VvlswbT@sbB8w!}># z&Qm|1`Y4RP2CD@qSSvpK{Ppf|$g&mPAeY|zLSn?!DV~)Y^GQ2iU|Hwo5LQ5FG_Z^L zpO;|@Vf=K#%ty=JLW-d>}o@;Qi;t3(thaO{^vHL9kf1=*R1t=Cn>SqVd)Bnxk)Qt zjzb1>?GJL3`_8b|$0*+~rw88rz8uqsfnJmDMRB-&DO5^svbyVs(biJ(cX)KH2BpWR zo;xyJfJYV!EyOj{e=oDS%RKkVPH46H0!J5ntt+-Z`{zq+y$dysN}@t*7o>#&R9uv} zv0AnzEljtL3h7H%wA6OT-M=ZxrNM~KQ^pVkbBRf;H=3HULvM0jUZxxv_nTd>g`n`z z47C@;43}}aL7^qNe0QJ&|AK)8Y{dvx`$oq{Gz|dQ#g7)G>h`?l7Y4DF3FFG+nKHN4 z4Ve4`(u4^FH_8q}K*&Z~Gl*8A#SesWD(-0a#aCeOFV#us|2j+X3gH)NhTmL{W)$uC zr*t}4mCr#~ZxVbu$iP;<@7|bMVAHd zx=YIZ+5;9mQ-@sYcF>VbJAF7>erSKC{{B3tSCk=wj_+>_aqlt8rTgYh7W1^*^=Xs7 zec~qvx>x_-Eb{;ELlw5Sb1}7ZaVGc=pHw2Cmo+u9G!(M;AkhA|XCPqZWTj(bXCvTX zVWi{WB+wPLla{+-S4=DSo6jjqawUw_ zM?2LT>D}yCZ)dUgnKofJmCb+BsxfWuZVDv4mC>Mm zdLE{SjnLH@Q)3`#2Rmq!D;#6 zWireAn-(yDLczh^Y8DVOlhr{cHBJZuXP!?9)KyH8fu&mR`clEV)g`P0I?C}*TplmLvg_Vt0821#=^Gfxn1Y3W@T;4`RI8FQZYRoGL<7 z>A5C!44--k)`~1^Jb^Hr8ZP+a-;t9$z))ReA#ZKxaSVGZnI#d*_4XZ(Q5x^(z?* z2Iv?uw7z_ImsKF!5SgAZ?yp_Gm)bQ<_h1g#BlVP=d><(|_S_Pq;n}VC?uI97Qipw6 zhI$t}-9cog3ud>U0biUX^S_jZIB#3o(&_{vHfIxA3LO?~h7E%lg3b|tF;EGsllXo= z)KRcOGSjrmO`e9jbBei(K864M(NDRx8c~xa712VUM z&XxW-%ffnsR;Q`!A^p)H&SN~`Y3@h4thN?t8?ff59Xv_x<0R3(Q?UJofg6_nsJYzq zB3!Pup%v*JFrVKC=yhgQSEL_Js%e^-(Nui{K;oj=$=V6&imL5)vkpO;TeFyVKKcl7 z5fV6oh-h_g+mwee^`NiE+R|7XTL9``ZxuxBaO1^Qf#gG5u`GAhFPPZv@jur4snM*R zEJcMH>(p-VX*kIGIduy)Oo2f1R7L)*?Gv)c_^n5zfW~4uH`;AA-A?V))Uve`46wg2 zLfbot{oL!CgtvECSyO8-!=6)$wAk%DJwPi93~h7^WrEo5WdE$Wc87hF&Oy5h*^|Yj z0WVds)_mLkOF{PfhZzN;1!GcBl=ddUx}%X+R{S(Y*tp`N6nfl^xFLMA5uw)dV}ccZ zQ=qNgI^QN})g}lG2}!7lPig^w&=vA&T;Vjfy_Vt$zP(l#n$dYDZITXhJ*6wvya9|P zygm$?x-BXLAA(_?ygx`@o<`dtnt6824-zi(p8``q={xBc_y~PgK=Z^T47`VV%750N zPo#|SvRLuu(zk(XMRZ$7GaaH4JVF>lMx>bWjrE3sSPSE?8BY34A>=7WcNWPv z{(u=TU+I~47kTqUu?Q}7d*iX;(pCz2Z&_MWH>{o3`W2L)sHSezxnc@t#_JKF_R zD_*IH@MNwTc)T;~S&2L7rLfm^*?q}eqLjVX5?Iskhtl(J_gj7Lg^^iKJZN>ya+!Fw=@wUyqfwaw3cSD))a6hIQ-9&oU!S^ zoN)Jq9v@fyRa4KNXC!R*>uYX4wA#Z!IAd_T*yncEBPd432N6CV{lb*G#jDw}s(S}e z&m0UbXF(MA3HJQ}=P1ur#S`BW1quZ~Lrt^yFUujeyU-A8F%<617BGsetpPc-7|L@B zODu7Z$nokE;eS(}BH`AW(_OGLd4EKKA^O|H4C>@gwgR>lG+^aZ!$^G*Mi@}C&>_iA zEG-wG0+b7hqMBdf-j);+Vcxee*t_vNSX%D{ax=cwTRh_Ey( zkwt=FWWI70^{(yriy1_1^4EAO6W`MgNJ^~lw3-$?Hf%d#%Z$fKf~{@0qn-3MgR`o* z6~xD;^^eN2B^ggTdPdiLzr}6yZX8wzyttu#3oldj;;(R`dorfM&;fg2#UQTQ}DT(8=0`F=WG;1QTrTstsbZ6c5S9bBaoWz zCH*w(jUpvg?d*IU8p$))TmjvD*!=b4t&)k-Uc>KFS=O#H?Qa{(-rZxt7dsx4_i#r1 zq4+It4V=G!>fKg7Ucp_~#$vys-1*{S-papi+IjcmHxE8-TdQshw1Yx<5Wy_#C-@5U zfMSiy2l1g;82oJ|xX52K%KVIYFUE=R6$3+ngTXyXX2x=w-2WRpNmf&YeG5DBSX76y+0kxa)ngDT`` zqtV8Ix|3@hB5iGNZ`TBZVOd*Xy#oBj1p-MY_!|TUjkZN9;NT8KB5}u4J2jR2{#*50 zRo%;H{kda)Jt$CII!R{>-2g@@pksKog`-0Rpy`T9Y)1!xj!qAbjtNFaF&Ua;A&j~_W(-a-UZCz5vUzhq#abWy&Zr@M`z%dDMUaN zz)66m|i_&=o<&jRK#p)H?618?v(=RAL0z$rEw06RlN!B+llzy&%2iZ!q^C%ExEufQ&&|(x0fSZk+(0%q1a$U-YWlThJOgkyFhCa6B@P2V z1~!1X5N_a_eApivTnL4P6)=E&?yoL>cx;L_*pt8efNnp<;xqgM zJn@=4%W7x`2S84to&~>(`8XI*jh=a3^ryS&mq$?dZqL8yjlf+S8{hL`HRaglz0_;l z$R#wdZPQH<-~3G82r&J#!^5N$1Rww%zyf@1a5?@YbC0gT-<3x{!e3j$1%228;9ft%ude`JfdC8@

    wi`BA@OXIonU+V!w72C$9bT}8j-A59o0ujqcg{uFEA z1{2RR{B{7V_Qj`ob>%fBFBi9Izcnd|fo}j`>+hfdS3F-j z0CskOd;xopgm-<17Jz^KSMTBVP1U&}1m5bL@=u@Yl6rnl03LUt2Y}vgHLw!QPl5oZ zehE7<(fQM-AHzR?GjIGmzkVCO;wgUBi+=4zq4H*C{4X+pncjZS0_hCQcl&7bGA|*$ zcYs{S9_iYD>M9A(>XuUjIW~Xlh#3HhzI006B1f0P}?de*r@Qa%O%51_0#JfBVhDoH~Di`N)I5upf9g`TDYc z75L4Aet@9>I1GQoW{dYjJcWM>{oG!EkbhPyY|?YOPZEWy7j{Kq|4!74{B{Dne`=U z75P8#+t`XkT1&0kcENcx$S!4WTZ{d(iSROLIMe=pJrpT6SWVu5_Hcn`fN&ME3B6S^ zq;Pme8CanrYQMixezH9Kt><|$^HcY(QxiZv+#iJT?)J;kv{+XU6S~~uRMIlR;3lP_ z{^@|9S*^a*{Q4T-U7{MVn*)|V@Z9~(wz(tOnt88LJHPjENuE#6Oi&`y+mDxJ{+Pt+ zRwdNDqo zY~^we2EnsS)7iiGiUA z?Z~K!d@_84NVJgM(za&BE6MZq_t{N7VzAkGO1z7ruz^}_ROYbqh8lSs%HE)PBhHb{ z3>N|W^fs-XOOQI@TE!`h1`p*6+E01Ot(k{}9d_v>dATySJAH*un%pRVBlp=Ab~iG~UdGu11Xn!-W6IA(TvgfAlr#2% zW3xRJ&YS5)NtdSR2ZrfUWLk-P)lD9OSwb-_FW$q`g&O8cph3sjh({^mljM(t`P|Qs z+QcNK8OF*0p*-TA`nstS$PC)_V#VN+O6dtoCvh>ac`at#lE2}7oqqMmz^jcIf+rq657Y2X5Ry; zlytk(d}&FgJL$k=4I?&-Sh8<5Q{#Em*Gx-%241TaLFfVu*#Vkbd=K!S%t{4b?fp8Y z{@5gqtyM(nGDzcolaIES=dEjaHx3Fj@N){CaEqYb$^fopG>@rUyd?>o`!g|1o$ghS zjq?p%@xtsUz=po^=exe@!jjS~`FC}!RL$?+!^=|znO8E4+6_&(xz7DW&PIL9r`~$E z3$?e5@Ib^WMOCv?iYxhzX7Z1l&tM|_*n9O>iR>6mj+y{ulS z<@ESMY>P-``XwI2k*q(b3IA#r)!QEeR&K+cl&*)PlPYQx9I12)Sbj6f4M8}I!*>U$ z&L79zLS~eN~_)XzddY8mPO$Qfq>0AM^G0@~? z)O^YaInk0g5O$bd4uP3a7O4wr9Vom_PXCmk;j8CuPbKW{HBcb?8!Iv%a;3+`zNQ6x z%*K`emfkJ1DD#L(CG!e2+d<1gPiW?!UE)kZ%3$EP#pOw@H%n~2CbyLX7sWgp+(_S; zY>9N~2x|jt^{#qnpVTxTriJ$oYm}c44u6jHmGJ7GJ#yB__Fh$8fjVzF4Q0 z{HLw#q%(!+PjfY!yGXoT&HbsTwhczziYt|1jn-r#Fgw&?bYNSTIWDKJei}z>kfZI@ z0ib-n#`x2hy#Zr5>@!heFt+|feK2NTj^b>b=1FpPunbLD*2EV1{Lg>*734qTwW;U8& zFYG-ZS$pJ_Q>9XwH0y};DAhu!$~*enW{x^ZS36+5rRjc^*yjd)6G*B2U1t-cSpBNR3k?68+iKp9CUqvs zh?Yo}TM%T1DOg)u0~0a@-p3J(p9p|^+g)*}1_?>`px}#1?|O;y#a%|HckyzUTH+D; ztX4$<7Eq_+vRd&d$m|vIt={=33zcc-jm7aIgdQ2!WOpM$V#3ku6j;V}$96^XE}Uu< zImCY~)UR{k>91>r<6Y^x8xzJdZWUsT%1HaXGX~H_sUBjjP+YjMe<(S_ssYx9*BSM0 z#6RFUZMI(pKGo}yZd2`KZ1yDx-la6p4swc|Ps@DMDR#gn8qH7J@K~b>)4yd|AvOlU zdkOY)rSl=901ME#sWmqA;d%*^Id2 zljb!%IveY_{I)yMdiVFt4iY=FfhKsa32G{+AXoJ!+8v_@I`URwNF>;H-HO%>bmw;C zxY5$JOEv{OXO+YC459^+O;<@WfUzi{IO|dXAiDN0EJr6clL)HvB_8e#yhE*}j0q|+ z*V@JkMql@d(uoTW0?Sl@5ckg$ex)uUUv_sDz*hARH1LPqBGF=A`)Gs=x33~oZ~5BW z2M?32$>>USO4nW35r)a5ufl4P5xyE9y1%l)f_{k2-h_^gFDs ztD&f=O~CX>?4Q}Jk}_pQO5`-NB*?IO#fCx%x%m~3DY6Y-+$gK`<(;fAo3yM;r~#XI z5azQ4LUyy+D;Fq|>u(gmoZA`Vhz{L_1>R$QUY)d9eM_N53(H|RT_-&m6JBfgaQ|G{tTy3>wHMkl zgs{jGGH84LV7ddVnjkdS@|Bg-yf-FWgwESB`+4%1H$mai0zpvoJ}m^1=6mMxmb`rv z=Lh1zdx6eV1RK6L+GQps6v$lx>8sWZ?ixaw5t(L%&aacucVWkS=&BEDC+-D9d;MJi z(gC60V)hTgA)^^x<9_mI{1kd7#(gf~J2~Dobge$yJqv7t%#{T>mCj_Pq#0;91eNWl_nOc*Pvfw2h8D};;|O1M(*o#XHA zRvAppYUK=NNrEh&TRJ)A2+fovxRrj68ljbWcjB%1L_q4^Wb-`1t_=^kR5@KeA25n0 zQqVh*@VBZkTjUNQ{)xpPZ%;_1z1#bf7<`&u(kA~^4HLMj5}2V3>Em_@HV}0rKxwmq z@!|cR!3h#dDt)ln;|ziaRX{oU>=_n^QBog~)%x)H$)F-98xH6cI5KK|Mba3?v34A` zCTKZBq|@`>Lr!m>!H;5nK3jwXInoVO)>Xdoj_~w3G6xf_xXLhY|0rn7bHd+}@ONj> zmLdg0t{Od|Zs6BZ_QJ;#jE|CTpUrIzF)q3b%Q0E3sl{eTHE*9QJw5+~u%KrDr5G>T z@!)>#pVwho)$4;u0qxR#A)XOzAX`F~Kew<(88Cb^F@;B_XOHR2?d5_@aM}mhP_d$y z%{*o`CpO%Fn_QI?5S%$%n+Eu-{bL&T293TJ*sGCZxY%_i!_XZ1Ev{&30A^60(HmOU zXgdlz-)v`M2qH)CQmhvzSC!kR7xBA2-&P#Zi8^gLYvhlEWHhbp6|deWpgiI6)KM|_ zIks5_yf7UWDA7f$xeY44HSREp?i@?(z{NAfL)v-*cP?%t?l|_p=6B@PLQ$L@HPlUP zxEC^P$R#3&)2z9`B1d|IEEuJLR! zNH#TGE{$Z|2z%i-PU=nD2e%HB-gK!t<>pe~&XK=o;G-c!fFRipap0svKU15L-rV0| z?kuD9B{m>%xz{oFT-Lq`lo_0n}aO>oVdz=ssB1lRw z>8w*^ex}ji4pe{F?o16&GHb5Zdk)Pe%_Dk^=pZxz0yW76ziinlN<|x_qiZ z;DplSHo%)##v&YQl9q`ZIMirr>93VCzC~TE%Gx=DA%Op53~on2le*Lf^S2cReNo} zMTAOZY)z7@pD(o)p2+P4?g^>xPA_qzU%!3gMFxRVnk;GJQnE^=1&9Rj5hj5SJ~8YS z6*vbeWa{$}eM39>HO3W|NXbrmROxO=GT8##zm6zWOHl>(U1V{l)c@SMJd6-0ET7#^ zvM(!*HvWOeW`Eo(pdoCqtGq7Bli4{j8eP%N+ZtPiIlmhS!a_cM@)MLq>)~aDK%%qK zUt(zu^?w(`XMalQ;S>x720+(HAg_GJ*Er%J89m)U3FUUOzJ7D5_2kPTmBDUljWaCt zT2$QExOht}&WiDDY`3?21HOT%ZKzZ5#BFtzUuk-6iD0`s68lj0Nze>YFqi*OP{urA z_Hs{do*wQM`WU$?GYUSrZXDir=JO{~Ij{bcRLrP(lcStUjGxzV{_Z-|O|51k!j&O1 zk?1YJTk5hFHC!!%!wP|}SeWFo99==`k(?yQE|psGST!u>-;|^zZ;zbE86VpDE~vLW z;Fej~ko|I+Y)2Dr^&9Rp0wDM*amzU@-e|w>?)iibHou4!n!B5qqiY7TzyXsf8FEhx~mGSu^bNW-gr6Zol=}q!ghg$>9 zjaG(S2i}`8K7r?n8oURoyib?@S_Gj;K1X6h0VKdD zI9LA^LDywS2I`4MYHL_x=us~_B9O@G0o*NY)LE=!MnOxq>{Opi`=hw0)tI(7hX+R= zhbL_>(r|#$$B-gDC>;B1g=lxcpc(ryz#PU4sAsUVvv3IqsA~)Vpx67aXig!KS*n;C zwt6-i@@nn_!@+v3-}Uy>=fz}*T)+bNV4V%f?6$;o?sGncN5-M&nqwFgu>5hYsvsG< zX_^a;7#NyB<$lsbU(IX2p{f6#WU!n_2cQfiV{yTeVz&5daaQ_)7i(kDu`xPk5dbHM ziA0DIojB*)6U5#YsaR{&M9TCfm0m^t2R9Ql!Eq0aMq9jy7xRI^e5yishiTTa^KGYk zv%>AfyV30Z$b&hnvT2UStrhl-bA>A$>iA1#T{y`$exd0=x}&E|Yf3C-37YU|Rdt|9 zd3uzP(R4_sf@r&|`Fxay!24cVg=Vug6$|}b`uk%g;E8B)pBjpgQeWS8+jthSyQx`{ zxUZZieNa>{KXlTfo=VoICEWZ3Ju<_<6J6^{_6@{Nk)tt|~4j8i)HHRUe`Dtf&`O z2jv*myUT}Vfy6BZaBjIxAR|IHq+R!b?WeW)I6Wy&lzQXS@LJ9T#9q#E+md6}svuLM zR1a1=%Y2cytxcqb#hz*}Dx#9pNF9eUtLxsH!=n@JYW8+eN@s*=K`ae93;1EcP~IMz6>pKWV@OuRv%=q z@Q2DUrphayIB(^leUD)db4fVLH^{21KTT?LJLHqy})mtjLP~ z&F7LoqfY0Vpq4UW{io)H5{}V8CMGxX5puw?8PI)63D$^rZiCWmqPGQFzU?mey|1EQ zYN~znrg>NuBcT^?>nfUWd=O)uIy{>Mhnt$L38{&YH42-3ub8JV^?xdejM)w`*V)$3 zS@tt@1=Ul&S~^AXyg-$%}_^E)Nvo37J)n9 z*=8jf-V4h`;gwx}S&n-##nnGh6M z2Gr47W7{SvJnB`x6o;Wfb8W`oy+x&Tso;adqB2%oyug6YOULAEshjGb#+!!s;fdp$ z+&J+fWu0dzZ>uU~r|^_SQg8IZg0fMse7c9VLM6g}aIvO>>bFWh;{TL*$=*pBK2#i3 zqe-VLbhA2C=u`TpZkj_uQ%!5}Nq=cT`k`Z@iz!}}Gx$9o_t{7H9cW z8=S9kIDZq({?T0qpO8j;gAx_CAU@WK>fqc~%m&XIcE!RVqFr&e-8YnlGU=xFEcHyA z67nP>Qse6dBYQe}AAcQ_sAhbD($9WXZ`A*-S6g7KA2){8vM?FNHsJgPo;V`-7!ETJ& z<}Ee&pgnf9KUl7u{{Xbho?aV!W z4fV#CeX-$9Ad^JX|AaYr>@s8pt5J#Vx1*o!$_(|K>^%0e*W(n-DNEOIP~8o(TwXg~ zjMR}2Df=MV4Cm=W_ycU!EqGVBxU`7B#S>&}RT>*%g{d?=KW~F~ru;oTcLb*$|G%N{gky)u2%IVJ%XsM#wN z_9)G0jCUeOqF}`#)LAad$U5M%3VMk_tDr7%_i5i9c4Qocw3}d-iv>J`#*cRfJg=~i z6%Ia5_gyO8;w)+B;x^t>p_dB&E<9X48cthm|N`5@0S_knu zwCoNCxB=djE%622N@s<@u{LsihQ5zQ$EuvAO3@R=uMV zcBZM%l7vwwld9*GX<79WQ03ezo{b|tZW2cD`Oc0`QH{QYmUYhw*M^DT`L9@*0$~%C zno_8uQlw%`#FmP(yl@eY4#d{jog=H>2QN4gN|9>4tYiz{;B zAeQ_4EVamT<3d?>PX2jsu;3fUqKPg!c{C&U?lRlv!wY%ja9m=RnWcs`H$BAC6P3mOG;{Hd@rFJ(g(cQrS;LYOo6h&F7E^_C#OYPWzs^Kgo@Wuxj z7qcU7&6LmC$T+5JRU`b-@!2f?5dB41MwSZFQ7`0gIIdXJ5PO=ev%lp zK~*g?0*J9lp8IDV)A!Cgc^=(`Cr68pkRpDahB$raqF76$Yo2v$w2Fl3>2rYCJM()dT|Cpx=5sR>-)u(I;X$;AUDexaD z&&orRFJBcKP@%J(XpnPuHVsoZRz~Q5Bh3cW9(=^tBdrqSs+Qm8&^;wa@^*Cl{2Cv& z%LCm<$jH2qAxzXOI2Oeu~J~aB$Un3he|XPjz<|LP{3}=Ib z@pRTY61(-76hw&z?wRV=T~|SSYipK6(oulF-w>WJ0u2a34Jn!)zQL-*S4FXD7U2<|`dYcgV3dwaB5bZBgjgO2jv{yZe92^7YH>Pw15C>Z@AoRMvc zjY`vs+V?=VUDR^1-VthGobES@5R7ko9j)hkYydN7uN6+XMlVdoGTWyJRTRwaO2Kv? z(&Jl2pj%^K<(>#|49J~x{Q(wyA$Q{zbVkQFhZDi8B=jDlRDVkF+A_Xnac+;cIl&ht zVp1Gi!#4T*4biASPV*h+3X*u6B|{tWoJ}n=E8Q2q3&q^3mCQHaCeuV?h9kPTkPkcb>2G*1*aCN+dMx!7)yRK6?QP-jB>f&#`8YqyRS|>PnML| zf*VzkSxD9^iJwuA?zV!xiE>UAAmK@bM$3MNzcs&Ag#cB*1I#z4iw6=PAV7;$fq_6 zH40njNc_^m#}d#URj>B%`2#ud2P)-tpMOJD>uMqL_KOT#{7eQQW0{E6?iw2wx-2fB zDELqq!5`B>@paV?VB^z|V8=U4+-4fqxJT{S9ouN5STbJGG0?yH9@{H~kk*hIupB4N zRL|o38m*hqT=i0B&@cz%y25fwp^n`BGWzg( zc558hkNO$1^4KM~{@Bhsnq9jUDyA6OqG1JwXmneq+Q_kQY35)7T~q&pE>$v%U%n-0 z%nf^d*Fk@Nq&FEi(Gee|HuOX5J4K6%yxo?D-83W7c|nQB?oE8wp3{=|=gx9%&GDSm zYOX$pmekd){Sp8uwQUuII+uQQrR3jyc(ZJ{^&4a(;-Y`c)aFtI?di~fPotIe=nbV3 z=gf+-T+wrp47HB2e+K^Ms+n|Lx^cAMcimVW91h%P9cqTLu8J{!fWDPU0%9Y`LEP|; zc4*P2rFWJ(f(!nm!jaJ<2xMV_xT?j?A6UHE?Rx!z&dkx8o1zO#-ndWUSVURj?b-$_ zHtUDfp#e?m&ZkdwNvZVSAf20GNuTY5oqSKkTK}tUTiOzSwH&`0r9K~o7FeFxOkYMI zOk`cn8EJ|Bt=UJ$A02CqTjj5Q3+Z9mGLg*i^K-PU*5!nCw`MrTqY4~(MKpRbT0Fw1 zB>4-jn`9N4cnrlEC}#DDzM!df-2)#3$vVH)=eSlkq!H?)@X$$*^Y0hhxq7DMXCjqc zM+AWFHrCfIbKO4#nA1JL9G*;f28!6^1N()7S=E+wLKT{BLdGQs-%(?RbHZW#e9Q)RPDxdb;vs6jQUJ<Yg}Af5jZvt|XVT z7*lM)^!6l8;z?BGUew1HjRPSIkFiVaUD}7YPlK&ehoRcHEL3Ta>{gO+=*GYM{e~(E zo>RE-x_2)f#^)x(*~Qy=Tf8bDs2!U7H@k7&b)rfSqoqW@grW9a5W`$8WqY=lZZ^NK zSe+3%g^%1=g5KBD6IcNU0!gEXj!8|l(&en}hxhIzo6x(u(;Rl%k{NBPODYsn!YcQr za-mTnN2V!*j*|1QJEXXDol%_v7g$N{9k;-mh>L%}`z#Ng4u;%sQ zc{N>`)DB>dL?WV~(kB$}%pwU@`fZqS6GO<%q`MX#F>e%*+GuA?3D^d%cJyib3}C69 z3-WF8-e`aoKYVnT?b-{JtHD}UYr_E1PQTg@1J-(s&@QIpi4bR$@F@%ZY4E_?OF;No z+;pft3HN7%{&-WJInCORr;VKI$L|qG<+RZ>EQeT$w+ZF5*Z{;n4?C0OmgNbR2KI*< zKWj_Mk~1mbMg=B5z7tw?$^-0rpvAUkPJV-t~z9OFteL6T58oS*G7 zu^6+}cN#kdb_1wl;n;Kf^Vm~(!Jq4w`5_Kb$Tm*v0fdf8x+x!Ysp(-%+(_E^__tDN z@$lD) zc<_rSPnW94rOOu6-c?{uLro-!%DiZL4&lXP4rx zeJ1qsOBBq?w_eWH_<(NSz>A{{QBA zRJxGs8>)>Sp`j(V^)AMW-X|!@CnX0pW-!%t5Eqma709wP?Xmc;62n@ST78J*ejOTQ zWwOv||6!Y5X4V+*GU|hWW=0@pPa7_L6KKSiQ_IrG zM+=H%#Z=|}qmAb06W!flSg7Q=Sh(XvU4#9yY~kriiPoVOl;LTPec|wyDa#rM^Lm|k zMvE$TDGfX62ctf@2`t(*YvDbT)0zt;M}4pjKBC9eq5@e;1XlrB9F5l}k*ZT3-luNv z8pmPVjBZ1CZL7NS?5KP7X}fxY@ABkubW`>gTUal!`B7Y+vN=Z{->rf579JvJ$|?%K zBGe9}7%SMZe)01JZ=^c~<|CmDn)T<(o2hR5?342^UW{lDFmRTk<87@&+#D0cItlF5 z47r<(nkkaR6f|&O@}{}rm=zGyweua7HIVO3bh-2uP#Cm1(U`0tVo@rdnoK%2uE8-I z$pk<<&bgWK*Yl0*s1o{LaJCyZsXY6;&f09Fc)hkdRHO(ArI4(?o%4jYC9QJO)<9hU z-TbNRP-Tj(-m;p#l&hJlf%}^LxIgjh?_{VsB*1GAj--xg{^Zg|8%Obep8iYOYDXR> z&r}?qLt*pj;)^|sOZ2zY>Y`p@CUWZ@T(9a=Up%9lmNC z$Aumu$W#AC+B*ej8ntcOv2EM7ZQJhHwr$&X(n&hD-LY-!iH+&EYG!KY|7PQ>`giY* zwRhLLYMsY*oLD@$wsl-ib|3dqy_~%IL6mj={#y{3HR~i?k+knbGf#A9$bQA{LM4XW zdsb+FGtxuW>snC>wfdDg57e0}bt+v;u;(98tF&n~E9jY{$7Qd!7o|F)IN!se{L0HZ zu0g@GNWio(G6PVMr}0#rONW z=l-y?EFXrCR&h(=2v_)>Jr3Y-`?zf(HcN;&3cOSt*9@5}+sO zC?)kY(5ROZcd_$X2p_5_?zLdG=8ZQ9_2TWBO4@m$w?Zu-h!hm$NJN4W^mEdR4Oh<7tlj8Gkd6O zt*~O+tJ2LyI^eGR6A(R;b_$pGev-eKcm z&d*Ija!93L+jCedloobQ_xSZ2M(=E;*MqkA%@cEV#0?RZm?9{ye(lV!_ri6!W~DZa z`WVU}W108DR7pJZ0^lJ3O^EG;rTkwBXtw`00nN(!e-O~@+$fp#ZyQ3fJ|#5lf)^#k{Tfj$;e4HKFP!59Qap`v_1a*lHCbr;@10TDO~4oE&VvgZV4~8b+JKC5 z2je2rM*{L=$0wS>rGyJC-tUW4!lZ*JKzs@%(Jy@V90bf10kMmV0--V9*7MO#;h#qj zf&7umFhmg#NE;|cGfApJ`~W*HYoDmOCRWuo^s#-5En`~=o%?rl4bOd+Sm|OgrLpm zaTjS1@Cs4)OFz(D{cK;s&A~PJSfRe}_kS#@#X1|K<>l2P0cbzG<)xu_5U){EKw_q3 zrFZV=DZoGpPS%kf>qg;kZ?jLicPPo@0vsT0f2%ZfGrfzx3(-|2q!&A z{|{lpW*`v});H|u&-LRj^$%yrPxbxJ{c8Yc>B;`VJ@3>H?{`3G5mjl-tRcuw69HHE zj~nwVwa^deGTxnqxf`-$Dda_8Nj4XiKLXl(yeDH!AbB8Blpq&MP57fkKYSur<|5(P ze;ldu*{~>aO#MbleFpTebVz4?#;PQ0mRJzqHdDhy$v~A| z|8x)_p<%U?8`kho{K#x8HWAfmBFw1N*8#o^ilHkg>cY^)@4$B1_BoQ5gvl)ZfZD zC;KK<^@8-#Gk5-jx8L!qOlZ#CpSJi1#6hPoq0;PvCWb6TL#M>!QktMkE{nsy_7hG0a1 zW!3&AYpH*XHoB^Y;&qhpT@;a%?n zN9_LEEvLo4uC=~(wo8eFhN+D6C%HLX{idKMZ&hYL@}^&>%c>&M z`H*l`^b%!Ww3Q}LWk(3^MgnRXJmj6d6Md`Z`H=;_+i-lG$6&sW9j1!p=3<9RFMO^t z(QKEk=wka`(Q&Qzo%wFsZp<3@>x0>0baum*m#k8jI}Inv-3vA5AI&*S)l>WL*Yf9f z^uf9G#*@0vrZ#O}U)!4@esvkP7M3v1z9bL{*kdE<6Nr5kGDW$p@YFzM{AsCobnURc>MRNGA zQ_F&ucy5lG=Qy9(Di{{N)3Pue&IVb##Id zA<_D@?QXpYCduo7PUe7xRQ{J7`#u3Wpkd69z7LkH)gmY<2{@whx@8Z^3Kj5kco61?5Uz z;5Xi$^;Bo+^I!V#P4`+uiqrMg`!wqv#Cmb3CVXl~>RHOszs-E#SOy}z)md?W=_S@S zi{X;P3&%C6@8!Ni`>A0vq7RJ3SdM9qyz36AuHSDwhqES3v*h%-*kciRUIr8Jzp1>? zC)iU+Mzk)JCD{KI2H24O+x%{nUTU;!k@4TwCsH6KtkcqyrKS|nZ`Z~#lkofIQBMIy ze`ZsNqTSm>R*n=on2@n(uJ}EiVvXi*C0^ZZYxQ+cMSK}*AKBARUsw$Fmv8i*I63;p zn|=Yp_ZN_b3+J_6@98{vzT58G3RO1&GI`(K_fv_S4B56DVNAhEyH8aCoZ4YgLObjq zyeu3sW~K}EHQ7^)tv$sVbFGG>GziL@!|~U2#5(a_(49d)J&xSMV5>Ut>+fv08ykiyN>K2Lf0Qae@L$_fQXV9 zv1p_49eblBR{JSki>%Q`_{sPI!=5H=!a#YbVy#x7G}L7Bhpd(Tn`YXn^sg zwm<|+1)O-Dx*PpW5Nm2@yP$UFRr!>}sY*n}Z0KX@P1s1}SdH#FgDFTX-y?W?bRyI! z&EdsR@O7P!Th=b`+%F>icXf(LEz@!JoDxG{kCz#p$0OV<>U|u@=qy8j`XOG&d>zxs_XFJme}@zLtu81E^t(BFn@lnfCfE^ifGY&`GUcIG}G>h>Uh8|`8# zq#|?VR9~A7Vg@OZe(h`)vjeu{XoD?y-l~H7g$2Mo1t#+um)=nyZ<2hxLX*$FigVcg zG^uF&pnBa-I-ag(Tf({W&S_{w+>`bZD~Ij84O`0<%cK8n`_mY)KT8kng4r0{Ah^L$ zwQns&Ml>_+c6RnlvQ+wO)_VL3dsd}@!)OZNf_ojh+pyck9zZCC?<&ndzY zIiL8kC|d7|A{T-{tyS9dZJmx`cvbO?OS-$36f2Qo0C`ehXMHB;t-yg7PWbGe^Y2~7 zidPE}5_K~$@^6*+@t7Z5>nAy;%+0HrX+cj^l8xzl@8g7GT()9hJ~S8(l5)^i`>OtS z5;Hj$ab=57$$$orPg~^aStl2y7il9|YF$@SmI?JdnK(L!xHf|xp?N@6_3{*DOaHQ$ z8j~s%jk@`qPLG>(QPh}i>K@Iya61Vq5?CjmG|!MJr*BP{os@0n+#Nb^5W>p3~9J}!?KwwTzB}|fN8`k`}l_3 z@a$Fb_BR{FzGNOfO;XxJ9?)%G#IHf(RpzNNR3&$2Hj#2|@Jr;Iw*bn*=EhA(R^ zV@$b^o+4|Ta|2FnA1@cAKT{(6LY`kBp!A4_S4o&@(>sL@KoSxGn(wE9=#U!M8u1&K zT5t8=gf2WJjM%d}zNu?`1#-OX0E@ok0KV596Sl9W^_v5Ts%Gx;N;{bizU2;cCWsvr zQpkPUKM(#H?FqlaPGq%T!R7rSvU z3V9S^CM=#I>B0jyD112_{bQ1Wsy~*$$D{GI9vFrFhnLg&*&%{2*pt>?!<|`yQP3r|q{o~P*QUjV1Bm$$pK*cwB-C zTUq@6Ktew*y3tG9=-ABum?q_G){mFVD=H-C8X%PdskaB#2HB_D%@}2@t%`hTjWk%h zpfa%=ZI}I-AAr-xkL^5?LGU6ZPHDGd8JwN3K@+0oF+8IK6BMe9f@+G=+^97 zViX@C;H-vK@CPIdaQ zjf%f7#my_Z(mCJ2=Mq_Ej{BI%VQIhfM9uaoOyEPrxn6JJu*OeAHMhyiFg{fI;fbLX zwX2_+p?pEA7YYaDBGfG1s^%*+RtMSS4@(OS;Jzq>9zp$StzkF@%#{@AHa4-HyzixS zuDzOry24l4weJy63Wfj{rPyi$l0oVATMFldve>v7RxORJ?b2gdS_hXD8^*KrPL1sX*R5 z_Nkj5fF)|34l&&!C**j^;*&Kc zLChplA(wv24r{c?{HzlPTDxilS#;7amM3Jl5~;I;4*<;vPR?$@=TbM|g)Q^-FzR?! zqS+ZNev-A8Hj~@fHmvBD%5($f6aiBTCXevJGogr4VrwhTbCbcy*!mKGd#dfR`_Bl8 zF6Tv#-u_(+7&ExuxExu7wL|vTBA`LjRI3%({?%4^yQ~Ua{?H_SY6tdgCo%dexwQO> zafOIesGO6#n^t+QMo~UuuCcOuU#^PAQYCC*VF+H_vV;SI6}zCCOW8!C8>G<0fD?w8 zLmvL}xW&Z;7aP~BLkNM?`rNqN^|@p|w?11*ORwJFE4;iSVCGEPGMsUh5`jwT{C754 zw>Wl9s=R}YdWf_nQv593m^SwHs!ZB=_apvoWRC??G@Lq z^ddUSV$8rYw9`~t)T7&Q;PV({HwS`d{yJJn6$mk}e{ zH>!Xj(l4i=uS#F_9P)!VN_Ik<1!wt*oT)L~iJG0?a%3gI4t-AuUOT9QF7V_woXuQq zY)X=+Gj=GLXU&KRepP=(mGLUNrI?Efcb9YVTu}yQq>0$a@4B@K!eXZ*me;n>a(z5V$XA>dW7J4q zMsLgtM|`igY%;L#m8WIj5V@=vl@@2nv0+LdxOO%*p^0b9&u^wxXjl7OkViJ4wmmJT zuJTw{ndNE5bHyO_wBOH=GO~lo&sum`oRG7)$1nft?n8YOLj~vfZ$Cl@BuVS`C}V$3 z3!Xf%8w#lTdid1oUr@{YB)b1)F$?hDI-@EvAE`)PaWYfF!u5VgxKbt{}7RovA)Byk6lHO2PUGJUf z;bWHSZ2QaXDkQI_f-ctF2f+bnjPsXnn^%gyecmdA5w~$nlPc?K%MRUC{rgvYRbwHo8EyOPh@UkRHOTTR zzaq!&XTGAeU8?K99M|Nr2Q6-vPF@w`JxnKquoulMfZNXCd?TLoBMQeMu8zNuZ-FAN zGNhl)3xK05`{&E<+aF7%A`eIBS^vQ31wklnHEnBKx(~J4Smc9)QXm-Z@RIay?sd2l zAf2#thwV6UG_~FhJ7x_go4=Qbnpzm3GqyUzflrU@0%H2JkzAx`D3OdWm*Hty#&g z&1L{%QrpeG^%?mELabH^11Mg<$p3od*>H3{a1jde}oy* z19`@kL7UakvzJ)S`@H0y)`KXr4cd#8AF|?>8z%kmS#Y$ET)TgMgY5$LBW%!Ub@7C) zm)l>DmSGgeQpC#bO8h^LKW;GvnjcCcDz!EX5<0S1?Ip~?nH69_8j-e~uPX_F@HpLW%zQh%1}Wk(6e$?F6K~(_rtqQ~!%6$o5CsPNw=a~0 zbtYvd|M;-)h5npW`a!a>ti2nv2=N|mNlJDWh6}u#v9vpVET}4Z+T29QQJVsjQ~IFPr3jFO^CWqlYQZ z*zuDu7n|f~`OfUN^;nBsC{v$Ixy|=Y)c2~$md_BI078NLB{l&u=0&BPLz@GvTl z&7UHOx@qbdB8}av;@4Rd(3_mm7#^>|_BEjs!~zfg$;#PQY32RXh@I3_h78qT#j8-& zqvy69do^K%JVy>#QSSCx$*Xa#{yNioCCv}p@4lPUC5P*q#`l3ZD+3)kt1Qp%EkQvS zl(}t+xRvQ!TCCt`#hIt3f*TCjK0%LfHe#ZiTX3C?vE?&9GmRVZ#*LR`oubx`VSj)l z=0_Fv<9Im^m$f_$mTsO}=viB0r_-)7H5?43(poAv|1|fz#2GZiR58>Y;be6;-gI9o zCX#TCHh40g4>SO=4lS5|>HoGjTZP{P3Ncs{asCd;km`ie%-;B0u^>45=Br3m3 zVoe`Ofpw|=bWZ1cXEM&M@swnR0;##amuFEs#(;8(G*nF}2~2VA;41!ST>s@TeVQ(c z;Z!ED<;pK+)7d$&L0h#8744p{yZt(_lAvFhWOj(w*L9O}Oh`jB-s9-VpG-4AIkn2T zbH>1HPvujqU-DSVP#FQZ^!V-(<(%25SYwl1_d8PXG!awX)ke~i&>_gN*zIsz}!kz=z#Zc93|QM!@o~SRZHb8 zb4J7}(vZhnrFnhmoA8?F_3!a2WU!NrdkhldUCWR1@n(7r{lr%M4%yM@OfBK{xFmY( z)C9GqNa5`*66|}&bthjPUU4ukV>55l*u%}j^rU+5z*)prB^&Dr{pRt}iix?ATfh@z zAq$`}C^)rC!Mgw+s07X5m0xk7G3CT(;}5B>V{@lXG6cf^cl`Nt&g?{IUeeTE1vg;d)gVF2z%5%p(E$!;KIVylqS7^Ik5Z0*LHY z84Tgty2ca0ZXzzaw(%AoxAnkt}J~{q<{QqV6WdBb-_wR)Nr{VKIr~fzXMMNyD z-2Zndw~R9pe>nQIV>nO(mN41E2tgqQvL*}>6x1L0x_1{u|EG(aGzvdDJO6I=bXlZY zDve5p6n7@d^zLqXvyEgXpC$L}5Fz4n7Xaw}3W|(1GHoDU|1v2jKgdGC!G@Tvxyo3- zbm?F?fgN3|^>XL*eYRpaqB8^xy_=|iJOTBayWR0rcx$98&OUFT(IPf5w22#J^u1ZU zI``>wn6*499@~Fkes#q%g*8lJppjCiRs^qcdhG7*e!av4U2~CQm%%w@QI95;vgz92 z_`jiB(0aZw3`MeL_3(_#Qy^i2+^noCdi?y`5-D!PM0qWDA9DyWqJc;iQZ7eYrGpv+ zg*T0aGH=KW@k{_$_;nC@k6@W1Vv?xDBO+=aaze)54E~NcXSugTg@;ukX9^okHoh#p zzhsUV#M20MA>@IWx0^s3B(AvOXA46;(I^h~yn+iQ9^J27u80FU1OmL-#uSgSJTiJm z&;%suHQXhXJXT8y4vmL1Z}R0H?n*FC4ZEkQ(@%Z5Ohk7VVAO*Y6ANa-=17{9C_Esj zA%C~+JJ1p1Yv>#K_Yw)TO&!%f+U(EfG$z&?H3kV?a;{<0NWRJI8-7il(l|WTw7Z zIk(1MLQ@-JrUt>fK2KL9Upv>>kDsA47j2)-5k9CC8JBrP915x>1MKpJaexP9;-=!8 z!u>qPQJ$#-s$*{FZJ?<@s)rS5HmJMnF7B(gPHZaF_d=P-+V66kH;D*M$&Q59BVILs zsmrX}_C2hs-w~kp(kJf&O+~q`e6=A#OPQu8Qn5XmV=rt8kUK^y0TBxKNJ|nHd3J4z z8gs@UrEU{FiT1}9W=}r68FuZ4384SSoR~zLFOUK-Ga3*W1(MiIJXQ#X(K2;L1s8mG3JzZ_YX zTtdZE1j0QRR!(#}w zF0Tg>A|hR6L5Zyi_KSrFjs$I(V{V1WtaY4BqO;GZ(Lans1r|RcEIDf}aOEIrg-Q@d z=QV1}s9drGSPkwHjk5(1T%^~?9ZI^bz+b#Nl!e=jxU?lPgWnkC+zJm(Y|l1uYzID# zJ-DzXH5VJqpJ^ftx{b5eBR6+S4O(R>AU)$ZnA`%(s?5*#D^`oL+BJv@9SJS!EI~z8 z{G9}Zmt7=vCQ%{Mu7MM+Aem)tt2ve;bp}g9Mh=DHl>>Js9&!P^YGa0{=(!mk_QW{* zw`SxD=Gxs_1GllK?HXQ?y!D_0f~`Eq*=mYCxWZ5@0lNXzqxshFSYTOY?6F6pdZdo4 zz|fr~7TfjGX|zd7Er=!3xr|3BLRL6?&RbHPp-~V$hjRaW-)KdrBU(28=o8m#tUQ;k zwi0ddd?9aJIR0IP;{Lwa&kGflM#y#)Plb9#Uq6P6V*H7MO1rDj4!>(8(bvnk57Vv5 z6&GOf<(fQ4&afUsav!ov>@LO8c)21mXV4zCw9rugIwupJuQ9A4vxv0A(f)c42=)oA z(QLj3VBP-8UgoVX)~K(U^v>)lnHrB{1-ew)lzjoi--B^IbL)*8H`%_M7|XZC-U-ky zplc+xY~nr89%(<5xHxo=2=nS(Vi8aI;{7hB$j=Xx_4fA(*RG%%e@7F%RV#4bI(-`n zWeE_}GSMRL32#cQ@r|k>G0O$k7Rwc{F_Jw@yU*QS{~phfPJA79I>!w)j->Z>FWuDs zyRjxpW=&)UA>N!j>K~3XghowlaG4q1!&L#U!S|sK7^)3dtN2#&p(!G>!-E zQGbRpBh|KjGjYLOZ*^{551x%%)4J&p9qt3hP%S7(vOBsk^8GWe0tN!$-N*%2wsVun zVWl)*J`t$vIAz&;0xvB>9g~6+9Bhe;0>X+*+tfOs^(&mfcj!z+f2t_~tJRwjpAh|8pmFi1{T3s;W_^E^u zs;CJe&yEXCh?*BKJr(f^NF$aP)$wAjNHX~+r*ksRBB};l*hK)Xpo&D4iyC_&bv8Bi zy~?Wa!O{#Y*d{lIk)_)u!+@s4FVTN=uC-^bnh|}R3ORl(&1&{=ds1=Uqq1W0PA;M* z0FR(4^1Z(ub(-|U&SEGKfZmHr@z`ui6aI1P$3t~tD^7?k+L0`@6OL~1zk|r$4yVph z1ferEW*#3N^3ti++79`%V`HiF z1IbxdQ1V}gLeBr*g!a!b$@-6*`kxThzXob1?*AuU#mU6_|FKJYfUBX}?sDcW#KDkC zjGf&i+bfA+ne>BkV1Y_-28Xf*6A?$c%0z|Aa7tAGFAx(E-zfk-yz*cCdjYusUS5l? zZ~Rq&M;T6&|qb(JRYntr$xzrV4fX&AY|si$kN)#R5~ayB=8{9@8d|JNsy%h0Vc`7 zUL+w%;0W&|pk*Wif2qtSSQyn~LrEaSP)s5cQd06;O1#1Y1o1&4BQ7DrSm&Tl6B?0z zdmvRXFbMItFH-P?ZdjOOVp_VZ%S&1?_ZJiqqC9jjaG+kMRM>v73vlswA$;JzF>tKF z?Vz@qYeB$zl9puqk3KKucD z11LGZHApxYP+lXvZ#D!7%W5pp{>-=U{2AEbP_M%7&~799K1#IjJcuS!`1TT9(^Q4+Y7q=XDgHlgc!&z%p^<(Vr)P} z3l#Ad4FUOX+b=+giiGM%h7bnEE1Y5Cnh0n#SyHO#Go6|y{bd=*4h71G40QH#x=X1G z*NTVi$l3SP{?nni|6$IffpPK~0P)=>t&Sc90R|Nv3=~|9LKGMo8H*(Z;{x?=fkDc2 z1z-^RiCPZlB?e*%V2@c}=)-w_`*`;Hrhs7FE9ihj!WtF<=KBF|hnE5Y8}R+tKt1%S zIQ|2_-PiOf2=u-CW$E43@%88aA7DqQ(ZD-34RGLvsNbQ2dwxR3g6RL*Tt<1v)PE|9 zXL5M?X|*ot$3m#=&)fd)5zEY=fP;5q3oasJ2oOGI?0Itt?ikopA`Qj7dIloNb;z9!g*EH&ybU zAO7P5P56A&W3QE(!0U8~!Li>}qYeS!1{>r#vH$$!S@m11xdK-9`C}bw!oL=5uP0HouLm5_oSHG1Bjlajd+kn1G)?1r{IMay00afE3T5B(n zcVt{45T#poSkf=B{MGf|C7H+JFO*B8HpB+=gJO4qi7HoT?FLxV?&-CwfZ#+6ulU;A&oQ%RrmZ0SkF+ zL5U2LR(Qe+dGv4nLnOKbswXo@qaw-~Oks37y^0D_` zSoW>FzrVo{(nG!C*MxoBsHz}EB|cr$hDSKXg;xwbqjGI;nI_=?{#GC%S1R+>wYQ z=n5eNnC~c1wZd@7({C4W|KS|^Iz3N0qJk)R<3MLTOJYwjkRFP`K$+!ZxIKoO3hjUI zX1WF}cF~i6NmQXtF>O-%21Mx?uCa}lc~Ieqe+_5BiqJIa$@hFEE}unw4V5_s4b2QLW2_Be&YyDjWAHuy?hL8c7ds6?@XGN>Un1l?bbe26c5dC)V9S7 z$m!IQg5S8&T?Ggl1$-`iFqiZKRqu}``Syev^ep=kesBLuHPpV}OZ!9L z^p$g@(oNt8+R7ZP_MTEV`{KuGhPZMme^jiTw%!!WUG>>IGr_LQrcq$|QBpTihh)%e zR)sry@~fL$e!)rIZ;#SYjUd>^4{e?wnh+8Y*0w$Xc@q3*u<;-`^I6*gL-asSc^y=z zL$Q>`UjD3=S!N`%mG@Yqx+gO%sQGM5ygO}>6svsLq=Ut_t#4Ma#vQMB9!~$!akrS* zmZPGs+|g>Lp!V;j@xdc~Yt@PqS?URZZF*IS>b#rK2h;(lSqegdfl6LY@ze@lD@JlS zK#A~Je=W~bCK0b0ow(pO+ynB=DWw$QQLHnb)L(4pbe}}Z9$*)`$6q9y9PnDT%p{_q zirZFMI3Y%V*>w{}6u&r8(wfpUCH{jv*d`BtXhIhgn0uWkn^Avf@LA(qC3h0cybEjo8>H#kq)4fs~pmK(qdaWHH_riF@%i0sUjZo&|}kbJm`cxE*utyYbjEW}BA) zjG=5;Uf}9|t7!BbGp20v*zDeQQ?OL#lVg&Y!~XTe;MAMGO;(5Oz1D1rNERPKDcsv1RLm9 z1KV-!5@^$4AKF=#zU189Wxm40^)X2@mR zxZhxi4#mY@5=?zZfr`B?a#K?#gjgS0XzZ4MVl_1XXnTC0gF5v|<$=5itHk#|Cd-~j z5F*#{E1tG4=dw8uk}~0N}V$n2}Iop&wkqT=W9~Y}M2nXpg_pT0CiDUy-$?AB7HU9257W3RTzv!@8x{6U^NBT>VZhp)UK$?#TOSDzRB z(~?q{{9d{u=>8LKc`rN;roHv_u4LEqVUhU)$rh;YsPq9@Z{M355nwKg-gXraap3MU zjLbtggv{5@@y*Y$+scvCPBZbumuB|TkESY0iQ1zp)Y}V;I9Xe~7pQzWAxOE>Szo~x z26Ncum3q7SDPs#NvbJud?2)GRsTdNFY8$_emPJBHNLQNbLVRBGKEk27)h>fbUFjwk zPUpqX8yLN;=&g9iGG<0#O?9lSCX%gGR#Qo`?kTPop|=!nWrXMPSg9OT0q?TtfAjm9 znBNv5K^PZsXP5Eod~1wFB}Bzbgg7yLVp#iiYN~Bj!n&r=S2z5Wd%){3tuwkl7TEVE zqeq455R|jQS3GsuB+I@fw+Pwji8 z8tAl6((|k9TJx7S=DSlY>CVG-E%56cznFGAt-BFx_+FE3Z(DH=_!olsZi`lCnp@`l zdsNWvOgh`f>hiS28*W4il266u5)a<`Nh6Gw#-AlfZXr04thfkc@T1{_Y^#IM;!#}b zK`iduN=6hjgst}^2@DPFe4b=$9&Nj)r#}_G-8?U+-^M^i8oRFH3~HU%`Vkwp1M9qpka0tJvBks|n6!J2+L-!dB?qr3((DheOG%9|j&0!&`Ijoo4=g=1tChotboR@(0zE={ACB zuQn#X=UelaEzj6C{+u0Mc;Vue##)cI9ZVi8_}AaYN!4=Qr-0_WM?K&_V4{d2&&^Ht z=GUmCc`UE(-iK6zGsybi`d4IxF(W?-A?VebZu4-|P!2jw*qF=u4Wgc82vpxRP_NxI zB2~|NMK?J07>YrS*#G@e3L8`WYP87IUTD*5K`vi8{`H#MoSrS>Qb@Z9^xK{{mvVOS zHoxFC2;CBcKiRF#0T%G5Mg7**Q)i;B@|g~?tcf&&LOQFIX<2o86(m+CN@b5foB=i% zaxsRwuT|M&eCKfVa|!V-h$?zP*SQ;`2FPz$;=)BEILcwX`Fz_iKjEvLY0KIofL=%h zmH2N8qS~gt{tn}E1UoeVaWnTwXB7o6g)X0LxOjn5;~b3xW$FoWf2G>p)vp-ay&d{! z(h*=G>ivc zRv^n-1VruzS@(he_OC7Y?*VUGVI#=TnoS9nvM>L|>puhnbamwB52CE*6rcU})U`db zBrBcbt!o=z5*1Al@-Tr-EB7=Sb;=gGmC4kJ6bMZ8> z0D)t8zSZqPKkVfUN>PX3__tGMBFw?uBEeh3xPv22ni4-QD9u_YDYEJwnFW*{NDb8P zVWY6#Hjrr6V=m(%Iwt_-H1uc@`FY-pwfzM;#=j1v?u{G*kaXSGTechH&?F>hw_&ha zIQU148gGJQ6Opq?IVYS^!s6O+yMmw9Omfz&`(M@S?0F47FXOqA(-n}bn&&%kcce@5 zOzGYR$fP(e|5`@pz3;?^s75*w<%84(sB@JtwTU*+W^~zS`ZnfL#gilj1e7)t;&D(E zt$FCl6_b~GPxV6PGEe;VxM1sDwEDj0M}Ip@F^+%-H~F0t$r+U69(9@}`SsK)T;(Y; zObqljOi+ao4cD*v2*TA=RGc_Hr#Q04@%nCk(iZk)BraWSL)AFZY5Ss5y~G_xN#>R{ z6&fUqI^~a@Gg1iVfCqpOSfrpx7ptH71Eeg%><4pf=)*N(SWb#%$uA2?&n|VBtm_Q^ z;E~I3lYT9P-Aai$7t9`7W!t|zq-6D766ziC*<9gUmHi^Ib4tn~C0HC~fTDoIouGor zFcYpUc*^RlFcdTF?4UtmKFeN(-9eSPzJi09Qx(6wz^`JSo-7f3>HGqaDH z`CKw~QEFC}vezB|>c=vyk8d-(s|Hr*3Qn`R#{RjiKAN+wAli7E0)#Gz<)@_Dziz5f z-C4}zG9j-H&ziq?H)w|$w!MIqGgFI;FXcDb-^(u%>$tHAL{jZVe}8t zOQa@u79BpMwS4RE!HM6WKX75~2UCrS^QG&vVLO%w`q6noM4P&+FhgJ3C{3@ln{P=S z^qq0EXV8TSuO#spVrjXofCSO8Sy;)vxvDW4I|x5s_A?X$n!mP0F!f)|JF#~A9{$+l z2omVz%nYUtXEbO$ziRcRG41;KO8DM3UImHsN)Ehbtejk7eEl5+-PE-3?FnOLH0xCv z*(;jCCg)1Lc`$5eH!nPbnn}7EOnxkb_7AXXZwN;DocH8EjB(1B8O%xu;RAVGuZJ5F z^ONR0CWmF)PxM7@WlzKS*~BoRXk$DRu(s&g&i;MK>2fW`G_J<4n^>lG-qy^Wa3_sY zJbVYMo>VBS3-AJbg8rS*I8P!2$RoacW$l9G45&s8a#;jPYtL`BUuE)7hjP&Dc>t*4 zKYFV5Yo(XrT_XY1$g?VL0j?aHpl?H0CHuEqjvHJdnv@tNxGk`Z(Gu$KY7=^I9gaJ+ zFD?o3f-%qDgvi@Cc9g3!nd9}4?efD3g5YIOI9d&KUzBy$c{jk9YXQz-)}gM7r2mkdSt<@Y1e>{sLIeP+&bLD zNwkYnozOi&9v5Zp;LwNZ0+xa+~e+170GT~@h`0Ty7UN$1d-?Qu3Gr=)WwIl z+MUntE{3uFgT_kQr#w-$Ivu;JKTMyRzp1k7ah?`0hE1QPR|qa41fQJq1c2jzMI^rb z(MV#(@Kpg~Tb^Xyc5r4qKp9*3gzyttG$U*AYFUrsUQZTOfbJ6rAl>#4mfB~gd1PI` zur7>d;`FmpR3M)9R``q2|462JxvYiR94E+UoF_@&y`x)p(nCqGn7J8_J-o>i@<{hJ z-#n-qXB#|J#YZvE%I>tcrz|QZ4xdNWN4nry?-tyfsG(Iy%PnXn@Wv-~JzJo3oY;@c zAZ6+?<{v!HcrB328!r5N4W;0veSC2JDCzxQb4P@|^`XmbpK2(}%i-cQmXc%lg}h8H zCZ(e4Bl6y=p#a+Y`_B13vdv2ik5dJTD-bJ84}pT>ZUUl14VQ23(v{wpJvqvQ8V4JV zC;n*40mjc!O>m6`dVA-AP^D_orZzA`6em^@cd>rAhm`d>wi}a`{Y85byyI7Q1-3QA6J0BQ24PA% zj-~Eie`$JM8VSiQ+Ek~-`xn=I;Wt>NCBH(K$qeF2@KaCzE#^O-w+fC10rJ1Co~t5?@9Ok1#ZKg70*@wdBRkN8b&M zFIAH$s7)nGsgMa~8-DosQm5fepP(-wiRcBst^iDXX|?2gQ$0c+5sL^wxk31z?lJII zz5EaM-ZCu8Cwv24K}1AA>6BW!K|orO?rvBlMY^O}K#-E|Ryth)rC||i5Tr#)kWT5` z{f zy2fMf(yXg}{!~nup;TM-#%uSpI$YntCt*$NRpOWQtI~$Ha>Iu?*bR0hc7KPO2#LSA z*^w(TI@M}~)@ssJMXlRCy2z|De0Fgph_AOh(GhIXPv<54!IFe}&L%#i^H#y2*B5QW z!1*V-w3^!MUG!5zdo!o*PbjF2KYM3Kh%WwRX5Zy>k(3wwqAXg4I%n`ZiJQY^Y2+uZ zy7J~&`9+>M9?Qpc1=Bk$Ic;g2U8`BSwRwz9>hbrbY#U$AQO0(5*MOr>&6v^2siBO; z35vGkbo$w`bE<8Ev+WpWQ6n=kqvv z-MgA@UfY);!cw2_hRqMZT_x!pE$lqfdEk6sLBE|rvB9+NqF9u~;N|V7q+WgR?lO)L zS3ePG#!McalKsd&`nXH{q1gAffoC}7-U6C&y9Xx{kAA&~`j+8v!PJFo0UL#*oUu@6BHQy1a^+r?Qih6YeFnYd z4~`v7iPqn-5(x7*vF&lCkE@6EO=#^k>X3fnTn#nzZ|I^kb}|yYT_UsZ;Ogq%*qWWJ zDqg0X>RsbTONKNySHVqNe(bEp+JNi(-IxDxtC{!PHDq!uw)+3h_TAji{J-k4{x=C2 z-_4!QK*1&N=IrT0CwOyM!v8l#*#BtC{vQ=#H}^sRuRV~q^KjR&c6;vZ=;G{jbAR*` zI-cjw4$f}cE-x&>)pj!0uk9?YwdAG$U#`AWu(q>(d2{PDINd>8^@Y1V9pB9@)}Zs+ zo)#YeZk$$hyt#7vf5d49>K3o8Ej{RX^zE!XUeXCY{@+i95CGTb@&2EVh1kx)HXxpw z>c*1c3?lK1GcAx)t&BulUgk$K@lAGq9D%;fSKKz`>z)@pnYX}t_Doh|n}Ia>m8?!O zL+h^p+V1ZLt-7Jq=>WKTuK2+2Y{s8l_jv)Y6Vg~r$p8QI-w2#1rlcHiPuDgyG}MDn z3h%RtY>1RKRpa7n;JWGE0w1kn{Lf#TU`r_LZ7N~#ndsNk5`~EvQ-dI*_<>&75!{jr z0|I%<@_ua;0}cLk2=V3S`ppA@@DluAK6004PAV!XDS^DlAr>GO>Bcvs!}#HDcMG0@ zXJ=;@M=RAv5VWeXtZ_vy78?BV>2ML&mGvVlYileltgyFlyTSE&EG$&b@>ozzS=_Gs zviMyDlaBGC|FwV(EgX+lR8r!vqko!s(}o5y#ms~EME~=z{;04(jGd=f>Dd4C!4LKK zxDmAf)7QhNQ5PcilanWf^D0hcF#dg7)|bvdcox(Rymj!cZ&VXMK!#{%^9i{G<^ z*$JX!V`JmurY_h^k(+c~XSW)IbCq$=2E^l21N*IN-o3m3%>?&YpQeyRicSiQf%I*7 zn6Infg&Todlr8ZO@@G=DH8uH1@A?hd%gV}zhKAJC)Ly@S?Ko4{`g(`5bz^5oHDPsk zcfQh4z}VRMLc5w@OQe{&E1HZ)w|pE1M+tiW{hce}cRMog&0b~V)eY-+}t5#+(iX`DYAPln2Ja%QJdx|DutBcY{31F z@Ib=Mn7VjDQ1{&n#beEd=IBwTWGVrt*@h?*4y`i0`}e8&trYqanF2oj~_q6aLJ5}jj^$?_G!Ve z4G$0RjTFeUsAaS2f1J&ijXpcogiqW$o;uUmXQDsOE*lWhfER_`MMvGUc_GjYCA-!V zZw|6aS3{|)s1)w*fHyvqDx+2Ua+U{2FK+EsTlR!9l5jBU4uX+6L6)!6#IPe~PPxzFY9j*U0P}dNw-fo>Ce2*>LR2Pg>^)iu*Y)a48Buh0 zG=~iTy_fGc#usMloyYiqF_O-2OjJyLdhzY-g6iQz`W7B=Sy021i{73d`Lj~5z4`MA z82d`ci}9>n0bBfQ-)l6=@z>`MqGpu_d}3l^EG#9|`nQyxq6GQLQU!44W(|A(=W(8v zRJgeld2R+>a|#MY=$bd^$6cViwp zWur@7(JA9FHT0Dan8d5C!9kVsTFMF7E8|)l)kV}pM!EOsSGPA2d_KN0kt~WYqds~P z9qSuKtRlV@7~IYI5twuPJuY)mo(?yMUgi4YBKhI z0gGbXepO1V1pP=Vu*Ljq$mPinE-tQdqnmY^R*?o=u%mFPXXy!FY~PU{a!Yj`bN;*aJCn2?w!K(!C{*Gy^`d-s#M>Sx|%h{pH#vLq{89F^&;fFVyxK`7lldrcKa%EZwVdrN~if6}S(NRq$sN)k8I` z$1NScLSkE`01>)t} z?ed^N4AZAqxptU(?eQ2-w2FK=hFN(YofYDN4fs%q1M3CW@GCw88a{avHbm-ibcp z?^9VNRn?p)t`=QUB+;Z?7t^+RBYYt_I_?!ZWzx3m!0#k7DQm!0p@D<60o+=lH$%71 z6KMCvajr{Bpf@c4Ce9RozAu4d(H1lj;N~9s_3Pr|crdfOPG$|hh`z9=Qy@I9Q{VxX`lA48kyqo{#WtG%txHPe?13z*kloNRF)J5c zkW}%w*s#_{XL}vXlZ%YgK%-QHzWnXOhYyMEbkL<_;=V_hRo!JRT5QW)WSfZaaQUwx zSY_`HdX{&uo#tCIu333`EvR+QmPjZ(-i?*qT)J zM#7MRrN~m`+uy1`oAJnUH~$>n7%dY0YdRWhCPTzmL`0*#aB~m1nE6&euT8czZqrP5 z%Oqyi(%jwY+7d8RM|NPUN*T!fn_ z2yt|!;nx2064R77XKlE1|4&a@_FR)^h5z}%(Hd|;EUK9@0cM+?qj|@h6Yj5HR5-td^U{4Ceyc%>%qrnH5~%cE^Awm@AR+Xp_{ zfB)=FxjrKB?C)YY0j*i9??hKu*Y}vYduDC^8M_ZidCXMqRGPI?{z0g41r8?71*DVb z=6*zS+#~_5ms_5!xQ)|H4Gp#zO}BX^P}CrV@p4AJ94*AT=FD9C^~D~nlj62l)fQcp z!cHK%VW3g7hjI5v*mV$Q68if3qBCXMB~OZu)5ryER5nJ7!p`M4HZ}xohYAT*gdyO+ ztm8=GKul~RI$Og~wWYA@Qu15%W(hmLb4(Di4BWRgx}9f(apon+{PyDZ&7*r^yGaITJ5;3$ z6$ZTjMGllSc)~iL;lk82U}kp?rYbHEG!2*<&&V!X;xdlrepv=pd;nuMhgu<`7PPn&9Bxlzk5yJ)Heuhgn^K1S_e`=5wRJniegg4; zJuDoyzA|q8=b(d4mjhj>z%PnU#3JPco>{%p`|WW?Fx+MAf5BEBwtXEO`A9L3{jGDe zoOII<(~^Y`mJ6iOb5*UJbZLSeMg~h3|H5V0Ue^2DOvn0Lz9q^Z-u)|L z)?jN5@E@({rsn1u5JS$-TfO&z+?KH?k1|K;JRll8%I+CqeI=?yPEyyd@gOfaLMSnDFZF)6PevT@8 z2>j40DpS9&pP=O&`nEF(njEUrV}FxjR9_v>ppA*8wPR;B14?_WNK^eTx4dQFM?|id zR8(;2W)G^IxV$OMm9`%(RJ@XBlzT`1_~nD^i;ghdonK!#Od4EP`crapa)^kC&QIO< z;8wP_`pCcl9v%es<@F;;|Ayz`__9&NcC!upMapUG0nW~Q82A2O(iRmLt7Sg{YdT6c zniRENI~?km_{7JxQmg1*&If&j+4&CqXwGW^$B&VHcRe{ZRgMK(@g!_*_(*yLaueM> zH+5Qlk3pR@3F@uh-d=HJJxJT(7aJvEz%#(w!~-n-7hdqh~0zz0dZkH>S$u3%Ge9M%T-oXT|$`%V71QpI8Kg|5I%ykE5S(w3-tR} z0m!>jtTzj{`f7#jB2&6_q*9x0qx=!4JQi{$fmgaG8Y7tCNSoQRw)N;JZ#0j5X=$ml zstN%^sv-0%4K#~YGE%vW4`?UKb)z>iTJPfG7Ffu53PGWrpfpQTm!uH&V1=v1qTpg) zyVMUJJnhOk^KJNPdo$JYy2K7A2@u+*G6EaQt1qFX_MR0H&s0Vrz7-v4){n^@5 zCNpjE=1YM#v9`ij`blcsL6G!#3(}<3`s=-N-3m$}hhC)9ug`2K_cNLp;KpCt+Yd;w zlWjVCcs!m{8_W?)6Ant6f{9jYm#7_u&9?X?IYIB>4_e|(Mnv2#UzNJP5+L!q5FXV% z%fi0k-*E6y6E)V+(TSBRO9pv^%XE!3_*SEP_$KGI`b`K2GjPTgw{fkLS?|0s)OYH? zEG%EVYE@oycB_f#bbHR}4Shd>irRp~<3r-e64+1sIiBd7tocA+FST-K!Imv5c229H z{6LH_*L`F^|LJc`khLhn5V>e&WgREQTAS~sqa(PR`rHPef-XFC$Vxjk()Yi_iFSbc zfHbz`K&dFc-lP=y=+Pq`lQVX?|3ku}v7Wl>J%72}M?^)HwKklGyQjh8+D|-5OTlaY zwBBhh^z`z0E6o;F)MR6AE!)L?lTpwgu6{3I+(4Zlu4x;t#c5K*Q!dYIm+B&Q7zR=} z(k|J-s1;@5z1Y4@1Au@$CRp*?p>8ivAL8r65H%L~)tPH-ZNSlpyx-|A2^yMZT<`RK z@w_%zr2gsmxjS(e^6?Id-ie``frjHSM(NhK8)GHF{98eyD`-Di*leAGnJ;rR#XoF* zuP``^yF&74h@LcCdDAr`Glu@w`3uqG)6)g`-h8VVmKlhBWt>8GqoGk7pk!y)tL&xy zkuQr|ZrwHi%v37sDSxhZDQrBcO0(dti<+bo$rjJ?>RDVV|7f11q@>Bm3uPLsi_&xq zoiR{84)lrDx~~pCj4d2kF@&GPyFNS*kENATqw!%kTNy|zIW4nPlTDJ6^FbBCbN;RY zAfhyLtxXAZB#Z@e+w;87p~>fW@+3^@byE(=Y1hX}hLP83vjP!H`$7o_UhO4Bq z0a%@bA^!1He0(KW*+AmTE}T7%=I@?$;`bG^ulXhv$5Rm+UT>B|tis)5WZvxN>wh#U zYl&n<=Lg!2-B_$}H)`GXH2YZE0x+^g{nd|O*vBTw?5b9Vrs99AH8GO2_d6c$yPNAe{6P72|a)6Dl@YgHnFe>JOFM&UEQ znp~J2&MVWeI5@9m7$>^{H~?O<;Ry<#wV|A>%XF}y#wMI+8xq!}#ypmKsObzDT@SO% z4xVnF91P!A6qh<*P9kJd(#W*h_#`d4iFo({%~QnEhtGnH<~FY5oWog@gwu< zAB_{NNVNuBzD{6}E!9>Od<=yy|E#v`Apb-C2hsF;M+sY-453@0=W$0gQQHWPy1F`} zmjh0E6-#0OuF?NP>ZZp%%&i-sy`+s=#ZspG&p}P9i(kLA^K$N1iJtIJU{dYJY>!WG2Tv60TIk5o1FN;Mx zka>RShbbw($D55!O`|yKIig)`RmjeCK1-!EZmvNoC3W>Y5qIVk^Cs+4jStdb!Iwez z<(;N$iriNEbrRdoSF^5GX~8<`eH2!Dw%s(!Ob}P0Zi57N5h-$*PK$$XzrjMw2c6 zR{r!!4kB$YkBJOFh$k~+eWvQGaoCXHy8FY3dIVQXXoWsT9ewwz2Fv?Vp(DK>V=kQmA zDzcNLxGzYW=H1RmQzo39fhxL3zse{D2Dkk6*^V9FL)HZYP%!{zq=~1AU9Vn7QOQot zMPz^DJpBE`h4ga|e4-2TUk&jv*b>RhcIh12kEuwm_~@o>tm*AvUn(|He{_QX%Nz_0 z$Vmd|Q(xhkDclnJ^V4*Kixy__ObkJtMqN>WmwNxdx}XF~pEgzYgm9Svk=NJ9{#q21 zPMy_F1MayrYQ$`@^{do`F7_X$RqgVHIm8@|I$g*&xapS6k-m|U(YLpF3s}jzE7iv5 zWh>>zW;31AUb+G)A8-#C1q70gh~6Xzy}qGM{!+>MkZ2z)J={bld)_qi) zB9l1P4-(g+lC7pg9)g?1e+qVmAtT;3ga4j)3#l2iL$39w5sSp|=xq*B*Zlz~KYt?6 z*YPyPTTdlejn0-Tjx&{maLD?mLX=ecbw-^3FcEeyIbPU$=~Pyp;Z@4sx+#u!5qW_Z zY<|S4Z?q?nY8r(Sfdv*l)Nf~GNZT(De$tSXMyfFXQRanYN+%Rt{-zzU-h(j1pcdtH zd{9N`3#iYsr`upU9|PqL`YCg&ucD%IV^}}fXS}$vW?KH-D$fEZdO&hbL!tv1QkhZ} zZET9G{dAsM{I0H5>lC-?kUbzN@+Eji_&l+*W?^`dqy``_)zucUVzOXLF8)rTQJ3fI z>_+umSjIV0*8{yemhy2s3!lhOGMVz3AdvSkaa;byUn9>~f}wAq0Q!KwYmt8R#O0}p z@l6#gdBv2}hu*tJ$AzVNe(gu@7JD1JkIQ=s1dge2V&g&L?>T&3+kE9@-F6W{K;?71 z&kjkjEI@Chta%>vVN_#P1oo3V3 z%$y*`xD_6kw6qewh54#W_D&y(qSs2MWa_aYkj~`|U1mL~VI=$NoVI@2?RcwCCh$6i zhd2cWM1k%>V1kY|5d&#F#)gI@_CJC#5Tof;Fwd=z7pJj|mdo~~vE$(q5C|RRb&R=% zr$^;Mfx=M}dO<&BdFvrb)j}??bWL^Ao4P;Xa%(LQ&TVdK>@zD_H*fTP6@XYeBXmov z%@Q(Z8+}j+1YG8wws+!ms2}(n%pmTR!&f=8m>Fd-Hl|BNr0qYxmke{LkIUg{!K}S zc@}-qQfFOWqiF!AuI1LV*ft=Evu~KeHZbQY8?fG7VIc$^!AWE$WKAraVSlt9Lm|*z zY@ispoZ`5_4j|&u3ey`f1cFZNvjU(W$LTkVsHZ)t0Xhh;%!GcFc68SX4XT?R0(pt4 zNQ6V&M;xh({=2m(R(Fvb(?WTqe!BbWe$WUWnB^Dba0%a|Qma}7>s^l6d7bw`6Fs!> zN{h1v5i-x*9S9`o;cqzOp;_tjgTw}~rW0m$uj~Z;&StkcCWxMT04l|Zd=SQc%~^IZ zbL+*FGRdXsJxi+GxgYf}fQ{c8{y0!VlcFgp=dsuk24EH4?mbw8ciAnK8${&}unxS* zU8x-DYL(%>s{@|J#l?O~>PIo)^nFOuo4nT^%PdUc@eL&0Ch4IcRS;}9SP%sT#T{O} zo5zmAuq9BTng$*tAR%DC6qHGiAinN^)ZKyvy_%PEb5~-^do5ElS)@!>hizY-2=#*c zhKr-_ThVMH3VA;vGtt%2F&(dtC6K6|wt&lIn$|{v=tFnh`<7G?Na^owe`ckuW>yg^ zkS?^eiPY^XyUFL<@^0OjKrrgdmc?CT+^v%DSe2F2cfMK=ba!?x`yI`FJ9ze%mW|fx zE(G$H4&Y@vNs*(ijOR4cA#yd{<%kr|B0gh<-Pf@DeCfeAGuVz+QXH-no=Ab=Mk8gZ z1z+j3$=52rKK{fA))(}*mza?etZ(!-^kqxUzP(w(Y{ELl;M1FF^M-#HagD1AoA5IV z_5x`<-$Fq^+NU7c0=^i-Eyz0@#UB@SDzW~DG~h1S4yO-Y$~I)d1( z{gekhuaA`i<1GkX)_VAC<%X(!_NvDi=a4zqLu{ns?Sc1 z9nHmVK~iHE*qJ4v&wM1_Gxjko63SG%wH8C|Cs>*jIw|J0ZiZF{j%rw8Px<|VBbH-c zG?qGJIAmD3uA10jGGgFyCx1Bv(oXl)a56q}IA+HuP|~9Ft}GT+T_T>}qn4HO;P1;f zsH)sin(c4px+gQ)V-mjb67qIXLHSVU!g`UwME#H<1$D@51xpk znP%LR+!i+k-x%M6d=k$!)2*4<1H}o6ZnRA0T4wZ3BcKWFn*~1w)7&rnQk+{Df#*#) z*W%+&pSZKVEiHXu^!aMtAQc}wocxytBnZpRoR=uOKxz#Q1sp6YbO8g)=<`e0Eyc%* z6ga=OZWrv3y}2=%U7od8H1X#obaTMrs;a%cJ$)`95(dPJF_8@%u;>CP+2K#}ZVU(~ zC}^jd(tpQq``-oLG?`8hYJx_i;WQQmc|AJ=UNCb^a}Nn@$`>AR(|}$l$}KgoIAyhK zkW-Q5t$~DIAnuNsuQ?Y!BxrtdYWC-dz$uH^>un94avUP&PNt$HklmU3C7*8oc>8tT z7yog`Iyzshk9)wM)v4ahKRrHPqezK_zI-5=4WK$%*?7_`_O647cBVC?D=!4Hj?sr3 zdEeOmk4mh%88Xnc$;0khak*ZVQpcB-j^~8c9|r;sOgo3^$W4cX<dPe_|pfbPFEc zs@VD3ROn#OqWJyV(*TvPFq|?9JR5I~BeVMfs_?+eo%*Q7ot>SW+OGgg79^coK3-kG_Cx^s}8GM5Qact`%8ni_FQy|4< z3zFY!QA02?Fi=xdhu%d1_-SaPox*N5v58ac>d=sf5(4?$4JS)VV>(VBXMHNIQ=&%m zEc2!oSVw7!eN6ICh@j}3Jx!0u#T4Xw2oGy{R|5ISH_gS6%Ee#%YJ$BhYjC>OcFn=% zMWes$WU9}{-g^*;5ksXA+*KBIF@o6B?t7--(Q0ivl#n|S@k4*VoA(q`MP@iSGd&i0 z=gKd`;>?+#&Q8I`X0;?QkiFCAgLGI(NQmSUQ4t|O`Na4ZFDMX1Io{n*-mBAN>v6It zcqC3oPbgDnJ&+33K0-^MVnarJ zek%Z?MX*VIRbJTDps4<&<3f0q>)_u*SH^X^P8IwWLT-yN*xdtk?5Sd9W$q6U}|QVL&@ezI<>Q%GLQSgOI}9+x`~BruWcz zn&YZdQrADLQ(iL~eRZggM!lKJqxAZ^Mx7p;i|NVB2Cq7{8F&V7-Naa!P*qSUHTqKi z;1Gc0fq+fJ#zRwmOLz-r%&fpw+(8z)$;9~ zm6Mu^(r_?H>|xG?TK4Le_Pu9PeP+hrCMI)ZkSP5bzLE>E)|*Vis_{)TFx5o5S` zaT1c0P*1V|ltZ8L?=?0zAMP#q6F#?)O(e-lPo3I$7o@l$q7hkkZr>3Mxwo-!vOqWw zP{}xpzc;|pn>%8D)&8zoFJC?f@B4Px-xIDp)>wY27i?@A48*_erN?|aVM-iAO@ zpfaw9{rr4B>x?b(TF*lmBh>eox&SY79%t57^4G6^&WAK@m?9>q40JLU=OTLHx%))M z=_LWkTlDrxJpcl?7nj=C5VK=AnVsY8tqpqFG3}!wC-hpwM9aMU9Ys`sEl~F?7Npop zpS2Feys&Ref1e8k2=9@x7xEhB@Va&m34v%hi-15aFfnP;pTB<1BjMKpZ~Wv9mpCi? zi%=HIEsbXo9l>eG-{QMT@Zl8i4^YtCz zjo#5c!NMhNabJsdIol6fgK9vvp?Y#PPn=aWhJy)J#$W^DZ`fM=;AakN2qap|pY$_O zT%G2bF7%Ju+F^1F%>AgtfIw9N>HJxeD4uF2^i;u&c*5pjnLvno?@KC5u5Om&=a1s@ zj>pH;%i(qx%H%T-{yx_87GPs50~xBcTr#KO!9<1rbY4-3%k{Vgg@--DmGcfnA=%h( z`Lb-nhMyrkG;CQmo-&aJ>{tkwvbL15SNA0Aj>yC>E?c9MQkjGy_mHyBBm?u1OIf?S zyHUbLQdfV!T@Ih2M5jJ4hpvr++?F~KH?STn4AqH^M_E`Z0HFIQuI|1P8dTtKy^rn` zv`G{0@hr?+JTDkVE9%*z_D;8^)cFKkTIP3<@q|68Dkb8+E~9r>F(8G#nDx}nT!4mU zXIBBhCJ6!jTxg|$jahg{q1_6+Vl_Lq66kLdnIVEUh@{i_3rM^*B;1^e} z(FqrC^GwZL(LEogesf>g;pcnrH=;nTu}wf|WQ!>nKja#u= zPI)O8m9UeJxHywU?X-zHAyfTKg4`!PJQc&?XHF{9u#F5uF0$+oFR%CJVim-}_HQ6x zB6aJWoIC*>%XD7O6=oJ824p;B;niQO6B{`wBd`fw6A60}9y^*I zv2o1mxs_*y>%b9wNB;(Cgq|NZ`7b?4Q0UK@Je;nPymKS~r%Ov&w2M{xT+b%LN1!r* z!R$#NbdqoUufYJg>cyT=7%JUV*sUcmIavp2<+>6Gf%w6SRtC$xHmY{em*VBka25{_ z_^B``u$t9+uEJWppJ6aW;NT2gYUb>n*{$IbG9)rurh^M;5o@ceGBTY&qo4$s^#+$k zVAiI{k4t=&8pM1AeaRbSQ(@1Ouu@%v5{chcK(v-rRdAor+5J%EHrpH|XeK@+Hdid!O~ zSI6I0If&2Q)s{!{z9&4FX=A8!O%mhXyFTdbK&@CGK}Jcm$MZeWF|v>ift(Ve!+Fqv1iz-<_6H=fAs0 zO=fFnRUr^krEP6yTqu4Vk89&w*BgS-D;gfqp$KBB6*KY^fT|u=Cq2jNU08ts>5c)C zR3I?%+x-UU4Bg+)RTf}=2+0q`FKhog$bHQ4YGlE;+9R&}lI8EVKr6>f1~JcUP_?T0 zR3(;XPx%MCIkWA}?QpB`PTPeEmTq2s0S$OeL{*jJ)?`(f6ri7tzr0Gh zg6iRIy}mYRRsqbT{5x{`t41Kv0t7R=GXp(*p98V_li0u4UdlxRVivA8$=@uy+H6=i@9(65k|QXBB%TAuM$h`97I{1?xZb?b{p4)XS0lX0JWHc^M;g zrVCxr=;E4$@Zr_?z<~1p+d3e}s>E%n#vFJuoN-5p1Y&OFJ@nv2eru*4k*}8xp#5P| zsl7JE5P^O3pkS^EO1q85^To~0U!|IiVq(pJ7g!NS8$Pr<=lFYWtQ4N9t+r|w{bntk zHc&%_!^_KyyVtZ0X)DXkwstQSR5HP%@IWkPtY?o{)N^%oA^|zZH%toU7hJY?nvF|- zEAFN>=1wO9$NQDMXGGmup^s2X9;X{Ptu$l`wC)}(yM z8tyfN050ypAt5tC@j#m4Z~-r}Dwjo8qTZ@-ork?SkIQ`8 zmGycX&@*qBw2Qyk>$wBDD51YoFuf`kggm46&~OQ1Uu$#BE~}a@BCsIx5E~)Iw;L zCu9md>T(21+7P<&GHsS&9Ax$tcID8(&sT?A!xcZphi)g7<{EPn9_yR9oy0=tpNR-_ zJbdDJQn|FVdm7MI;Aeh6^iF%o?{Eo({qqe(=^elu4j{T3ue^)}0-)t-yz1(ACRC->w!idQ|#-Hveqw(!yVDqbs2{mdM*;&jm<`D20OUO-f@Z5hieWI8$i89)wj*C1cY<* zLRJa3uJj767A~f+)pHML6Lo{ql3g#86{FY~?Ih}-LU(u;Z3K}ktRm+xqwr}&?@rrV zS|)w2%xJ+C?};zQfZUIoa!_(tdfkPCgkmYJ9^S)MWA`bvSyC_>=6XqJVTGa4+v+qf1zqPgTY*--eE*h_f-TX!B+bkxN z?y}nLi_(7?dR*691}hD99w_>_mil)5CJMBfc?LVi2N+G~IKF!I3h>LJD%+^)H~z5S zHM27cZ!+#dcyBxBxx44Ee)SXdm0AQ9R}&ONiIPi%Muz|3`zG$FkqbYz)|9*QxBFKs zuf-AxOZK`~`x8;C+IMQo4_ z_x6d6w$Te?O4PFsw!<@hT~B&FaIH%a4&9Tu! ziw{UlDCju?6&j@%O=-C+KMS)3^X8IQflRrd%I8ko zvX?R4ExvadzFiJSv(mgQa4rw{)3R~*@3JWZcUOmUIA-Z-x3xoyc5(yX@)1JblbswD z$w>YviHQG|yxMOZuW@AHo*?tbIS%`6wdO*4Qm!$^>N2AA%u8VXo6g{Sbyd|WeICCT z*`h^N0ye!Rm{OW`DFC7M@bQn-N+--1%^2PS1a?VL5u5We3#>I<=1t)@Fi2GHqwdP> zgI8S$I^mZ|nic}(*U8o!)&rP*5cw>tK0h0iX^9fV!R ztWzqclyC*c+-rLVuYiZxU_37ltWD(U z>GiMC_0We<;tvSI`{o5-d8H(Tod-u@mapgDFH<7AnSTLx)qQQq|CgGbegvV2wWcZe z^R7>LkRZkQgj6LQu>n`N=50JVww#ISr!QtD;fWE|&CcZQa?dSNeVx4d1q1^8{VgnY zuOrGBZ8i{M!%M7mD$t4tW z3z1;rc^0X%QCTzbM>tY&Ij(nCu9Ko&;a}Ut+uPfZBz3Ak1ns6*AOmOJQV#477R5HH z|7m+yeH?I&mDW0^Ng8!(ec7>sC=x02o-|`HZKspg`J(|NUOMJ=LXFO{l|wACf!RP}sZ{-a-GDIZCsD<*;KCG>E5K7-1`lS_9GEEnUXzU68cioi1f|MAKC}+$ZK*ky9R*nzLSUt`?JrKTNw6u-=vrUiPvy{$P1MhM z>u!pv_@K>ntz?MYj_sz=)bx5}%NsMzrirZGebHxC$ELs@2Nu+5w|a!E8zhQ8v~k^r zyzJj$!()|*I~kaN^#aK3LEj#hisg6)4r9x2%t%|lmJcx-olofJO8kY+&235vSoRBgaE11-`*3)=yaX6H_ zj)1rY;e?Scqqul>9)8QBeI463N86Hj9_~NMi6H`X5?nj6?i5Oc$8&~>q-8sQ~j_irkBCU9ep9L<@)Q7VH|5Y@RxZt zVCH^M<#>Iz0_WzyI=d z56*524B_8~iLTbDu(N@kIvZ1S3m^vfI;9VgXK!RN!XxLNT}XFv%fj5wvLE^*!-J;yHqfX)Ayn9j$yubo2Bq z@;cAb-SoIOsS%0)dkr&CGlr|d^>_O%L8^N>FfZJ7aFa~onlF=t#9Vjx>aOXRN$yFk zfqk+$)TqQKIm{2!KQ|C<`Fm>$usZ7Snf83J-EguZ0TM)Q0`~ANx92AZghLEB|T*{SlWst8mi9d};ApI1p5q>Gq2Th&H3p zW!jE{;U*XmkMPl*lGrb-$D_q!8kD45Mn_=F=c~G+$IdS)zU5+ZDuLrh0p+ow#v^Kk z%(5~}Muu|#CH&Id-U&8@u5%borhJ!e607?u1+NfWc>sCO7){!wF{-)AwbQXm&1KeN zfU1jDuO8aFuKN2W9xTBZz9027g&bcwJ39l(Hy{Aji5~#lTIGpr=3!-`dNqnwEcUlM zhANHKiLn?H^SwT6 z*M-M*;%H2wlL`nP?VyY-U+_=p!Bjd#=%t^B=!<-MEHOotk&yv}uA6byQ7wcoL|W$) zx$4GRz(N&3i$Do@$9u>w7@dE)h|sSFn}?grzVPs>1Nk0MD2VFVx+n14KJj>|F$wXK zhZryel!#_iY~MZhmws)TL3O@d?cQ47={c&qvR<^G2zT6FVgxXGVC%~IC41@yPay2K z=-4c*O;r;)0ra=)&7wyVSjNI9 zNtZd!UtX<-TW>Z>{{8#+<*(0W6&3bYR?Eg%ovl&U7ty;>NaHnm3Q<()9f8U+UEtp< zNa~ex`<({-rZ`H`_dWyXwSRbcSr__EE(&RgcBae;D7bogW?*MP?U) z=0Ev{AB&w$fyuH!d9rQeG1*m>vE<3wfBN(j?BxdgwnW1h$n3HM4!iMqX~-cDKZNFg z_I;fDT`+y_>qmoX3vft)CQ_tGfJw0EWaY2$g}|s)wSfd#&fz%-ww%*2!0Z%@qYmS3 zqO&=HqOjC4xCF@;kdBt6KlY--f|Pc4by;_lg|RlWc100$e)8DRipjiof(Df68o;AETSJ*Hw^ozLl_mg;@m8Lxbb+0bu>fFU zC`ubC+6wJD7jN$d^t;>bZa}eLVf>Nz`ciG-Ef&zR5-ABEXK6D`rEkkA?p#CV;BuM# zsg-L>2LSmbVbih#oArQgv~&O^_eBMwjqsG6bQiHW^HH--bnkeobOMNKD=RC9`g_8u zck~Ov#zxXJWg^IuwBk5WSSYb7RR~CteyOV~mKj^WkK8>j@px2iTC2Aj8n)FKp}}I` z6H9Z{F+ZORAb&I(Xh@0vwcq^EHTe@Dy(PRqObh?s-kxn|^V3{Myds%x_Cn-x-foxv zS!=6a|7*LNut*ohKM9=cSm`;cw?28`XrXm2wOPINU;ArmFgu{1KZ0-Kf-L3CetVbd zz;AVn@=Lxm*q@4VS{4-+uX)2W`-JN?qMGh}d+(#Op@Q%d@O3Ns-X@>n4nn}-uDWV}F9+<@-2?j04BiJ7emfz!q?|vJ z!XW8P;{#_+Lzge~LG+p`ZTwVLKhSsSTcaWU?}&yjBH%V(uCnzn0pZ8vSLq1}BbA1= zNU`c*gSeiVw9oapcz6>@36OM(|AoD`4$Ct5+C?dml5QkKkWNWS>F!SH2I=nZkZzEa z5)hCs=@O*7Te@?P@cYi$`}+32u6_PL??2`{JkQLUHEY(o?|XrpT|9I2Mv1mOx;(X! zv9Y-Wtc04xoJcjx^yplKZ)O@C;MbCgMiBGqThzsn=ju9$`sRc z>U?g6Z$Jpq;qVDUNx*Cj&^(1t+*KurB}gU6BZv8mCEz8^8aH2CyW#z|S6l{h6G(&u zFgVk0#SK}3F-z8#aDCJ1iGlRo*ya5F!g!a6QQ1FiJPKH33P5~2w^iRmx_;-sV2*S5 zw{D4rr*l{`no^I->dP35+PeYpkOUb40RdoKcURXMn(gGTj?6oeY4&0>=+wc^d#XEvwf-ZtoV!TLR0%1;t zxAle#NL@e?LwUphT!_lcE9dK6Q}zfe0II9ItS#i4f+RN#FAH;3z#(<>9TlQjuvoq} zS$R-*-`G)WKma7PC(n>777OIS?IN=YqZkE|90BCmU2o0+>DUM`Z88I*9xAZEE3-~& z$~6pd=R zrTpjzMc%x;JyAAr*_;5=B9_Eyzj>!i$EFrLmgoAyLIO{E1oehGQ}_MFu3$vf6~uNu zT4;21YY9I%9K5bpUb^Mv!QUlNysgzO+$X9Ltd_=uYnaHX@H9)>-)YO=|Lf<^`ap#T zVIMe_6YrTr(OTK(CfP9U38-GFGFRjx2cLF06;97s+_Sd|pu71jUM+k&C2-Ys&pUoq z+uGXNoN?Z1E2Wp{TyqP^9LFI@5Hb&I!;cS_tyqse2Qr;KGhCRp^^SXq1r#~F6_e40 zgGAf)J3cohh+j~uiId&RCN^Id0C0&zxtSp87uG*HM&txu#3m55>3}F$_svpJ{A2NG zalz29Pz+WcXmSJD>!S#&RFskLFi#pR{n4s6io4QNc0NV|0s^1_ReMP*^}*iRvhqYG zA7D(%P~JkuAjCt(!(Db)jfT#-VS|+9H*Aa9J!YPEbf16fCX(=y8yHA@x(@WLf@@ht zfHo)pEo7pEZ(4DCM;8;YyOMcnVfd+$2tPOkc?9c9AV|CdtXS!hn7GUt>rr)yKBG)r z#aQ+y`4y@+Oss2vt}T5tB6;;RSRM}=4{zA@*SHl6DCKl?>Jsn|e_P2vImLYR*6&ky9>Fn5$EmeLgM)W~TNuPb^HgM?gSu z>1&ylB-t76HIu^w0#8I==_{+pt_?KWD_LY(flyRb)a)+TAj{@&3vL{Vuut=}i%OJm z6nl3uN5LTxzUh5;ENUcL!f~y*4PS=%PjSH#8j?}C)_UPXC9C@hzybBO?}97l_$t|! z|5wU$b7`LIBgfor>{Q@YfnHB>Upj^_8I*S7wV|PT(~P>lzCH+Qg1kF21t?@4O|Q|w zQ=L+PtoMc}x#GHPW-x0_nNITuaz9|*4qx-Wj;HP67oofzLfWqX;nO-!#zs}vm;Oh? z=EC!2UHm3f_Eo^8^gVD zik2;rk5Mdo{5@Uka=eOpr;#3&$C`0XRY-@0=> zP)X|HW>|EUyh);yr(IKD(^_nVd zY#++UTI75I$wjWn!j?#aMuJ{~Y2QAN>iNNX{y|gF91AV3Jq9~F{aY?-l`WY~zEe0_ zbl=H3fD@k4!fThmUFwar?~rk0)`$Eqamt+CUhkzGOpFDA>X%QJ@HeK<@SaU)%t(3` zRK@%t&4BiWG zgaN^mUM#J!2asGTb((%gDns&J5*fWrn$5muh6icF%_v_FM zKTUT(3Paz0TXumD{rXJHyiK=(aVe4x;l7J+>jyzd4dCG2oPZ$FjVs0RbyI=!KUak0 zGj%3&r=W^Ch&cwLBd}ZJh2kaR^XaG9mUcfoJz98nqDi z+lXXxq0t!;+wfaWBfDnR^0jV$b)5dc72^50BJoi&r?G@R?Xyt3$KfIm-LSu&YA(dn z?u>$it`srnLbd3Rr&@;+ZG>7m*%4booU_Aqg(C9>>q3Ugfm4YP=LugaUg~3 zM2_&ZtUFPRsC$F=Ng6D&GBV}r)$d$$goXE5uH(*aMrg4X#2|#W%BIi}R1s!3u}Z0Y z_-?k}A{YbH#kxZ8EEj@&T2%SZoUU0gc|#r5vt_uSZ_ak0?7Hg=HEZ)nDBFc$L#)Xl z^iS@v5y#b|)-a7x>Ih<>pT-a}JdI{s`~=hd0XMo4&rjfcn@}N|^A7 zN~<{;BN>MMZ>%>|8nva6fg7l35XrITE6fvIs z$JhdFg43x3q<;vPgtDL7zH%lPf{b;0nldF1FCg^e68iq`OGDy;bh%e81Cv2F(q9=7 zcyJG}%4f)r_-U-c{5+Zr5E8`)*ci>Gnpw~>g0o(wOrzo6dO zIJN|G#304>`g$l{m`g~6v6&#~-_pvZ%2kC}7m!0g87^<~9)7QEvDmmd`5efIV7l}~ zN6w7>2H172kfd!VsBHQ-nY3^woDaXJRp4Y0l<0VVST>|cdnhevak8z<}@$VU+F#_p{@`+I@$# z;FiEr*pnJQJ7f<~CB~314(=8L#aI0#=4q^0P$3+1AigrDZMeAW;dH^JvsxsA7h5jG z%m$%d8*=LnxY+|KLr)C6q)H?S6);LJ{H`>#efj2&5>rvJMt$1q{+dz3SEO2|IpmLV3!@yy)8r$y`C7=% zC~lh_+RWlq@-9#RzxcdM8%re$G0{GH>U9Sj8X zKoTnbR#%E{D`72D=TGoZn_o6+s%m23ms>Ifx_?}NX>i?oG&|l-_G_BbxL8l=Ad<~| z1^u)|gUCqP+-c7MpFx8K1p$FtsVF8p43H7cjNR~oVo^a#xcO(BA9%X2Al4iyFP$B+ z#Tr`+v&~0y15u4Zimko9T_ZitFWvj(wJ*g;5Y&^|K-+J3zemppCBQ{@qC(+Qa3Q7S z#nNhaW7W)bHn`o#6NjJOcY&iNL?G}Iy6;BT(pUvL8JGqU0y5!>i;*F>rv2gw=a1Ih z7z;Wv#7`!ThnphBX5QoIrM(@0CMBI#SWqxorm6Z{u!-ovF-ITC=E9$Z}1f%^_ZD>J5*B&amqE!VT*J(m+pvFADE2Dt6C5raK}#`LBN z;ZvYtLgOUca(|(DE#A4v!?)jQq_4@IO@v9^*rIrMp9?Z3VWS&sYhSz6anhS)SEN76 z%()&$wls}CPjrHXAjA$RYG20FWGGo5kI-dg}NuY0r z=1>J(A3Xd?&oGLNU9}{mFb^vhIWDDthreHd^f_I7N6^~p+8W3V(845q`J(9H@T0&a zQdYb$rl9R%@3$2X?klC|z@!p2-W&kT=~4khMX|Ev1b`8Zyq8;P+z}`yHy|XIr)IJr z@0?F<T5mqZ209ka}r!2~^ zsrmP~)qIUVMAU>o8ixD2l9bNdnbAFhf&@Dz#hugcxOlj&Vh?oYzd#V=3T%7uLZF`P zvD;{8hr~-a*@Q_v6*LuwudJ@dV5tV6YCOC{BBQJf3Y_WH`3yl)O{6^JK$sV>fju+V zcLbPhfaHJy73xRLqO^9sgV~1JjX5aEQA8aZe4u@&D<|Xbep@KJWObaF&~?wQpyMZL-(D!phA$SotVoMX zNk++7RaHXvLJElP1fZJ#&W3!EP(Y!xf+YYcrFX}ovDU-EFZ67bF90?yTz?|n?xcGS zS97eaXK^=fo{(i5ofkY-+gu`Bkgc#&67=X755C=d`FznbK zu;ip=r9NsZwv11pdDA)?8UANrG1!dDn=gJfnhtFA>TAAVfnt_Y{BKbBZh54ApE1WS z$J*-BmeLQ9tUf+IKI9t~Te~qF? z3P#%u;dzJVhr$l)Xdy7OkFrV7pb7wGK9$$8o&ZhMS7N2%xf_3 zdtIHgo!u@-W6H_JoUE-deDP!X{OiIZ&kUfSEE?#I)YQ~KwfcoHz^Cur?zC}_-_OkP zxeJ{^vormLeb?(bwLd!S{&Ic$TH%wN3tWzXo?!de(fT#TvAIY4C@9BYPWzt?K>|8b za;jXr&T0b_0nj?NrBGIwA6)1v871UOmnN zzJKs+A8izfb~&Sj8?!L79z666(O+Btupibn#$nJY#ianL=<)4&%*59IU_^y%g`Z(2 zEWfcpP7W0dOPPNHS^p>r-tJzWg)hfoB!L2-RZ3RYX1pjiy95YHc>-@Y?9crEXXn>y zoW<69L6)z+JN(ugbt@#ITeA@-pd^ZkD-a{sCO2*BaI>IF)S5;g?D$R^@!#}!h4~f)XU0+ihmB`y`dkvpsnYi*-}u#L;^fw#n%*{cgDyg%lRSu9`_~RP-iaizXr;Z0i~t1V~c=1 zwE189C#q@2d>~+$P`0@^OT7@Pbtuyoax@*Y!Wm4;12WnK%&MDa^hjOOq+x zndfCkW0q#7yQkDn_CYAbnTI)$w^c89_iqvAapA=WRZB$H;EV z+AXT*-t6Cdt9PKlh5-ONP}#l$%1*jXZ#g;D|5@(NdyoYmYkp@h!{_?7eUlkzZ#jPc zjCxk9QDY7d4}VQWXzPDli2dh?+_AnF0xbeIXyux2liBWdeRO&<%DNi@#2Z{n#>K-g z`LLKSm|mCxiqZ3Eou=6g*<0QD{PbYm3)Wq(2F}FANA@dkpo(>;Hh4o*Y5OYyC#g&9 zvy+pGlf$5a^^nO4D>cpMk3L z=V-5TQ{P;qU|0m22kPnaL>2kv-kq;TwBafW2AH-4o^%C*Fu00lJ6a2vpiuNo&hpx^)gTfb#0{3qtbD#eoUHFOlZ2ZWKWt*skgK@bSm6r|o=m{z$2zmTcPf!p8e?{K5)P3#?5tydGps33SO z#iCIWbM^+jF~u&7?>1PKGVTgz4JHAa6C844=g1rU@+?d8cfuiRx*N`zAQhdc0#w!# zx?3k=1NNpDkEZd}n_Z{H=${83@YA;44wm(}u#l*&oI)s8`UY5i;;n(muUJ><+jiPJ zm`$X!E^X21@$V*6rCNybTn)^oo$nr%-w)fU`zy=K=5zMuEk7n^l z4`SceSAEy%SIAX}*20M@zuG@BsK1QJz@g#gUF_}_nF`j{(n88WEVDn2TjmmLEWx^A z-Rh0Qh$Fs9xR8X`mF+aq3_UqH0kKgLO+#539UJu9rB`W_?|D<}br->i(&bJ$Uv|D{ z(ID>SbF?neot%vhLUN3;&tIL&C(&uXyC<>(3=|QbGLFZGobI+*0bUfSen>Nv*EwZS z{qmOMMy5JCI%8qCS68^#*3(7b&Geu7fzW{r6Vw&M4LocoO=`_JR|^(r4xm(bgvI^ zrvB-%M0&PbYz5f3nVE1PslO?5B{aPkjEglVdu{f3LA8=v*`o(4m7_r2R69rh3@E$4 z&1&3K3v;n)U)~+86EXIC`VpYJhnGAz&-tf$<+oW?V7u;EkAk9g2@|}YeCBt9+zZX$ z#KCav43o5$%m`z*o#C^VZ~uzO4n_J!;W7zmYyj2>?)5zMR(Y7_c=rnK&(pxd znm@U8($OE!HY5%{pP9JTd0WX%oS9-}F{IDXy3|b|Azax=k!)=jxr><%zH6V8Pg{Sl z`7ObakB`sHGcs!nFAbHA%u;5$$Q=JeU&Ql}G|I&kS7z4mQ+wf^JM0H|r|}@4%X=|x zFvdVJlEtUn?3{3rYDM^VU3pF4@EcTIX#C`vBy4;Y&`N7q<$btX1Bd(j%}_H=XP$l& zm&|SA{BOfU^nInzM&fW8CZT)Hrqo2b6J%>r0%)!yW7>H@`4t?|r!1;FIeqyu^JwMJ ztJa5O7aK2Uh;al|R4z%l!v3k4m(e0v4Pw}zg#9Xs)X^r?D1-0rn|~VD2+{#)6z=}M z)Bk$21(Mr&k!~Pk$m+UQQaM|n{7XH=Rp@88-JhEGHsSVBZz?A)k9&wEEk1w@w?Sqg z_JYWYi-_qupx zPmO?VcdiidGl>ht4I;BYQ)ZRNQ(9aUzpi-EZ-s*+g6% z9)Y6lYej`k!brzvrHd{U8Uz0dS zV2S3wx_Z+Lw0o7)mL_dn^O8whmieM7kL1RrrR}Y+lUXeTsC%gu%uJ|28_jG+Bl%y} z!V`RUqsl-*bO9ApbW&qjDuG;c698x#o6U)5w^6y5J}FqD57mTYOVEJjHx7I<=kT+Q zimfiL7l)i_${QV^P6Se(4MY#UZ=;oN!HFBv3+RRT-4cH@3!2~IM=SFL{^6VWYcxt3 z`9lFH+VEc^@sVE%$ZVYq{3(FRWZOirRUm!dVVa>5f6oj`)8|3^ z3~g2K?VMob*Bo*^ki`;(L#52l=&|J6Y=Z|KlJb!eVr0W%X zpq5idK~6s5DP?5Tk;c1+0l`;hov2#fAiLN@IY2S(-$3zD8b8!{^;t$gG?lfrAiN*Y6#6>zZ-pK}Kg zM?3qyziNNWkXCxV53+D0dYtbAF?a=>;_6X;!7*^jV^Bj)zG%%YF?O_`n8K=|gz0}% zHVjyOulP0$`(N1}5ndV?%A1{AZ}W$BK5dwU->=%OPf=d8yL?blSD(?eX(qQi0o7lR zp{*|FAdUQ#P}^IWzonQBuC&o!^je|i2Ub42IDQ|+;E+~!1cax#-kGc9@CwpVQMn$} zZ{<1S0S&qp`|_xa5$xz|{i7~eIq%BYl;=I~_UUq~*@yBtVq5Sy$Qm&XxI^Fw%}TPE zjl!ttRjGbbr7u##ME#!kk!5e7vtod0rW3j+Sug0TR*Ycp(tHaMQ2C?TaN3FFltr?&5 zHUS9PgY@87ZL904@t3aRd}=J_T$W&UZx8XSyGp)D|J48@$O^byV}w|O0K`^=sbTm_ zuZl%pX6$ao@^16YD4cf5l^2eGjJAnfEMR;XQKhuAMzr$V+W5_|W_YLg0CoF@ax=v&4%CZ<=uLe-|2DjM9lP@Hgffo3Vx7Z@JPZ}{6`GH`3C4WeCMM2z zl?4lJB^wrvd^f2_lT-q= zn(vpPGXetxK~tWwm29BL3+VSu2`?w4WMrZin?V z41&_PFih^?)tZtCX80e?SmY;5 z&wF{R!WUE!P9fZSVr4p6_A)&-AtvTGkP+JXGzwIo-I}E1@&$K6^!9d$Vl13YRg3vl zr5*I({-v04FH>+zsvGzGIz*Jf*Y|7%|K7^FSv`V2#Pv-2$lMbB9dHDTN& z0IfE+!No!VLtAm7}+okC?&`3~G zNu(X6#vIFcE=E((upPna6NUf9K(3>M)lprx?fYcOq|hhfl6;H!Z;8y)w}~B3bt)I3 zaOky6=W5Fwu0Gq@xh>-qDxslI0Oq>c1;8FArKgwH;f_VEhb!}QB80iV|LDf}ca$e2E5X1TitF>bc4>%gdk0BvRS)n0R=!Z7LO$ z>~0x2ztvlu-a%8spj^d4KCchcYPI#_`M}z0r2o`w$% ziaf9Kx4o0YYn#%EgH-877ix+_@Y5tDB>^S8l)dF_Z;Ijld&O>_p&)ILo=*QP_2VYl$K{jJAk{LjB5D*c+up7H( zaJ!<5|CS7|s{?0;*xNYunU7An)K4Bom=!z8)qR`&&Fb(h7oU)r^Q6+zn4bwv7Rh$s1Njsk`CU=%nzIcjA){&<5 zLoolUZEPNyiLMBYj$e^0sfw7o|us`nT%Flt8QZVo^9xW6f z(+hqAyOg}3SnQvYQV-?%*qoBv4%{zLRJIG&y8Nzy)#}o-OU!8p^B5N3awvdAJBhBI0d+0E~5R)-h9AbM-NbJu(q0__5L0HrFdF#u!@0C*~nYrVl2 z%N1yR(UiYc;RgM?venKPjxjF-TfwBMUOI>Gg zx4~rrD={8`CM9eZg+Dtu%>OX^qEWVd8imTOk^>MMZY4n=NXNlW(m%g-B}S|E{qZm8 z4lMLj^fdSvDu?ezOK8`go+bE7K2k(+;re*NNk?uty*M z?i=5;3!nnG04`ZwSF;4CNm_0lwW_*5OCl^TMU{(`lc2pC`;y0dHa3-mnDaMeFa^%g zUr$C}MOKok5iWddZlZ>v8MtQYHGFoHe`siE!lg#;8IP2D>SuGl4KyuS1$kP|Njz2& z;sT%m=xz`e7WU0+;U)kA71pm9_f3b$k@n^R_EeYAqE{)tN{oqGZ0Pe#GWRzrFWWPU zJG-G1SuNcjj6&M5dNpM%;!XkX3xIf%zk8R;E7nA{h!43P7(jydFRG5lYTx~oFGWli z+vZiyQi{_jlTXj(#p}Mi`De8hbG7r>Q#aUTvC?X7GJ8dEO#YwD8NkqogoYMRHA^;e zEb2epU4t$*_oq{(14OoNv9RSdNudW8TKwU$_yp=$8 z24>>AQ%S#E`smAW%tK2`-dWG4n(L)4*1y*ZYod=VNmbR=r$B#g@9;1yF;RuWfJq02 zArL2>!f)J4!V6CN-zfFjueftqx`-RV}j_mz6t1?Sz1{E{c&`3^rogJ zAkBufWF2%)`re`NyP>L7fhvFAT+?mgd$aD<;xvsW-d6R;*b5mR{8_fq$Y_8X_552i z1&G*<;0Cz8ZE8899M!7^5w54l{X+H^2;?rE?XA+5>5fF`9x5UJD~j%MefuxXGJts7 z1aMwh-YO*%0Bs41Nvz+w_k=e~mGXHVcQ*aX^kj#S9a5V$KOmbUW6J`~V$JZ!le_hT z=AhZevr4nk<2SdWzaYmK7hAxD0-+{`rlSrT^eZgyUwkt&Gog~JR4%0d37?Ov+-w5s zME*^}k%uv}=KdBlH9fucc+o$RQ3r24cI$b-SUSh1p{8y)4F)yi?>c#Kmk5$~m#`>V z&EGn=8D_nXzAmB`yZ?CHlDV@;3oX%X{`<%7mv<^k*69_^dqe9vZS-%;!dBPgh-U=t8D z-tA2Yc1v0F961KJ%2*ypd)K8LNjFBbsj?;Gd;Lhm4k=s{K2mV`*hH)I+NK>bL`&!I_}JOZ8BI{5;jhAxwF_3Tz$W_k3RD{kL9gc z@ILeUH%EGqv_XN|3k|EGE+2robTK8xhl2-=xO-3!J10d{R8vb%OvFY*tF&3-MJfh0 zmJJ2?|Mw;BdL)%hrbjjcn->60DU`2dVi!~tPVQ((NiEvE=qs|bNq|TTD93?5gdmm2 z$-$x3>b1~zQi_8XYxIdPX<>JwBqKc?7+)pBYcw=H7rn{wkY46zA0}jo_q^LltB{@? z2pXC??2{i438964iu;6w5`CXe8&c8%uoJWX>TWVtv1E z`*KSLc)rKT|8heE-{n_La{u(^Yte)`CSq37`opry%U>ht^GP^N1PX&enALBL#Ao;^ zdcv}wzBEzaX+Vtr^!HtsVoU@=H9e2fdC9M+j0MAHV)WTU%%dNP#sBN8U6!a5I`Z

    0z)$rI2UR1mQo*nU>^6NZg3d%`}4v3DJW*K+ggvuf=_ z_(g1wd4hf$Ykz87aP-Hy=Xv4aQHesk6o0f9pM?V`r#f}Jr*yD<3j}Nq#3$b3-Kux9 zE%Ggm3|7AbyBA{l4}2pN@58jtHXt}Oh!8*f^^$rPN%uF}MIjb#7 zHl%k}{P{WMBrkvMO0ZJF&{DEiFvn`wgcIluQBw9f0TpwKq{pg^?gW`qhE8nkn@df^ zbtBz>(0^c3gX`T~xxi?pzs9bHBBg51MGB-n!f`m@K)x!=7%An0rZth~Ysd)4k0&E{ zwAZUi(-j0y6R3zTne{R;X+tKls0*{9TS3c_>lnjr)NuQ+r3@Ic?Pk+!jeSY8w}RXY zpLsTR8F94pd$LBqa=S$E6XZ6QoWJB|O=3`v(0{;L9Yp6#YHZ|iw5aiP!C2Ynkf?a_ zPbxFR6N56+(hK7>xQnv1?cA9Y5{#rYtK%@Sd}Fd;&-Ylug0i3;0@CzoL`@(BurT$` zeirkp)n<~7_N^>%(UE~qSvHtwiJpB%_l%Y$6vv^z_Etta-Mi-bxF4I~!JJVRi<+)P z4S!e3$Xett9!yg@o4fV=B(|&gyu0uo3+uw~+(I}y=^{ROE7sGm@1g(IC^g{f>4y(A zoV9Ado|3n=R6v8&RZ$Q3L=Kx-`7K`TYu$B`EXNO&(9-m?%^I76=Fvv3)3W#PPmm%c zd0)QcB(&!&@dB#j@T3`#B--5SD7?&iJAc+#wqYbUanU^|Z{FqT3zkR7@s@tm!PG5Y zj2J@xg3t-&<^7%@I2SA4y^CHUD&|=WbEl!K6#kjCA3M@acnClbg5OK|ijP76Rqt)= zKO>HLoRHqZ&S_j88odi{f8e36jYEcNPNe(BMm>NHA?L4``x|E8f)G)IR!`%(kAD=X zYM*(rpG+D3(U4o%B!%*s;a>hyVqf|gULo_iGqf}?Il()fTewaLyQ+T2I> zeqTKNn7ozfntr#g`_QW?G=q1Q|MS zK*Gr4za%Am6U)2=;s}X`GpliTY{ZU*_*mh`SP&y%y;q8PUY6js|VVgCu@t@!|m6Yu#@L0P0{k&Qh z(w8o+%({|I{$w@KQ zC354W5{faT&QW)2mDm^6Ega(j{$8q8EG7{q<>ZJXX>(_zx>dI z3qFGnU8qwTZ^e@#HO`4abxIT3oyY6Io*mmp8StCoTjARGnwSt=et7Mb^m}!$#$`;b z#&GS1bSu9W&3jTT2;oKFYCcCt?%pMY`XD3Vc?0KgfS|X^UAE;UUmQm3Fsk>2oKeGH z!8)UIrQ&8KqjIj8Lw|rXiftsG;bqy4tv656Td;{jbB|vk@dN69Jnj zx{wI=B66ATYY;T|*k$K;>1D6uE_v>Q(GE%`n{))~srUIxvF@q-LW!4rws*bi?4zMR z{H#hlEsO`&+6FfO8F9H;^~~b=Vw~$=hqb^@&z%HX)q7$4N6t!a&EFa@lq}L{*CcNUx%c#sbcovFeu+xq5 z@3f`vvcfua%80Qy!QL``Cc%l2VT9`+YZyyxI_;4qPJgBDWrVFhus@%#M!7|E(mRJ^Z!^J+aLds;~)TAjupQp?j zpqYx&dc^qt8*E8FKJ*%h2!2TWTMO?YB=9+`;sh7aVi8DfBl{RW<_mtX+ zgSdoto%QVZVaSF7<$JkxQCZmCipkoAFsz?&<9~@!s((KrHGRbWS$u-gJhKxbEq~kb z(M}?tC^ENVQJD!ur|{c}|3+`q+rKbrM=U?LvaTc|5W_6nN!eRcC7^~Z{&JNBXIK+t z#8Mf;{flo(XHX>mh8e~-+JIWzb*toM(GF!u8OQ6R#IeUt_S_>bqhD#H-hl1bO&n~jC5n12bh zA2zjH>Kj#>nUU)UEL-P&U26o^!Bm=Nt*wZwDA!x33_Dao=Q7_r5scq|OfR>3-%Ccb&G_E{Cq~yG)#Nfd=Ri zpHLB%o!?nu3pf~~36~OX3GTP0(Xz<@o~DtGm2fUm&TADo6*3`RXSQ5Gr}*7_n7BmS ziAImt_48h8;yj)T1N|^40xpS|+YhOeW+NV~NSoe?2Y#WB$EFL)5f}Jj_;AwI z!1~0lRKQ(Nqo+$K)*%n%z-pC|UGbN{UzYGryAh6YM{*T@l5X`VdSUDGK|C)n))bfZ zW1(OgV_}gN7-4ui2o~{rS%0y^`bCNvXyIz~5juggXi6Fmu- z6sh7Y8yiADMUO&VgEGVL*Y=wbkrA|JQ2YP^HLXWASLiub>K>CSL(O3LK~LO47y@T` zX9lX|%e+Cr17_ozlXx_=AINoPS};;ZFa zMR2(x^2QpYA*VdL$JjqzooF0%AQFADBB=$cHj*IV@TF!M#tLgltd}6AUEEvK#9;C% z+I4M5SltE4h2RhU)Wj9w9N)zRS9~7XGqli-OuD#8qyEi{kKoZs8?R)YbNRAdnP! zMf`L|kwXh%s4~d~+Y$@=Zozv|wK*aT=1z)}l1R;%>>n(H7ZF3=XQD4*g|Q{=CpFVv zQ3(AOD8qTXnHFZM2ZWIufv>6ed@h8Q9GWleLBBY$7$UWe7pTTsVY%w)db zl~5SKqA~A^#2f0XtuI2!ZM;CD+BzZ6-F?*31k5YB-=51bxLsas_?2)K5WJ}}YNnU|u1|eZ$7^Ovk*l@(_dHGK^GrN(&Y!T|aCwxu z*gkZ%H+vaYLN;Ml0#8Ct5>ro7N92qsZM=0^6ykUpT)9o>?(00<_7Iaa3$$FZm>xJT zF@Sv4uaH&>C$PgNxvHGFEk!pv6%L^|x7z$^H@_g(=zop1dY_1oT6F%DI9PZ*Y4`yJcY_=}KMksZW zLiE5#3>c}K*yGF5G(E=zqF&L!YBExUY5p+wTc0>K?^cd}4^or}aE$RgG& z(32@BvDwLhzJ`P^qUMf z&6qci7cDdON|I!aoQEJhDH(?#cL~R`sE%Iv9$%1 zni)3RJn)K|ucvIibx_{yP2};&1woz2HdXoFsDA_=^ayWk9dV8y(_G=!5b|E&U0KK+ zAzVTp2v9W4NyiQu`pfPbfwsp)q;3#8p(E{_4Cw4fPs3Z~kTH zTOVZCLH*PCeK_9P(m+@KiX&|g?^UH%_3_aE1MVo5s+aH30zJ1sGXlgLm(T$N4U=r4 z9=G8Q0v{U!F*K85p((d4(E_C~Dm5T5Aa7!73Oqa@FGF%=VRUJ4ZbV^pWgsX-Ix;Xa zFfcSRGchWg6 zNkkx9JY;1sW@9vCI50D2Fgau~IWsjdGht?9IAdgEF*rG6F+MzDGc+ zKixG`-Sc$tFj7r85*nqlgcKty6DI;?&r`uC0xM@c8UY6@FExqNEGq%h5im7jGdJSpU^i#sF=1!nVlgr2;N&qg;xIEaHRUpAXBQGMW?^ArH!Ok6%GT zLI^Id&Spk-2p(A`hK7dbhK5eYhDL_UCg!N7{tzsg&=ljn_3<}!2JSE5Fv}kVttsur z?$tua8A3KQf-B{)j!t=O#4yE()gl=v;V*sWNr9H0QWM3iu_Ycjx4#(PEOM618{PLV z1_;)EIuM;esDptK1(A>-nAw~DpM(Ef{g274ys3`6;8@@+sUMIKOqd)z|0hCbE)Kt( zP5wi|&Xp<*1woJ~3q_V1=MMo3u(7al|6c$$f6BXTaG`gfXNMR9 zV|CEgm2>_43u_H!mF6guexRk{_u;nRM@lKj?&dmfC6X5agTG1AeVM=ZOR7QB;(qk1 zXL{!I1#$t8J(!)c;jSX;hhpJQy3y}iF|*^;wYT@Bmk!`+yK*`3_C58{cpD}Eqq)ip zC&OWVDdX&YeyJk%xW-5&kyQ$zh=+*|YEI1*Bn!1~G)1D3a%={<&^BhEY34#??wpRN ziaYLD5C|VKO@USbw{V%VoEmJCQ$=me?5LOh)m+cuE{+)acJ*bK`hY9nC|GSVMMF-g z)X&Hok`81I>bbtvcOZ^{lh3ml_&XV?m+kvZgtOu|m&3z_zSuUIM^(I!m{V#Axf;qn zcWpR?mfP)dsSVT6TJE~biwZN87f=EcjB;>9eQ8r?kTJayVlX%;f*&U9d!1Y z4H40ttTd$&34Eiz5nOb|VJ3msV!i!PJu2rbLqmlkRe>^CL*6ho~q`7J;domNEM=KVswZ5dg7NjTnhn-&s(T*vi zz}eXs*UdjMDVl%DiG`plq7Sr8BJX&Cw@?+xI;XQN*M-s5E@f z*gi2l7hJ2tk<+eM)l5LHiuXIlIWCa0j!~E7%}_Md;{UG;WEz|gAzIp`M4*Ajh%!tP zKfEQ4pA-Da_MA?xHP{fb_+w{83982gVNEb3HZYeL`hDk9QC!#s{Waa>B+O=Qk2epw zHFuiFXS|IT6*9o29~2Dn?7~`4>mPw!CwJuA)KONUzzLNXNDNiiPy8IM{sMHnPiR2K zP)YA!Voz$ILNhba2OA^n4z2d@uASpPY_6Or?h=t0h?f^RWdl+B zG---5j91`kXVzvwv7D~^SK1hcZ-o+nFX)2Qb_i|uZZidUI^BK15H)yC76<f1k3E9z$5^ey#CmcRvAw3VUMTZkOv`v91a|y9v}v4hQhrvYgzftY1AGXBdx1gY^{;d& zjaIW*oGDF`c=p{sos(~2K#${a8at2~th#+DU&!UAyj~?ChSmg+v5bV|bXP%2=t;rn zn!T#;63VdR?n_a!)j5QfIuLo|^B!3};eo_|v zi_j$TtI>93S?%p+0)iNg6w?VSTdxc?$dGsbnB}A@q&wWM_w*Nc8?3fL-ye+_1jG7$ zsORx+bFLZMM;9+!GveArrfEq-b@!uTQs;>B#s_d z=sj4Jx9R4M>fx4y{Tt_?U$SKJp)+XDXm3Oz;z!9=uIZcY05lsS?1>>C4hu|dJmPAp ze*HH2`-AB3G~t`u*zk`1Jq63r4Ak&@(#lKvUU)XP^!pW#^awpI%Gw_;(s&H)@Q}1% ztYb+b_ovw~(vY6a`Ynp{;j74cC511UzN@(9o6bEFr@g2glM$JjRQuoHsqwct1VW`8 zs_gC1^Ka?SG61HK=7kVl-FF@Q47IOh{Lbvd zxIWnzw~%r?Tye2-prQb9^SDto$eLv6N=2F}1amS}(J$B)mjR;Fm~s&sT*Fxt@l zgnPtdj~8j#+6~H^OXbA+`};#F1E8Bda1%&xsxiFn!b0xOlnglPhS{kSMwC&MyNzMh*Ie)w5^x%T7NapjKYo6pM!$A` z5;WNXdZB+c+Za4SurtE&A7$bc2uQ3#EJcLmC@~{#KGgCM4YY28{BP4b&-YS1)Qv$^ zVDPoc{e9EMaQ%|c-&t~l73bklv~dlOobEt_1I>`%ArR?RgjeejwLM_TAftk0P~={~ z3iJNNUZWf*!b!;j;B*r3nFw+ch!QMV;;t;T=%9Z>DWUg}#}TG&_b z3Pc+q4{NAM7C99^ob3~Uvkwv({qUcQdqdlt@OAC7f5YF*e#0IJeG4_Feu4~@xs*oA z+)%=mTLs=ds^Z2LYOos?_RS^Rg?KTSWbb}8X*kvBa}|m{9DRIVZY_LW_V|2zt3sxZ zJhc8Q(9c@|WJjo{Ze3Z^Ys?YvVe0%;Ebv3*V`_w}x~B-@z^e9QZF5ea#@0@aBhdQ( zZp8VzIzGRS)llf9){71)tdZJ{!?4FBFov0ty!+k0Poa$p`H{%4)z>t4lvw75N`8G_ z8a}n)fV{3YL$|tXTK>VW><5n+?S?rR2>lf#%bZXJnolER1n11NPHKk^U~6KLXE&L1 ze|@ipT|^dKbI!8unK~kQ)V~Zm4|3P*vfJM6d))IWoZ76t?n->>AVH>GZtsT;tU7k! zy^QkYXLuV(e5%nWil6JK53AgYy^sH$X|#KVl1p+$WK#Q!a4VJYA=H$6e$z|7lt{?a z={}_qc+93r_0>Y`ws7WF^nhJ{v{+$*9etQMu!XO!c)n-FweaxL^7wxgqm(EmCy z8p8-yRiBwl%DCrm;KvNW>vwnLpO=S`#`S0hIP{~=N1<(setzuN50~XcEbZZI^q!0r zbZbwaNxJ-ctuniJW$nljc9aS1$Ra?P@m}Fa!3w=n%mF;!V0Op0(SubsQF3*uu|EAp zTkuYZLrZh?Ag<5Jk-PX`?=4)$_j2^;=3p4@pHX_boBlYz{daw?+#sHGR|7g??yon2 zx%b${$r9V3?So13z6>Hr%IviO{xD~LV%3x&FY^9UcQ06G3>fK%X^BEdFyForqRyRQ zqRv39tZ@388Fbh6I**yPxhkmQLN3aKA2A-13H6i=m5f!Yr-S6n@~=9;{@R098;o?* zfSyDM_OWlW8>yc*Y1LpCo;YT)-i07=Ip)=vM(LgRMQHl^_cKaN{s6n5s9MVsZ&v#- zMY=%xcPUv6ZiII$&NfOnJB2OHs;q%ZQl0tJ?mz(OYtOsoUCzrkH#hd@&eaq zA%;S_ZiL>UG`(MyL0h_NXqDb#P2=R7jZO~~i8A7aN~HdFkVJR@h5L7Va*xF$4eGGB zWlMYu%z0ZYNM(p>m>5iaTGJc2(-3`lVj0gsXvYZ&hSu}cB-QZNPb3H>^yDPxhBwT>^WaN^j(is4(#1-aGnO!pQ)TT8u$JPj(X)k{ngv$azPiKfOkWmYA z7qJ$un`2N#zMcc7D!TPYq*5xx<+j#FL&*N1E3p8f3Y#ufSJG(Ebai5BLlZ6v_B-r8 zG32yIV6#X!g&fqb1R5AQ<~=AKWr8sUWoYtAN44eG$+H=Gnku`%`uN}QA%%K2c$5Td z5u)M)Qz<)BL^@4=6cyH3n-AsDdXhzcF8S^h)b0Q?XtN{$7Rwirn%uRG~Y}2`}jP03+{@NUNT_CLB3;Ndz_$_ z5QzekQTkpa7(xvyI0WQ^n<=C+=oK-9o?i+Z3>hS)Ac^d}GkYz&-%W`{7DV!K{=9ED z*6@AWY&)JRYn~jyQUm|(k_WG)6oOjTyA=GH=3?9%WF~7d35AVl+z-alSqxro`$t0L zNo_zPD1r;!-&=kkVF4mgq)m(_GeqA(;;#l#6fw*gWLWkX=kg7U@-lXqT7*I~ z_5Nhd;}=PVlSQNzY@Q_6oM9^oFYH@Z2uD-ddQzmv(JnU%I1m}ZSBASX(;lyiZOqu| zsA4|l+IdWWu-d`QvKd7g2>kx_xhnKyoOtrLc%;C#W$DK>8PPu9Pt(;rE|u&t#--+= zkThCgT;9&J=`e-zSVoRZ8Ul(yP|8UkUE{h*|42?6A8$dH4FKd5rmA%95nk&yd zmP8xe+ebnW!3BSkQc`CykQDrP#IU(>@|&5~#LLS^-SV%4{97{UFKsfyNK#viK`u*f z{nk#VPc=jjTI0pyK;Ptfu*vYix*h?P0VU%pdL7Oy-#CHk*)+ zt_N;YlW)mH+=AIB&c5tQ^p=yfN@Gw4{-ZVyr5@9$gZN$^y&n&R4ykV&1>UpYLy1EH zLk<|{$`WrJ!KgT`R~Uslxg;sr_C0zpkG`3?omxY(q8AaRB9C8}(w%2UYbo`?42kO! zX8OE)0zyc$DY}=n)#pzWXh*h`0p@dInJoQIqKPZFJWJRD=nz=Xoy`Zb9M6^rB+54! z!rtO9@x*&qOiGy*SY%Fz^#Hj)AAQC^QZ?+7 z(L<$|epjhqmA-mS#r~?+*7R(3Ajm1jGAB}U zAuhhU0w}Lp`jW~R&nvqwuu`2-Ten}g-Y1GO(iwAg*V%o8viUJKubhkhV8w1HRP#u6 ze7sa3l$o`>ppQ7`LBb&mYZ+au2w(9g;q0=vTR zefT!(NoqU`#MTcP>EZ$&+T;5woZ%QOSHEczmzs#%sd zyo@`P))PVg=FP!-J&ZWZ(Jtv%#m`+1~;m$&vD zG7U0a^TDiY(Yw9B?*(lDgvl4YMd;0)HN>?iWWh7P5PT7FO&wSK$Q2(u)UG%X|AiG0e}GaO86ChB_+#t6 zxwK%nuuuymhLFt`SLb;Bn7QOH3i1+b?^ajxq!zp(^oNutQzodPOV8Q&T3z>4GF8sz z5zFpqi&hCiewv*dR_+o{YyMS;X{9}9C#yjY>|J%;=Yr)3F>+;=;@nf>e^^dOJ zo(81_>ve`y0S{iFtzAFn-X1-+6f>|LPmXj&y~Uk@TYqLF!LYX0TPyiEa?Fe!-9VJ| z{R>QLArp-##H-2fiKv0`wADL_b6fMcQb;(gAm-f_XA|^EOc@sYaxIJ)%+#7j-0Etu zv2|4GJ$U>yvoGXN17Vr%z?og>ll}val=;vbv<>}_%^Vf;oZ`Tp}Hw^LJVXaPwOrT(3UsQz5SJKzw=4Ut5aCVq!23?jr~?j;Cy zhQbvQ%#&fJfx50R^+z7XdM)AbgW&RyC!gGB?nO0>-97 z(>kctejK744@+FfPJ#c12uA?q5F#QY!1FG_N>Nr-c2;1dy6tDTLD#7-#i3x01pVI( zfgdm&VCE=YFQ|EfBKpc;2>;-}iF|QiUtxix!uj|1()bfCg2PZhQ@=*zS%0m(7Jtd4 zq4cU=OZkcT@6;R%1Iye9L7*L`?yp&(MXPslQcPAS{a9)23p_aqRR{p%$c=;ZSCUcv zjtYi}h6NrTi3kqyNhE^;^_Dma@Y?iWpn;9`+;;Jn_P9L0l0!@jWAsBmyE70CM!V*N zO#?~xlr(g3-JalIxeuRz55JU-dJ5hRl0SR!$~@a!--mg>$ld|RIQq$)|yB*=H5ta!G^9MB{{2=HwGWG;_@*o+Dy+vqzKhK0XV4tfzG^uO6)EItss9Ri;H zp4fJ__t{mo?s{CGxZ$0;mx9-B{28}5e*{X@#N95wRkhEYZD|?^NhwyJ)~H7aQgnK7 z4yPItI$+%zXI1qwSp>#F!w!x3k0{g~i}U%pzDJNb0M8l!`Y?zC{V$+)(Hn;fl=s$x zw{_d%l&j9F4(Y@3^|-LsCws|yopgfypIze- zdfSlNfRmc!Q05XO4nnwxSO}xHJXub}2;$SxtW2HvDW(>E)sC=#0tPmUo@chZi>gob zFgoC$FI!Md@A!8uP#*8B%|+(7!P*b|8+3Lh<|_+_h<$@ei5$LKrQu`(gLBoJQnfU? zlzS$os2=kTBdveAvlBP*OvVjTM{)F+%*K2A0QFHkPU(KJIup!QCCvJl4+y=RlGQi# zQBHk9h(X{R-^coB0+!b2h1+fM6MM~V&Bwlq=3?(_RYi+V1}?5dHOgex)egT2wW@;c z{cngeb!Uu%5#5oUrGHc7t}Tefc=3a^>>8_CM^r|P^NOxkqSlF@-^F1qO@)D^>Bsz8>FW3&lA$NI@)|W_;$5@u&D{gHmzdYm>==AoFMy$N9j>)Rq?(c(Rk0ebaUf>reoDzyMNJ7%`9#01$Rc5_#;Wj!EArrICAs~bf{P3)Z61{C%0 zvU(>Hdf7|?ePliKAxFK*r1XdvFlgMhu?^k8D{!QG9&d^LJV9sq(b!d^85nMO==qe= zlxm;!{;8V)p)k6dwNPYGL`d{FuHc9#R!HLhbHi&AaR{nx&^kFL3nS2I}XWTSZG zzJZzcT?MOVmG62`^;33st@oFR)GW1AHnVP*Pbqozp0rtcMpmqOViTh*fCFY?=g=H= zF3${(O$7ufHbl1s^Ug z@1#Jz1M*4{9Ty{Y6vzh0kLURMf^*Wv!Iux3&i(26dkHO>72QQr!8`9lgg33@dfeB5 zDe26ARIEFzD4RSrb0vWg;B}~>*uJNob)It2Lp@$@%$I7%&gsNKZN}XyrpbZ`?VE0= zcf2|;`kS@0#?v-6?n>7dL+a_}@Putk>H$lE*zS0OKS*AOFdJd+zE|j!a@UJvEa!2c ztH+u2%&ua zq?FoG%5~@H0k9E>9ik4n`?v|-tJMz9!ZJQ`2vxxQq!(H=&-WFysx^xq9o#XdE zNnW3Mk$>inGA)3jNtoe{0-%T~n2l*mnJ2pbOrxX!)<45;fzGtmkdp4LA10BoW}NqZ z9ZSiQip{yso)}ae$m=nTCo9c@(Vo_S@R=cPq6k&;k`Qr8t$b0_cv%2U&4X0Vx&DoJ zJ-MX1a8#)S#q4k6`c9Za$N<~@hnA$^IO=iL=SQ6(_hd&6RX@MukZE;Kwg&9pWnHPQ zE6?`>h%#&|)csWm0d&}8QhDcwBVN0FE%(WKPr5K^t_u2?5wdlY^^U@GtBJ|crVjHK zSp+d&T79SjM+o1&?P`)hc~AW{YyaFz50yI8yQmGoSl>lUv2$ogOp1Eys8eWBViF(! zYtkkYTKN9kU!057&DGyy#)nP0jN*&KWvYH7mbgHHh%j8W5Ad z8J#T%ro+9(`@ybj;qWQZ20L~;@CDs$>FzG(V9{K0DWu+C*u^9b;l8nj6jhe!FBnXi z)G#ms65Q-CSKZ7%IzcZ>F*J)H2C8PFaM4Kh5DZ zaboW-IjVj^M%_AMi0jwT)vaySynldJ-aaR6)!3c?m>9UXMg=DEcNfL-H(&~)nHOkF zEz&s>;40lvDgKtM8Qn0$`iI@u5dEa`@2__x5D}-EE#Yee`2LAo#mv8M?XPE1Foo_2Lcn$`jka<*!d>AriPnp`WuZ^H*+twb(|Tp1jmOb9M}$6=Szo z`58N+fnQ))?;Kd4I}QGtBu%D~;6oW6_-E52({^T=A1E4J2Mcc{=YYLo0<8VCA-!c7 z54aY(nSIl>o;j?oK*jo9RQ)!4MH3D3Fso{S->$u$(?6ZlVq;G13-+CN8%VZpQP(*9 z1&-8^F?3esGz@E1wse*9`UaD$L0NLeYa+5vKGVs+08`o1*GWtLujltR=Q03@fI-CE1(KJj74tc)4*da|{C z|DmAi4mo5##QxL9#R=i^d{EXj?Gwv?O$~Vb!BhWqvQ!6oL?)q=0My-Kyd%3u>NDn5 zf9R8GJQ`PS20D7Ig{n57aM313ooInu?v$RnzHtP?Fz-#CQn)CO;hZZZ{F6=;pXc6z z0tGFv0I!9tl(~x?qAFpz=2@XQGKbAKDxCMk|6a#ktUsNP^Zcfg#wBaRgC-B85HH4Y zil&a(BN;1@87QrXfqFQVky%1haSGZlYZX5p&I2^Fnx~3Otx7yC-#_$u%J@$*;o&io z-R_CK>&wNVM@7*7$eLoYXbaXRC$s$Qne+$xX%v~JLcABE*c2Pe43=4245C6Hwj2vy z&9g4ge?hy_-3Yx60l(0xda+B$*IOT_hu|7hwwi3iG!?+=frK$s{^{NVQa|bLzY#Ql zDM0r;df|psAtEi)Loq+5bd8m>-;c$nVq`c0X4b_xD3m|T?P|rvTbz~S+ zJw_Zi-rj8<632BKDh2^sp}iX|F^f6+a(dBnrF*JQm~LOYsPySc3zu}F**r$FC0c_2 z1n-iktTfVX3-&*+b!zb(i((rJrmDI?uU z`kYG7oGwT@o(Zp%W2M=lQD==Hfw>3T$DFb%61gpy_EVh2RrW`Z(kmO3wP;5>{4_+y zuH=e)tiZuh;~sc|0tZ$qg})rap7t^DZ42(20u-Nys`#+E;22uj?-i+ z*m+gC0EEK#6XK0K-)~lm|7vw~s&DO+EVc-J#XEL_x2ShGiV%FBG5iVS|uAxXGL| z+BT;c!IK=$LNf9uu+o~}p)>OerQwpyF_bZ)WPKa;|M5YxflJ1mLQPJa;0uZ@xdt+Hto}CBIehq#Rz6rL3N=j~)RE&Wta}+1 zh{&32v%Yf(kTDqJ8EMsjQK;SjZqIi&12|H#fG6`lwmidadek>F3-=9SN;iOC7G4yz z+_BA9;rkW4aJ?zAEC_V_e4d<5E;A}t;d~1gQQ5_#uA%7>A6c#Q#vn)_h%QU6v%zy8 zqNZhxNt%jvV$sCVhvoKNywLWc9Gcij^RfDlmG6`L*6^puONN`ESf;<-{=kTz9#E=t zkZZ@C2+s-tCuzex^JZskM!wTM?Js=kSZsAXVzad#SDwJ*g_$=`-UN(S*;OqNQht7;Z(XAToT{Bt;He3= z+Bnsa8n{W(UZ~a9mob;4&h@J+2dvJ*e_K~=mzGL1(f6RmAjD0Iu=p@FcS@c9SN4D@ z;U;+h>F402;XZqIyY?xn)01vaZn7>*g{=l+J5$&Tnt4=O>OI~OmTOW_G0qaXMrqOZ zVRiZbga$vnCtVK@9nZ8iSl~=1=uJJMUZH*GD3Gp~U;7%&*zIe{bxKx=_Tt&&y>mtNywrim`De~)()R_fRp zt+Mo_%bGcAlDYZOkFcx14rE#Gx$2Pg!c<_oAVpyoHY3|&z%yM<)KRtXVUk{qryRB>Vv5+0)Rg=6Yw zW)0!q@;$ljwuBD12@t`5TQ}m#G&wP==9n41p2#qLal|Wb-mztQ1{#fwEt6aJ(yQ*! zb##l1OaAMnw*O^z%{!imEG7(OdMG1s(r;^Z*?n%X+#Gub_?M+4Mqdt_B*>jHxt9Gv z7qy7?mC|lhh{^;`Pm3!<>@|ds-E%Zkn|1J?p{5E317_-_@%{{w#&}%S@=;AxDs+RL zQ4J5YG=w0GNvrXM0pA(Dp-Pocp^E+0roHy;dfq$3N>mV*hZ}eq*p1F>I~2) z6$3r&45*EUIw@zOk{FuT?N9t9+fsg65YqS1DlXGohF`&s0HMF}(}S`r5kERyHoa}0 zw;=uIW6g*!1-QK>SkPr|lRxU(hSNp91c%vQ@#gv=>})O z56H#7)MBn(pwGz>XTKA)SR5<-@oJyL=e_F|3oxz1=wPM`?J$3#{*Mq?C#YtP4TDzQ za5BWT!`NNc}(D;&Ih zduVxj0`SucXjtV|R4bNxXG{snxJkbIRI%iX=LiuKHMj}9bT;~HU(aF)iLQ3HQee?% z;P^$2wY-)`Ki_jE8veZ(S?p|;saQ^ae2S9v0<{pjhyV8KvaE$kU&Hmz9m%A2-MVUh zQesC)=n$@y+1}K>*{PH6n=1xs#ZJOq^M5CA#2sBK$|79hw9+RJcF*_47opD-#;=PQ0T8#%G^VO># z0Z}(NY?E~n{NE-bKkCcoBaK``19q}V0llGQ-iDChF26RXKl&!YFwSwN>JMlTh~@Q`hU2Lp4q$Fef{( znK^tiSHJrAz~7SEM9uoVQwVLm5Ymxr&xdo;8c70e<;;fe(*pCCI}xGLiZb@*ClK-r zg&93z=>VDei|+lJ${qcOumoo&E+D@<2nu>gnV2vkNWur>rK)bo)a-x zM>!G)vOT%*gq1R&`@S1^?)RNKGimWj;hCVzB4$fL<%vcH)AHUY%#7HhbI8p4xKnaZphc)BsBFS+~;sNch2x$mdye^_myKBPsyJi7VLxTQ z`>JL1e5SF8#{G_MqgCa>*zJvFo7`~)YM0Oi9*s^h(+Hw(~M*Hygs)P3SynU z9gPXHd?Lh*Rt^bC6%^f%y6T&y6xWq!t+Ae7W|avVwha(4$J7zlH*Vfv0{Hs|Mvi~D z4s)(bnEr0V$Dq!*-#g5l#%C;gk9OtDB5f@aoFbBxwKwB=%Hh8L>#{;L#@Dh(nPhQ7 zauvYl(!D3*U4p5Ge7_aJH$_c>oQZ*E&YA7{ZL3GZTe_@r`OHkQ$dg29#&tg+gip}u ze2Z;bE&3rnklks{D4aX=95BZ9oo76lDIsv_JQJ35h*A!F_LbwBsl0KuPD=K|I1j^G zOaIa9=Yw{8P?A0cDM0W$k$P}o@=YNjh|U2kYzp(0$2_TGIWRPG#ThrZoIoLSE>69u z1S06bIVpN1JZSM{0Nyiue&SZ`{Cwp|aL|U^uU+sJ4sC*7Rx_1>3g~O@qb}4#=KhB# z^NH@DI3Iy@Dk~4JCP22!>!j>CxD zhci4F(t+QbFPL&3`?}}pVjgb2M1@B!xX_SP6Un*mrl!+5f`i2sIW&?Uc-ThVaH(G; z@9ze>2#M9!0%%-p{~zX+hnJP*e=)DTygdJRt8jG7|7KpJl9C!-qmo?R-NQJ-2f-kb zI0q(W$TvwhDXZpXlzike0vLVSYI3}fjCp+-6l;=%qy z2z3e$`FEX^`1bt+&al}S{5m`wuI_6WInD{9uUA9F!XF0J2-ewa)Dqei>O`!v7Zf}K zgcxGC0OFv$0$p8ud;2UAY94ARbNaDB(N=IHP;XE#nk}?*sBmkiTQf`_7|I%WJKZT5BhBcGlF5Vcw^eZ98*J~u z*j=t8;Q56N<@Py%XK4oQ6bO+m*gM?}Mo>!*z~vQ{PDeOO*FySFFZX;4h;bYZ5}w6^ zbA!?r!hKiaL(QZ4^9@YM^;r{eq{qem?eEgx7t`Z?@Je)KG>I_1?2JlH9mft4^UxvW z$%171z~YWl-GjW+hqrfh{=i)i&ad|M%Pl*$NNNT^G?7~hUBD+F^qt>o~ zNNNE3PXeQxYp}{b4LE&h*3l!ScgIhbTK?YPw*Wr@u*>b-FM)I+mP!1* z^OKv{7ZT~o2i2|TAwWmK@q&mh4~^8oQ40-gw!F(Uk2pF%Oa4swMf%nHr4>#tBX6Q z$nwsL;#Y;bC>Y7I=nRNE0&m&#SegX}J z{OLO+;Nj%*6?940`ZRu$9sV3I!c4y4bnY{Rogxw0navY-OH~)lqT;_ z@Glz=jT)ocuz#O@uVG`K(O<12A|UrTtmS)(K{AA^ng&)g@WZt_Ybt~52E~rsH*^#w}6m+yFR>$5N zr1#nA0J?9$0 zMVgR_qAgB+gG^(@-r7TFA(j6$+C*``^W6%0rA33dmCC6%CC2nFOtzKbVN6JU?jmw| zexEfl`+hdLJa^5Ks@nHZ@4&P*&OORYIZbz8YdoC-Jv*_u%p6TBj7qxNc++~@w^gX4 z2NoXlsccqQAeP`Z1FmG9^Gp_dDgui01rP1|M$iemB;{=1dCC4>h>1h!?)IQ(g5TaQ z*(}4UEZjAQD(Y6ZJpE3Q*~9%;@4&-DqPn(vQdUXk!fm>H$Xk7xR}DttY{_K9nyjJ2 zKUmT4m=c&GnIC=~jAS$!Q4O?N)wXU$^yf*%n7qsQK$!&l)BaL~@K_763_ChWicJKt zxD<1If$YpDf`RxthH)_vSz-+H$F4cB%X4#eG-2WVNjgD+R@<-qU6E}gsD;nxS7LPK zps#+_e+`ui6~Sas6MZ`?HUsz(725M2ZbF0-4U?=&5aCU45G{M#Qk)YE*&Ig_^-=07 zF;}}BK&s5MiR16i?a>Y1-G-tSR?33TD=~IQ*RY>jB7Ch!2(RSb>XTP zqrc9A?$Ty`eBtul3IF`%N;C)Cc_`%7;4UKXDd}6jDQ=j)Q6*^dC+|FX$7wGm`tx}>_y+y zQt6UtY@0KnL_#2`j_M`k1Qv&F8OzxI3y_D<^J0Kr@hDKQ#t&P(P7f>+*`}V}r|56C z!#^8DxmdC{9>yiaC!E2?ol?re{eH6`p~2G*;j$t_qF<~6|V(b@fmp@PbP z96Ivdlz!Ud=V=oX*WbLb_l*h0I|NOVO(O&whmlk6arB@6n6=yawrli~l5VLpegYqb zsr*Z@Yb#FjBs$nb2t{LHoWzDsAN@!U>xIRyVp4lfT`T@)7)b=bwQ^a<5p4@FZr=_A z;k4`9ZmpCa>lny~`8l!B> zlAMu2!>ShsSRqJX(e8qB67 z583Ma471~B(2*isO&Jz$tIsgt!|WvT@h#&~h@74E#R;V?dn0=@!3Wv@QNq**Lng2i4t`u!YFSZ&i_lA%iZ% zlK2^Ot*3*$wvHu2tfm)t%f6tYE6V|URg?UTzibSh|1#}lv1abxUWPTp!ge%N`$JVV zCUen-*noef_7i>DAUUYz<~M1vi%vNt5zrQsq6u>(R^CnUW$a~<)DT%T3@KuNFSWVJ z{G>eiF~O*f7KY)%cjT3loRZg<-1Fyg(GFbk zq~FtXe*+JeL7mHtfCTf=4tbk@(gG?>(^l6hJsbV!HOrZjC=!(>^m(LfLpZraki~jO zR32>)D|#j}6t(*4PjRUsqd5Ms5p;K1%B9Biz^ZohsR~e5=Bi<3yqdL4a!9DSF|P7} zxPPy+FW*mb&#%^PNkw_(QOn{?D%F&2uo<9QM^1Bz&PLlu=>QDQH6ihToEx-Bt@0yG z`C+5NI&We_E`h8;NWwS9!q|NDz8pWnYL_ulj_#my9qvji(A*+JE$`(P#;Ib!0 zOI%kF!BgwlHE;3RGJQP)DW?fZWrt*h+MFfpW!mw$IS5|?R~PZ5P~S>m_nX|ZbYuXe zTL8b;U0wcLn@nm%o$qb8W)byw9SneaE`IbpI4l)1&m4*nqvi%_Z%ptxAnWHxSN3`{+=z#Yj0uYXn5O8qYQpvDP63k(KbZWKD6>b0cwP%~o5C&pvEomXywjT!n5#(ma~6x4w+>~iZ#f7Y znm;#Y_ar-i6fU1!e^#R@cZ!^sUNA3^dA|Om{bkcwJ0S);gANGOX3F_8{KFwLFQK2Nyc;fbR!ehx>Zw*ZZ+)<8Tv?kNh@@*`7GsW1G$`15w2f?=J%Y+ zn65={F@W0ReL?(onZ@(*UJHxWR(nw{Y-CcTmo;yH{qFDdix^q21Swxl9oNaOFDJ~z ziT7`>y@+CfqS%-DwfAhfbs~b@k{9OfQ>-O-icL%3eidAK(;{|t2ei(Bx z$&9am97ZbJ{x_-ys_B;vcTffZ(-A(f81EBF zo6+6j*{xifsGrEzhWQZ3XCH?*>Lbz{d!-#u29zYa%s$#pZL>I3WHf>?g)PV8E~MdR zq!;c=_ndJd7j?OI|MOZ0 z1hH_9Uv7d~lR~9-hsVn+GHoX0hMuBVy`O9}L_33qj2}Co=LHV+$>h@FGf$gptdjqK zAi%@KCqA2tHS;eUnb1nAa-1Lj?jb>SQex&Qpb+Ix?#XZ$FkrQ}z&+rg8v%XWB6Emr zR}6z=2e*V-ps9XKxO0eXZX8rnup4LElzJK%49F*1DyOta%36^YiF}p{c_po$0Mtt{ z)j?qI;(4}JJf~p&a;`5H!l5uiu@;z%?04@G!yk-c-1&nN>k4tw6-|kp2fSuWu$n^A9A;`|$x_hf%!|SKnsKp; z^Qqn+?}B`s3^TVlj%qcQWrjTA7H~_S*zBn3+fI0cG_iRCyqOC*C3{6NtStzCPb*%b z<70~Be&mAPD z#7uEfaP`Jniiad6%-uR%bFF!QEuwFYBtkNVa*2Z8e(OP5*)0@SVk8KM4mE$>>8aN^ z5*g88T zQM^l82@!_V$49+8WDFUs^@4GySABLcywhian6#i$vCRQozfr?(&Jyc4=Sp|n3aQIO zm`DW+(mbnmh0*Td$_RrGE;w<64HX{~%kU?m8@2_SkK8;=7bjn3&cS(Ioc8aevN@*; z)#|R!#Jo;V^&0sD@I%^vb2{D@Yvvt{<1eANI_xZUSueSNQL$5y=nX6mD>RKag#q;9 z+kKui?W+V_?`81Llb6#!DGWtTyW8$I!K_Tdnuxc0ee2PvujB8qgcAGkMpD}!PWkbh ze_Ke9ceBxp@mzzJZssk|g^_J1FV~isPE7=B&frnH6+V)DTGb$bMLf2-7{XzEfg>Yp zo1dDoxVR2YvE=d~jU4AsRWz4*$^KEIGAj&MY z%|z}R>RqYgQ7BLH`4P5Rbm}i$;->@_FW%_h(@Ln#-%BZ6uB%aIWH8mR9f#+`UNP`u zGMM~`;&Pva^0gxE{4~~oSLzaoR?CWPkqZO7KbOHSOVAg8?&KU6bjEA z9f~cboweDH2gP*aqMWni!+AZ1Ln=surt5rYK5wdRO{p2^1=4>MrdW>3PJ$|kwz~Ca zWsi_3SP^0;U@_zdqJ4VvZ9K zo#=7F+HQ+zD-LA3EVr9`^FLj$I+ijzdY*8n1K+?m669aVY4WSRs+<3{E~P+!q~kn# zo_9)Ca}qDDn|tN0ip_F=qWlV#5}nwGJ#o~3RbNV8oW*Y-`M|UwGNTH z>Cc5NrSH82UlP!e>eKZYHdQpvmOUbo(uGO*xiqM~E9=|nb0jPTDSFV5(c%zKh=zn6 z`f0#&BiXv8F*WS}a|`uchb;|uA+piCjv4B-x^tKXzoFlviZ zBY_%!eqkNSq{Q_7)gbTd)Dz2!pEPOMI0*Gn;gKrtl>RX9;j!&jEgF_Zm+x!%ib)8} zWUU688!Cw`?gDqgoLLWba;KFMF8bu}ip{M}7II zkM{X(`{Fx6EsRim*_jn#sbHy~jWv0+&(TPKaa1NTCm!;N(`}EP42#U^<1HhB_sQOF zECebROL%3SU?9*N*aL6j;8e}hgVOQ!$w)J;dq}tJk^CGB;6g_aMs81raGkwHj8I^^ zV<#P-vJH~33e_Db51U_Ti=UA3xWcvk8Uytn)yz6f2&7mW!LO2)W2yqJ9SosDYc3vt zI-}yfG|TST5+@v)u3@M*O2foHmBx+xo>pn&Cl$jSEMVj#CxgjF=2G?amk)b85LWxW~JHZx9^CTo^Tw=avrG3acp*o9}biJoBG~oOl))1|AL$ zfJJ-J4V&41p{A(SG`HPM>Y=)AyobAl>Xo+I1qi}swtuN7Fo_x(M|3r(#Q|1qKNQre zTT4cTha#&z&Uhky%{TFCUsqF9_+389b6eD{qD2gSsRfqRaUDy>k?R?MNL0OF>ZW9b z;FFcE-Zw0%m|F2zAK&*Hxe0vZq8nKDc1SB>29Yyxku9ixY*oT;SW2MjJ^hkR#jSA) zp|^vM=xs4}{aSm(p_9ujS;#tcg*jTX+s7*qX4kxV(B!ScDe(G>h4zd5^T_}fi=+1` z+SUxfS5{HP!PUyBczX>7*yLrFh)R?$`j(jRd0W8a4`UbB3FGSh2EBIi$=jsjK4oTQv2wQ#>Gy2_4!o63vI$oSdZ_Jd>km4f0AbjAQ% zz4m7kqE6rLmx)h_69rY{ox46$SaG~9b{56l(7tyQAh+GsVmcoBurso1{E~GvG8(3$ z{SA{X^}ze->%t&04nBhwg0`P39O41OaJdnYck9ZkJ?0STK`)rEaQL+CtRfG2`eu}C z7q+8+^kELCvrC9f`GSlm)asrow_{5FM$q<$^kJk zpP8$~msR(7Qu0nzCLJ~QIR#9QDkzu9c`cdW9tBbWjh*;hOkripyG*TtR~-fHc~i=4 zJoE-{-{Bnv<)(X09-a5}VHu%e)eI*@3IP*;j0}!ti#LWzHEVt-Ta5H>X}Oa4_y;1; zKD%Lzjo}iSuJ_x&$n`U)^dBbG+fN|50w}X{*a}WuP9+6dw=96z& z!Z>c`wNFp%JbZzngD9(Y!25YIFqYhcxo=?bdaqT5?^h#F4pW1J1-2v&+o0k$BCs(x z+{L*ZrT04EMSw1W^2*H#bry;7#G%c94TyHJCfJ zF<})Yer>2=l@T9Xg6ANgnZYcaCzla)aD-}lI5eQNGGjR`ATK>x7_I*Ssw)G+v? zRa{tKsPE+ndHZZOYAS7OlECRJ9b{*Z5Xxqsfx{)WkX??F)vNYt=kokt&Lnb z5ve0(c@NY$I)_paec4-`m9T?FEe5 zRq$(Dea+D_`OeIJ zh5aORiZ#$?5ZrtZp?`bvg2D}n5e7knwLK?L=P>#j+F~oxVqCfr@}qWtcsSukF$Gg% zbU+d5WlIb1N!Jt=Idw@SlhzUKkqk5PeRzkDMZ`zN5T>*D1W$WYzw!+XE&JVn-FUpG zWqp}=t8g;?g!iD6U(g!zh{Z7m3@%sWrPfI~G-S>fe^ZlKB#X1*C|f|rOewM1SW{wi zc7C3D^UYlyTU4MH%H=G7-xb8J<%>Yt*yiX;*!QYdu0^jq6w7lhC34E_x1G+y^EXsU zj$IcL7c-jgW3$_}&(qz$9i{w)o5YD3Lfm1mS7wr&gEVgT{mCF%^D=~r@QVlQofM>ZS@1{o!tSkDVE2qnUKBuzp|HYa|)FHQ2BBQ@|_8kxHntg4Ok zvd3M8XgWjscj}&T24=S7FVb580n^={w$Ra}NNA*3e$hz<4U0coApY~jkNVRCC?UlK z5WYN-N4Fgc2R8Bkz;@=x34x?qeD~Ql=4Ou$>czUo@23ZU*=I|U)EH$ueLI$7TX>5n zWs#FJT60EYYkMI0#^$=R-`Z#Ke&9#uy#@qjL&-}nrM+)6_Tn5vPRd!;lRqM>Jd0M-E_FgHC!642d{bA;*1L+WUvKIm5cJKC4R_N2JJLudhe7UkWX4Xl*CxKw?5*!9TN9wwA4s0am##4%5#SxnMl3l zRTK$-FJ9tgb>>@UP|D0x`_EcNWqyy&zv7VhxqPwt9<>_z`n}#W(2K9e*~6>W3%vN#nkWS z8YyE*FPZw#BF1XAzs;S~Tx*Ds_pAgdRxv;f%tp7^EPe7==U)iq#H<)13&^l5trIE; z2n{Re8mID`XF3FYCgz%9N|8Gp-4HKmwW+b{KANlwiKzo2S31ah-)g6HIO`CB`8!^J zcB5GID;N*-*_#cMq8Ag=d6INs2j|wvw4Gg)&IB_pOzQOp7ezRcMU|josuaoqC@x9v zt;^2iGp-f%Q;vwwwQvh{&>u*m9RM+W#WvM39beeD&0Sg2ic z4!d=__diNgKO1V;g_Sz4%W^rR(>OL;5%G$G04Ew~4L*6P4cNryPmYcu_nvjN{us3h zLsiuVH)$rw@@`jDZk!5l9S`9HkAAM;ZvV`WMcN{8?%x=WD(jT{BKCen%XcQE;*)%X z^krG5u>RsBDj~qDM=Ivab_FVbil z-dO1w_OYaE>+6|NUd_ghQ%wK#O$!dGjHH!an|*mMS)V3lzv#|Ml@rcC;!DQ?OTb0c z>QEFXe%=gFZc;6yTZAZ%+kHpjSV_!v6}QYZd9?}^=N(IVG=|H$gz>X~q=HacP(<)c z=#l;s`H}u&uU!NXXR48WV9UP4h4qmB&G;k@biPGy!WUaVD!_^q#@uGVCaAC%KvMCz zMDjYN(@aX5&iov+c%D#5@IsEmg4?D0OXfj(<;xxy4?b6Y+trKXxA#luI~~r3+U`v6 zA2-qg-fW^|`}#_~Bsh(K?RRKhTlv&Hy@x_X;c(|$fFMiQE;jbV7*ejkhIva(e{X;0 zjn?&nfkFGi$>knvfUa0S|7_f8V7SBA+O$Q%U5P>n?=bYeb-M0%T;bhra^Z42Zj3z3 zU3=146#Cv66UlMF_#pE6>b<7DDmvoh1sw6EuFWTm}Lib;YQ zX;^Nk>4nW3kpM#nUE9d3yUQl>_uhH#Ggnp@*OXnHgM9;e1gKTz1E)U&rD&}~O)mrR zt11x^MYdYZM)w+DTHm`x>U-i7TAmW*b-UuW7`6GzqI2T+bd(FjT0zwYL{vT=W%GI& z_(05_?9s4DBdV=Fzk(N>dnP_(RMA_j4v!qQy+(Z;?GG5I7^O>Se_4b)l{d8J#`-@E zwSqa5rlCEv*6jToleEAq5i~b8ATLa1ZfA68G9WiKF*uVE4itYlH8M0HK0XR_baG{3 zZ3=jtjkO0f9NZQ*tVEBV1kpzC%wY6HZ_#^+HW&hzt;DyS!?F(y`R0$-se2e88#+uJw91mq%~9ti9qv#_<<4tc?}I! zF#r%K#18}t60(1>>BG=)=-+NaHbbZz3Wh{T{0BhZ4GKZu`V=7OTbu?G0eIpL2Y`eC zAQ1_Ws00uQ5Cj6n{{=+4NdOce9xz*g20!2l5&=aKvdJS|yxm~-4(Qu${f+He6t z;^Lybf6@W6&QLd)4FmzufS?_q&bK?-K;Qs9qzw#;_Wpmb5}Z;FXtaxjfPkl`CqKj) z#gBBef6T=T@Pwfq0J=~V)Xf8G3-~=SKojB&{cAFQLN|k&xKubxTAMJ(a1watCzkv`q3VE9k@qobK5bImOpUxowC0QK+1I0vz#DoA)R{+$@#zEkBd3|pe z=$|0yxBGSiKVKK53&8Gn2&f;-4to1T=!=4QKmlkscc`E5e+K^BA_Rc|wlEtsz#3`~ zLlFK`{nib&`^&z)d^eaE;3@EydmsSt_vha$^ILk^A`x)!f8c-aS3prwS4&Zo=dX$X z9g}~PLwW&x`2>Xle1c#g00aU70iw4HzyB_y4T1gL2JoL;RfHW9aEt%b?(I4Kt7VVB z8Nm6sI=BG;T}%^sOIs*_^Bca{Ge%m23_C3iUdPnh#h z{Qnb%IK$xHe*yExvfClnb2Z;ZL8bN>mQmqEm7Uu5!zfn~*o?2>V+$^MQo< zfx>_JVJIb-7t~f8hPH9|i!*=u4Ss744nsh-kto>j$K^H)2>hSet-x%YZXXcTEiwNJ zK~T49L;tzP-!}ACPygMABEkk~`&)Q|U=aYs%?;vBczgA?78u|Qx>cwx)awtm0Rn&g z2qgM81#mmFAHWXjM)>=h#e@L@`oCR&ED#V35PK>ia3i2?-N z|HHgRd;Vhz0s#VEf6V{t*v8$>?RKO;M7tg5U-qAO0}Azm+7Ql6B5fpt9czM{&Z}f; zJ^9uKrEvCA&W#262JsOOErhqB_s=l=b&dXbJP6*i`P{6^W(Ny?lK z3T{suAkoj~!B_UVaoUZK z48cKkwGELuRXCZR6)EIvschhxf{xS0Iq*Yko=7>%ZB*MM7^AU za!JC5LZqrS{;v~UOCk~8m`9THkx1TQ%@b9PbjMegKRpbQ7;9`j13e@gywaWC%P3XT*c?!%R~L|WaIwM-_KGYbaCIn}qLdAp&y z$Z}@r>Is;M>kxlNO_}uYiA4IokS8nIBK>6n2`VgceSPaY3EQ*$faA=OcW)+2*lvi^ zw8)q%e|Q>t)&QTp`ITXYZ#i3~*tASrziW3G+(oKQPO!<+r-OEFZE$~V1LR@tv&oX! znGj|f5Ypvw@W=GV6arUQT(1ZVss+ET52`zLUfWtQ^5K7{&9z@+a*UR}^DyVx*pNqz zcrujyj_YavLYKGFQ`hzx(ysPoEVyF`;pXXD5k`FaI$bQ6uo$>okHUf%1F@~wI~ z6CJQn3a)=&tBzp-itZ_$Dt&AQiz4#MeXIo zH0+Uwwn)mCu>e7O-!|B)Jgi@xjVcVuer9R_Szv-gXiH-cp>hvXnB+ZVpxba?U{sGDK#mDVLr*$&l(_R#xDOOgFv#V=}TZbxz^TN0*23kNIk`=0X zFA{&(-o|wA!MIYGT?M_uGkEcq`YV%*HaW*L`|`_>suw>?v`>`Ajw z7vp`DbImsVhRN5i#6OVJ^Pz#CMpv-NPket$ImS0Ytl8Y1?asw2_FQDYMwJ{;5yKOM zs?19z#*&&%K)PY_bEFOUPOsPDlS}N8FRH`(*OLATlI-MWm#;YqG;n?9o%A@vF)!Xn zJjojYSr|C3T5mvuLZ^HfSmzds_b>=9zWS>@YT{A7G6@U-bV&!a8Pr$I*TpgDia zj%BOy`Z?b5JP%6gmE?dQuvkqetI~|RWj@!GES;8VK;C~tnC&cJ?&}R1-I5a7&6RTb z2$|+j!L5e|5rJ{yFH~QR%Y6@^2a6oCe7h=JWHDU?vomvqp3YYKk%zR|mp%Rd-Jc|I zxwdgd1)IxnM{g`>a%X3p)|)%GOC5h8)uz`w+(Y+_%POD~uDonKebKvGb9z{p#qZZ9 z;QP=#|J5X%x}u(dYNUvq`2nkrhvMj%;U~JKE|V;o{+)KL?|yVVY~mMV*9PRkLz=Fy zi#HlJ1fN$r8iPN9EUqi>PLYq>meQF}KjR3BzX&Ro`gv?Zp7lVHOenA#OCX9hML{7tL&=d1A@AsqpNA6=-CCC;#RzVxhxvysUPxjmM_w& z?6Vi#<%7D7;*1?sIwQ)|`FDR-*z|4O{OM3VPvuipbqA;$BI^1$CXJ_U2SqA4k}M7% zM`FD`eXYCH>TWpY#d4Vb*xNbs<768967GrDN8GHv$ON2M=?usC-r1o}7xm3I<4#^G zqoP8Vk=xTRC*D~Ab4*{n(i>u1NSZBul1vWM^QAp3-z+(zOc`tv(8F&GmboeY1 z{W9;JLqm4`lwAFl4Bma3uY$kRuhj5j-}t5pqM{6bWX=J8GGA3 zfVc-x>N$JNC(TvQ+*5yq+aPY3(2Yws#$6cg=}0_I*>8W|KbuIC6opJzUu$DC@y9aN z=)Z0QNDvof*1dW^aJRARdn*PYWN82FQ%=;q%#9`{ZKmcScr*y;tJH?x;xOLI&wSnZ zT@9;4Q3HEQY;<`IeKOe}&iNA~OGk*&$+Vb=ASHY;Z7WB(CTo8fW-0z)h=JWZFC5he zmmTj*7UB+H!IJTE;+4UA=GD47FOVHPGcwkfG{vPgDJ2`yPD5^dY&c;Ubw?s36mIU= zE)3UoqPQgW3UqyynQyjvO$O(g3euu&x|CK*Floht7=77QaSqDZ%BeAfXHF7`KDK$w zeWd_ZEMRy>VE2EsDjQSTgG7YV3@12jn54}>Y@7L0N5(LNGw9?wWCM8ZFb9p5ZLpK? znc%@n-^+akUi#7B4aUnxZhqEmPV%JqViD<--XuZ!RhjroN>7hP#WTl4q?@q68?WYL z9RL)DA4n9n*A%TxbO2po`SN0$7of`6ZaMJ!*SK}1NE?3+btl8M(G(VOX0vsO+UNV} zt4^ht$3e#|VIl7*2(K{F7s~^C>q}O()7NJVmz1cO`XW32m!<7^h#w9%W&JnBxrif0 zaI~p#EDI~%Pd_1!*20GJ4voR4LjTaiJS_Y1Q=5zwosHtU&8Pg!uO#@HY082dYYV&x z=^~s=n~#61m!{d+FeojRT%HtZKPtig&;u_e4Vw>K+UA(;qOpBV&hzzYZAj5|Nsxr( z5k_afwAM!-@cO+oGOb}QlnQm%U7cZ<2Wz;$EY3O_5QFNqOc(_@w$yDtbW#aIjO{Vg zHljiM&EMHb2<7#jzC4&IMbId06C6ff35rg$3zmN|`{;{5bF5bHumA4y!2D8owt9#< zM_GNbnmI@^4&{yALG+{*x(EqeDN~T2?~c zy!fY^#S3{B^aD$8ihmT&`pR};2-BSTL~~`?Bti4~rXboPIB z^EhWIF^W$pOyu;x-LF_BAdZIPHKKImf>TEFkFkRX$pRN>qAV)n{XjN^d8O;E&d@6rP zJP;r+nduud%|%Vf6WZQCVfk?3HJ0^oQDgX9b3A{LWJ5fUKY`O-GVe;CHLZ?8(!n{8 zYT!4J-G%7{pVF|U_L5q`%U*RgfXoY4gLYiy4^NmDGBvPU&!X4w=93grEft-(b9@|h zF1f;7v&S;2qvPLn@6FSA=s|B9Rrr6Sz;1wD^J=~?Sh@Dx8v{#bb6#5E>cG%HFN1~+ zS?QX;nRWs>rjvBJHZ0@O+#Sj4!Zcn^rT0P%c{!TMRwpP8`RX{vH@S@EFX52z zCiMdJg|b0dtv`=l;k$dl+&KLTULqEaUWCaK*%GOP?^I^U5L?Tk*K6}2kJo?PQVCE4 zc~_avDE7^7^88mE2&4R#)A3{i8SEW@vA~3fr(S4}SD7XJ5tMcYwXDQM7G52`&YKvu zR-rKwmy9eMfu?h7yk8Ekb*_Ht)?}9t&DP)PB7PYVPFexTU<+gj*6V+<*#Ry$D(B{| z^Usd0OU^wy+fCT25<5kCZ@1KQ9GRMv$$HiHd74gcInpY>%hXcs3Kfkg64ml}1FDP%*bnps)Nsy@fBR^m%k*~a=tNoQ?Uw!Do97`YS!QZyGFu+8awh_-M^ z8|vzCe}OVjsMQlr6R3ZsrJ9L#Z;{8_tUVIuiNuY%r)L`Ay6<8&QbCiq9~c2ws8~uE zeFGHc)AgKZ1tv;dQ%rBQ-yi+OGUT)07Qsucto}tEAKw%2=V(r4=!^AlH)Q?c+(WX;#lr0%w^zT;NJ73ZtSq;wxsY)G@ zaT}ID;_Mg8J!j!L=UMX>-IPX153?!A2A~R*%NJ85g);9i{{mxMa69&-t88BwM1b%x z5Dc9HDP&ciShZGq^=WbTB{H;-G7i)zor*`37lGpX=cZW;uEdWnFYb)Sjvb}%7jv;* zCf9b-Q*D}hi4|NOA24^0NpWABo$_S;Ii5sCaV^b?9 z_0`YFpYO9t?5sW*O{1R98y+{t7C#~9GmrIUx4c*fJ+v0}^I;DyWf3;Fdw8$+A(*oY zF7@^##B$-KA}Ku}T)8wEcEQ&^y} zjqjxZt+k3|R2;+zD-=I@p&3iQ-Pyk9%15OzeYh3mASJ3dWoDgAuRB0{ch zAdAUtJhPSde&8y6UO>*`qKy+fHY!nu1i{J@F-l6cr_#2#u#ukt#Q#>;XxBFB#yh!c zi@~rQeK;`BTphf<=lbcKCk6FWnh23!O!3J-s^@<~A&xvnJ*x7Mz$Z?A22h?Jd9@N3 z6Xjhjuh{?V;K|qA>0z(Z(aO{(sIxStqQi}!oWt~q<0+3`6mtz5oT0xv-4&Uy{gqCpbeY-u-9df-9FW8K~8(n4%si9bscu9 z`z++YQeDEeqUw*ZJxpY>RcLO;tzSRCng~~ZdbY1)6r^d@sGc?^0 z&&M0ea^&plofQ3a9V1V?>*%p|-WJ3a^PrYOc(>|+WQ=4uvWbQW`fP#@*4aV}w{m|c z4-$x6PryMox<9s@uGPolve3gB;bRCvc=}!Q5`~*;zE`|IERT6yc}8SH6s?N`edp6Y ze!4HzbdIX0cL^B2>}0*Wdo399MOQ_diXV{U5>lAO(#E4n)=rgtxd45veVFG)J$Izq z!{$xBeIauP<1K=(w5p(@V?|H6dZvH9e%!ZVa5B2UWdA8O)n~0;hu{Lmw_jmVS(|3$ zG~5(&UN5oaCx_p#ydB{5A7y#e)%I}cHStOO=PqNjqMk|bC7r=~@aB&a%WD^QU2ywL zy(g0vfYia&@dmf!MB|oq_bHl)+?Yk;^tf*sxm=kPT?wEvUb!OCT~g)XYOQ|>g>F(s zz}lcw^I*SO?SNKDPtlJ10p3+g8QIoy)HsVM>;hz=$*DAwL*a2ky&Nr<=ZX5 z!gTg(RzX#8rF<>*WKH>Spz$)&`z1>e(9FMKs z+69am=u^qw8FKDmqmU)oA#CxmCNjW-pmwNkr;od1knR9eCg`f zi1zNM_5l+1MA4TQ0{1J@X=+kWe-J9hdvTkjQQ)2J6|+vSwRbKQwk}7HugqSq8GqZUarWXu&z8jIkR(NTYW)|YML!k-pJYi}=|>xz zZpLz?X}Mk6?x{qA9ZL^wFBv=EX0NSObmZmgzr$}g!&$betT}%w9%L%YPi7@|qioRT ztMK8<^B)X*^cwFMA$HQz$6Zc{nE+TqpLEx1MQ|n86lK@kc6Ay7PG|YFz8;WV7Pe?I2aW3;0`Q!bu(aM6~j()C7 zyVS!xqPj~F-m`+gdUqmK#=jpCqU&VCU%H2gnJQYB)9$sh^W=^2w22MQ85VpmGjJLX zsQS@&+_g6pnJU;Lp+nR(6|gj(YUFFL&Pah7)wRB;PB4F*S?cF5KbLe4_G4B%-08F? z7nK}qQwuD#@ZQ)9vsW$^ zA*1*q*`yF7PA{;x$7dtb{AUeL(bxTB^PN!tVbM0a%V}yrn0NYE$y0$LhJ>W}MdBEo z%Smem-2stGt`begfZDS(&t>zI`(srQ+z zbG`hILwsJDRe^(AS4^o+l#tw-b+KYo{BFRT_~u-z zopbCyfu2Z^UzrjPi-a?0hyJko7x{F$k!lZ`-U|G)IzgK7(U7{`=)hl2Y1Bn;y4bNz zQ)qt>mEG@sq#sRjz^$agAD5QjuHf2t9!5KOxfns)tOxt=FZL7+3b;ff@ija)det zwzREHXB~>eyq=0qV9jVI(FVW8twqZA(_g+7GlezUMUAu7CU$5UTv4s5js?lD_A@M4 zr<=N*Njbkxr1hTX{N}VTwfqaB_5o8=YL9f$(WP6&rYwbz>)WHtizy+@4=+=)#4&$H zL<`mV&|q8z2NLYNJ$OZY&{um_SF8Cv!p4$~5h{a@h;#C&@`UJ1<9o-3QTIr?u9&Mw zz-6iu@j(mPHD;9KQF3G-=dn!|mUEsh!S`V&pOYHP33ADTk|VoWlT$9}H^dzFSGt*J zXYm7Ef}<=bY(H>6Q_IEf^oQb+xD$W>%4D88?S`}J%}egBlZt)_t%mcx_t?h?Y+~M* zA^E5Y*KcABuO%k=!FAV$k5J=Tyj0{NPD0!2$28A~6c7vDM(@4aJa|T=cXsg`J#v}* zVKLxgVquRv_XJblr16BUJc3T7AE316-|^+78t_)6thzIwrMNms-;YJOJHLPNo^$5K zY%66a7543y!tZ2$HyS*`B>?u=w9GRq?pi|Xl}2-1D>3&1T{E?7^B$%E)>|2=fukY~ zEH?S=ZD9&Ejb|FX>IvvF<#V$8KMoIuWl(BtOo4h~1RMKOVxMoaxC%l7KM-nE6l`mA zV~E5Z%CS)pFSKIxraNTe$IyS=b@noRduZMHY1-nXx3>6uCQc14 zqH~qX3=gL8brHG)HKFQ+>Z|)BKdV3eCN4-~``J&$CsAM!WU>k5`t{tVU3=ucgnBji zQAR4&b61@^Uylb!fHkho$8+jD8LO35u>mosVtiRkcR8or0#Vq&AB%TYD5aXrT*>%Z<{b!Z zMZ9dwlrZl~8MVvBic%J56~ZN98}c>SrH$0p)g7dxnyXH?^D%!{2z8BD;vp6hEJF6TLw?fFo0#(kI(HKJnWu8szav_rHisyX{$k&nnajVr@1#UVNf>ar zPOI5LPnf|QB$t1mrGv?klmJ#ynhfk-_Jl@P{5p`^;UU*NLHQopbAuar$;R34ySwH2r74E6 zcd8P~b(qio4+Kqy^OKqEJQ6ZAIXECMOl59obZ9alGBGeQlMoISe=;&OH8LPRJ_>Vm za%Ev{3V581w*^pKS+p*U2M_MjI0SchcZU#M8mDo03l<|5(bU)$pl)w!1$6QJPY7B8OBWXhe?DercXxLtV>@RidnXGa zItGBdm5U`n4d@JXas!$Hel-kGGPVN%NkF#0{@oc9A{9Wx(#rX7xw^f%i@UKC5C9g~ zTA2bt&R`E$kQvYk08S22msJ2LI{-m{8!P;6zySDXHUL&8)_=qO##Xk*CSZfVDmMm5iK+sO z!43Y?p0lZwm4k~jle3lWuNIkqg#k}l5@aTBZ)XPtxi};Ks!zho31|u)yC?JCCu;+; zcL#a@1I(>JX6C<|FmrWa)&yBOx&mb-{xJcI5P!=ofGz+|7Jn8NZeDf(&=COiFtud< z6<)*B0r;1a^_Ljjfv>lNy#v4;+yv0q${Yy(LiBbvb^`)joLqsv-hV3oix62^0cKXF zE&vmtg%t?#cXY5AX#O__AHI{72SAqv%so~B%dgMBPx@ebnc0JEJ%5}3b-v6}T8grw z%JhGC{I5<-%zxek;LXUv0$^n0WC5`LA{jUM!S}ymRE(|uDdP`cS&+FsfcNie!DITL zirxMp0PR1^K?nG6EG2s|Yk>gT-z3*#;bbud|6%=qruttl|9=es73Kd%^8a0sl&h`n zUuxRF^#32Vv7MEz=RXEu(z?2U7eLV-yau5EZK@6Ydw*#afo4{&cK=%|>tYOE1W}NM z?Z0ERa+b340Gg>-xtLo1&6dCAn!mQp)(Qkvv3Iumb*%sx!AJAIbl}x8wELC=f5c>L8kU*zgCQmlM7(%W`*AfT#n*z1TIJEHv(r@{ul9pv#b0@;Owfu5jeZr zZv@V+{<{Y-u(GiG-4qYF9F5-yT!8k!h!>20TYvI`%Q5+lz$s0fj7@ET;J1jm%WpaR zzw*B~;a>%~e$#&uCpeg?y)Bpp|0Chx_$9IXqqJZ2U^e>$f>Q#2M*z11{7(i}HgIk* zVT_$EfA{;#$I%tMX1~LL$7B8*f(^|7fWMShzmu^4f^NUFvi=hM4#xS*+}_pckLX|n zix58`xU1jQaDd5Y>FHnz1pSx6GXWoe<^;Qfz&rJa9^9+_?_$8t_Wx0Xn{oK91_yHh zzbZlhIbIIdf299CTn=#64&ckp{`YZlfCu4V>+1YRe6YmvU&szl@91g|zIpz8h^*j= z{V`8g@OXa5;QWPvZhy>=6Kw7beslbr7TmS7?Vl82Wd#@aI|2AgW_Gc30{+2&ByguL z?)HB;fMdA+0l`Ce`vZatcmIPhU~i8b4~9PmyKPC-0+{`d49ptqH1a4?d5EacWb$ZHSALIQ zPmVrXfi}=BkYDAfvK?J{P*rjOS4Q8@@2c)qamgb+mQFK9YktrRESjat zG0B+2BZqTgB!+*3aqjVY_UH8sM%Kg&sazaAqVI7udx7`6O}3c3Ij^;Uat$`;PJBxI zcX-6mKQTt9sJ+DwlH_m~yo(D~`xiZ01PVyAP#8Y1GNLgZu%%U5sYQXBdTQK8m%gy> zWG4bbXbAf;cM@t!ny?I=$d$3H+6<#GU252EfW!x1%*EE)ueG|&tv?ej^G?^j0A^8i zERO=3ySyLj9oL42`x$S4-hXbr9cmih?()?x67CZwvT$d8BWbA{xw^uaM*JDJ)MX5+ zQyVCYg~qV#mdNu6YaA-z9dsdfPr&*upM~We4{Q(QDA6frw$DY3Z$-no(wEIy^aWdY z4E^AjU@oN>ldqr8&-3vu*(HtA-_z!#Np?l#tjE%*^49_zW`j$Ana?*XaF`@YJV_Pe zzi}>J3{Vzu$V&I@E>sRh>IHdP-|^-#ooZERwteKxQzhFuj$#};Xb2n>3l8n&y*4}e zc3oB`W`KQYuXT4`;T|qF6tktl9g-9AMJ*t!(^)x1S~Lo(@Me3i2f>8mL_^Gt%&sZ+ zwYG-f{q|UA;iEf$L#eC;6-~jCVxRn>K$y>x{-Q)d4}Nuk2u{S$rU16u4&_@~2;_9M zwHT`Oy%lH*!;YaQt&3*@F+z2X+gu8-O^BX_>9K9Hk*RG;Z`%sJB97i>06*u46lmKx zYO;mxfYi$kLD~zeMO^~*#xX|w&njpM;l7%_@}R~_suSVH5+GJyONn)G#r z0(z{M`GidCZ(bQ9_oT7Sf|bsCwd+_v1wzXN^*VJRDK{j9!!^GnOzu5$C1y=~Nav`6 z2FeIiBk^~vs;K5aWs)sSAu6yz;MVA7rlMbM7x>eWeJ~Gw8w789fF1=8u`Mu1gEd$i zn{=UuslqOQnL`%B$XA0-gTDDZDT*rhx{3*Qskc^KZX80+r4)j?$D14OBUcR~MWEJX z&t&J(+`P;jVZvn;bICBO)PjXOxfJK8SoaI{a7v%5mq2?}f${zE&qzp9Mt+R~86>PM zB|h*eF9L0cc4zfXcZ=!kLzd_3*&!PhhXL>n4b|0uX~IMJM#7ieNk=$HhNIcAx`|&d zc|24EI9TV1F9lsDZe<{rU!(AIrL;8rI?21T9#p&CDcNDOTyIj_-V~zrb)%F`z3_e=FWwOD z&6EFxV@iiNGI6t|cW#m8Qb8?TvK=$gd-VW<(>QYPNZ4zq%r;Zf6K_t-A756!o}UmY z&}Q=>J>YR9Q!tyZ+$OX?^4nq6V*W5FCMZ&Kb$>#}65pkhWAAlGd2%;-GY~-4Tk&;& zY6#nXYkiAN-@deG15j!BBrIz=^4j$vN6hY23J#aAffW^gG06|%PjHYXeusASsa^KbQt7^a-g`$G1Av;$3a#K~ zI%kIsYt>NLNj*rec>LY2SENaM?tKM+UVeq$stFa#QZnqDd!y8&SG_q28wt$jKYKE4 zJE&A7*>dm9=vdW1(api z7(%PZCFDijTsm!EFI*>{M*VTO2z=VgLmCx6R? z`{o2!oQsbkAB^a2y$RrNfT}n19}Pv!akY1>@t{f1ke-GzFZrEv)D<;mS(>dsu2KzYD3K6Waz6@t~$v@3#1 zCPBA2BF{jtm#9p^ToyYdq9@Z2-E5DRZ)+~BqOKLC8ORQz6HK~)9C_-CY$ooX=uH7G zCHbdHKmt5VB8k!3HKacB6fzROoicuUZU?=5cMp6Foo~{J25X#>m1C<13D_7!S%#}E zNzx5BTjz%Xv?QX)woRB*r>sV+Jg!WauJotdOXT;LLj30p{$4}%Q&fodZB-lD9?*j< z$<9IO^Mm*p+N@H49uudt2cI_p7SDEZ(G4D2oSIp!j#v4J24QkdAuMlUw?{z6P6QQ^%=7E^BQ3{)llCOr$p5f2y{63pt8z^;8 z3x~A$LFqEG5R!j$tHA8Jy!+tRH!8dfyvOgNoq59`X^gfj zNKlTQmbLHrls*+44?55M9Qf2kDgtL7jGS&jti2XW&Bo!5QDW%JD+ zf2_=F@{+fIORij)g*iN?-Sb8YLw}9A(8#m&gK7;z_|PXk)x>T>sW+voRvI`L(FX=f zfNL|uJVm46{P*fq8g)vo^4zgi@bqda^T)bQ1!<3iIzRg`PjnoCzU?)OM92kEH;X!9 zD)(22<5G~ClDWs1&mYcb2rZ|OgM$Q5n?og?Mz`~wRJC-BjJiQ znbIGB)5%Ws<yA-f^DuNbqFh;-pdDxTf$- z+WzkvkIzWFsvuV@{0uEncFq&W6Vj}yr_@&kJ9NaSv z^(Hman~x88c^10`lWrN-ig{HIhh@FLViR_Mn{9`OgZh5i{&OL$=Pjgh9vKh*T)rJ* z(n=Vfh5HiOD@6EP?p-Ma9T87;eZPy)EU1)B8NzCXJ_@m~txJ@|HRXv2n|_i9KC5I5R_^MmAc|UX^%Yt1_Uv2*rj+-o~y~(yF*-M4?XywqI3$9pc^- zl;!%*&~?6V%(!bP_`w{_|4JR72HBwHC*O_>j9iVi$agG{vbtbNS{CVH{_$4q6;(&5 zn391{HX1Z7=b32ynF1dj2|TF|3>}7I)Ns7zEA&IuM7c&i%@FcCkA=O=GI|n6Bd2UGUCt#!x zUC+wmx^bjTQpM)GmYFIJ*Jw@OuYJAyJy*qWSek$-vXLa6#N+P}cVx4WvhcGyyTvnE z`0`W-rUjB!&Br7UX@X))qq6#h0qSt9Hvo#unO1a5)KOj4_X?J!I*hx2L4N8^&z{Dd z07VrY>5{ogeiB}oXd-=>k||sr2%M-;5zc`4wT&rS0>s<&I3c8rp5Ue-2^s6KT(oUx zY$xm>kJTi^J*IA<<;nS~s+g(u|r0nuK$= zWlbSO)McoX1YTg<<4<9KfNmfN9?ZZDsURY~ZLOM8_P$Hw3Q;mo&-QJ;iy3;XOjEKv zk8{|hAd?Bj=lO^&W^-Tmjij`rk-~v(a_N#J^oo5Nb4BN=SF@yVwKbo7AFmslnss^` zq79G&W*4Ze#|Fq`zMMrV%e=r3jm3}}-Ze(?AB5G8|L~9dCfDqLmV;UwsJ}{qNV)W? z^z{mjxTSC)XNo|GI^Gj;+sR0E*M&$z1zrY1s&RRJ03%k4sK06C`$JoMZOD2>+8?oS zP7qB+6e~sxlOP>$>lGt*A6qCl;!2}d8d=-yC;!bFvfcW}oS!o)-NVP;pK{?OtCG(I z#~q9h43GjBEsvCcZJ>=ZnoiTU9d7TDD|lQzS1Fx-B&}U0x+0qUnmYE-b9Q<9kv*;H z&t=>b-gX|NYBE$nesRgB+q2@6`H}raIkb0$w$c!&9C%19rS;|6aS{$ksND5nvzJkt zFMR8w*DE+PG)?B69#yR7iQ8f)1PRKd*R}!P=7?CdCslxdlE$~@Ms`8G%C|?G!tHig za`Cq~j5F*ZH^f%k3o;_B9|O%Nf}d=f)tHXbem=R;1Ps_QVbF}JZ+A-?M-udC>@J8Up$tde%+G?Y$zb=$DSTKMqVh55rQ((`8Y=(lskO^%2f)(TL# z;e&*buLB%^{hoQL1+OI~@qKY0q`t_R;+@f=!E}qX{53yk8C<^mz)>5_j;xd8nP@S) zxoFUa4!V_Vc|iBtPS1~ysk7s03>_!5Lt=@a*L<2012Wl=*UNmr5_ov z=)ScYm*x+(T7H}0)txPJeSufs$K#cc#}7g8)sQcLF@8(A<8CpO(5M`&`whw?iqLT& zIL{MCmNx07-5QNkp{P{0)3m|Y$C9LzGR{ll8>Z$&_eb|OooM=wr}B4v<7fN56Zw7V ztY3dL*!nL4I|&CMja+XQnm-mbnN|nKM179*m67b1(`AQ6hD# z#v{>xjHbVgN@nJDyAyQ59vhPoBIkJRS^ZEj4#CCnwH~hC9};=Ui`@0?^Y?hYcc$G4 z`zmD@6y_Y0%mR9Y>Wx}uEBvm+>oO{F7$Zukd7tNm)PYf9ih3~b0s2hdNC;q5Urg0) zl$3kA_I1d)RJhe`q^;jT?=j*{JofyP>hM;7v66{-DE&(Nm-UcLdvb*6r6Ns)cCV>R zi|-a=#yc?|UF)T?r&0uZFyG#Lt~HmIPeR?lX@?rLxPIXfe#@rc{gIKzg>NN~i;~a=nZ9q4bx!t>zmZ!}=SJ;Z z)*-2aCpv&VvtB_Vrk-9BJ&;4DFWU?M+R_G(v5X=3Gf63Dmy*k^R-HgY2R(vf1+P-! z^9#p#(doW$8pH(6_3=&5oxc>WnU=JF!aM{0K8`bXx%6}XrU7$viDP{a%+NKY<%ho4 z<#%`QNXorJBuZRFklAm57^!Jl2a1a#Le_Kw+LlH;itXV-FAKRtFMeCV%@ZvNxjCQD zt*vig`%V>!J4FuS_G=7^4jv$x<2^wo=f!_g@#Tk&B%f)Qzn-BOkJHF*LY2CIx!2n# zc)Br|O@JmQfJWj^LFn}Pt_G0M>kUGYah>IQQSE!0Os2_DWgj%*_n>HwA!WZLRUhRm zwKhRNS)ponk&Ao9EHs>>{BoL3?4-3G*p2U@U)=)NE=2e3EUT+QKfpHQ4w}>c3!3hJ z&ZHDS8iNvbF%70wNu*wll4_TK><^jQv8zeaPGJqc6Ol!!Gu(Zp7o=C}Z@bo5Y6QyZ z+AKG<=ivf7ILuq5B$_N^SC|&-G@$4V)M2L>NkT#HzE2ED;qR21C9x;PA+M@#kaUou z)nI`QUfr|T=j`p%dWemSE+@~=I$NAZvA9xxhG`yM(ZSG~nLbf8Z{r((2Esz5MP6&p zqjAY1>5-;{?5|!6J@O4{89qP_3C$JqzL90|#hGc)Bllj!hCgH1T=wd}7;@c_N;iid zUCIyrsj^W#Oegs++y*pjyxdmqA2)5%a-=>*0ML|o|Dt5T#E5`w(g7kK0 zdlbeNk$6OTXld@)ZSo3#AJxe)sJ+trUBJ5^Ud}$DLB4st3Ul@9n2`m10p_K1cI`#o zqU>j}^XKYFY`uc`ar3%$W=)F;k8Q58h zcY2P*uI!wue8wM@bL(c1C-s3u_)#A^k*Kx)@nbq-@?)B6NWJcV>biht*IPa!n4skq zVN?2Rs?8dN6Q#CQF?CMf_qV}ab&%1endCk5z3Fup2O5X%YdZ!eCE9)Pa4WR6ZzusD z+~LY^59qKXKO}628el1rIaT!Ncohf~yr;%>`phqCCM!;8#2g;zi^ymVfaLPh8?pWI zdh{tWU7myB%~+s+JR|i$x@9I5n-Q@JBKu87j6~F ziO!Dp5M!;>5Qd~;+=71UpjgDWEJ_Rr{R=iK0o9hhZ+?5wmIhlS+lQma)&6+{6w3qN zW`z#!Qz664HQl1f z8)f_aCv9b}QYN$htqKAWvi*h62ciZ9mAL!zNR_MNP5e|YtE2OwZOpKH>h#UpT`0QE zm^lEHBV?O#88Hfz85TrRKj}LpN&c8plED-hrO(q+?bw}HJ7)H`cb0t;i=L3;O)~7N zpl`c~qX9dA45O%)x;Wz0CNkU(YP}z$FnzX>5yFH|H}N*{Xg};nDs|3@19^ z_Ms^m>Rm%}ATl?%yJR1l3}wi z3fO!@SgIG~9diSeBLNiL@6JM4RX+=rbR0bR2TQYTWlHrEApX3buRX@SE-=B3 z01crbiiS5Wd{d&wyGMEFUE0jZ_IYT06>w)xZDZ^LiMnlNhfYVzBn-!yRl9+>?8iuI z`&n&&pA+;wwt16lXU}n$Dtrsq03vCAK1f#uUWW{M5amwD+r@jn0GT3QygQrA&N4OJ zklxo{$zAM8;Fi^8V?PPh7$7PY4Q z;mdGte{KhKj>yoyrlyWGjXDR;0waYUh>Ri%?~3 zz`L!)Tci`LJRHU1T8}{YNffG=AVef&*}~*|_;B^uHOD~_^Kq#uV{D4V0471L&w??3 z;ugGRI~+Jx3CUP$*TodW&_*P|Ws&xC9E^2myGvnO5+?m`YqJ4(C(y-Xynx=Mu;U9K zNjx2AE@(4hO)vf*$?+`lxI4u?Rnq%TIZxhe+Fmpg?Clc*1bCx;F-3T}rWcfNui=e2 zX{N%N1i9%r(v$L^Q=|mLQ`m=vm*3@o4m%D`go{-K2AZM33&4j2orgJaf7pdl4XWg3 zx{?q78Q-G0pI|MC^NGku1N#FLQ&N!3T+^PKNC8YsHwE|HgvuE6P82CKCR>!b{=PC$ ziqH_N$_=$si~>6(Kr6hPZF+PvGlo+u4#wf5#yBKnDGq*3bK-pj9BJSPjnZj)cxt=ey)f-R z_}-zmTK0NLLhxQcBZf{{+4zMz4V9tt!Exw}aQjQwz%)7HW%IER3to zd93xkb4E285ldIxg+>MNAA_!AcoQm+5|+-QqMn2|{HIw+2%^$3Cj-5s;x%;xN=`&m zzt>PwOve?NPld75yu;@S$1I#e-rjC5K(yd4_I*IihoQp=0ct4B){eC+@y5O;BHx91Eqh)psQ zRZ59J+jzg^Ma}%W6F3KI2?qFs|N9$5XXG0*SUzD%)Xjun?0{*^6W)n%RKL~cX|7+! zFp+or`F@Vxyii%q;g!^XxSESw<#NNb-3cyJ+i-sn9s;vOz`%IfP#oWqylHc%m`0^r zvVB!RC}IjVZ9fx4CySiYrauq4$G9{f|-@QvuwJZcQ3Ji%6roAG{5D&G~R z$4y&U(1cV{&sT_!$tNCf1T@zAz5yhQwzn2nqKp>q2?~vHhB$I+VhHCbeJAWx77x^) zRsnkt*Iq$kLiHto9(4(;>Q*tx)0W&<#C?@YevaSGqdzt3rzDZ|FTIhcrafeni(5b#SKpTyBDX1@1@ktJUSwwa2t(PfAh15&A(LdUi(8lcncYh? zLC*Ta{=vBIA?ZQ%mgT3pi4nh;0x_XCIwk4DiQiiaAa}xlRbzQSR(2{j8^ZKf&hK`^jg@7a_^~yy$d4X-gA&7uLB-QbCs$kJEU~eKn z?c;1ZV=BVr5?$(e(QGLsLYY;Nt@5;IyIQl8-1k}%$kSL_^pei9#FgAN2hZCdT(OIb zH0etpBvvecIST@bk8>&NAH0LApHr2!(b~5IOg*FM0#+v<^xM&)F@$X@Z``C0klHHk z^rnyC%&u-hJ4s#%ZE(^jZg)5 zCJ3WT<4O+g2UGpLWENO~PL+#q=i3(ien$o7B2-y_Z~F*at`BqYxR&}YVn;sE0Zx|4 z`uiQd_vM({{^R?>hbnB){Q;GhEY#U#Oi>?@o@|r&lIbUb1qcd2?apw0BPoEZs4AB( zHgzh(-4X;cCGVZ5NPK+XBhRVj6YWjY>-nY^XRiowa5a2CPZi6foZT$j#C=N zSLjy@A(?||9n&Q_%dI@Oaz!m=F!TZ3KuUQE4zoVjm z4`0dt-se9*ra)4eDq!@nC?o9|KS@$2Fu3GRc3c+aS>aVuuB7r_hxitn97Z*(cmx(g zpvcPDn9RFLQ>E?ZrVG*@4^&e`O8dU57<|?wr2F~)r2LBhZ6POUNbSV?g!gB%PI_!O z)(yPybo=w&wG3GD8{xc;tnNvwNyi(1UeDZ~sC176y}2qpIsOGPpCt^5#gz$>KqQ;` zQ0deBdYu$5OhTatz2lyx9{Gsd2S3zOcg^adWG;kKvI2puQ^|bnIYMDFN)}7`^!t@T zHEdRT63!>BJu78y$AVE;=1w~P7j>Z~hn5#6T3^I#a7POo`$Z!H!`Hr(Ipk)4bUNPd z@sp3_N5=aJ5I{rfKtAy?Xj7UxrWd3FZH$GL zwp}||C9Csl)k-3+4dk&FZuEaV!fX!W&%JMk(zW;OG~U4ds(AO-9ap4G`UyEKA39cc zKuc8sLYQ5vOd^}4KYAp?x}ZgWH;WhwN-KaB$X7yrV{yM7q@PS;;bUGd&xX+$Ugurq zliwOsBNY{;r|%Qlb?C4VAA;1aVY5&Q-KlQOr4mV{c@o4&HpRi@I=<3>;*~kh752qs z1Me{Y`KC<6Bh~{nDcIPkqhxWz6t45LrS8U0i=qksjq&7Bk~;9odpN_gn~)k?j10;- z;>$~9@D7Zjz~BOm4m5&KA>om!cJT9QSNu3ns+~_8TC@%7rSO&SYpXEK7Q_L^SM*k) zvN9XeTKffs1K3!m-$}@So+qjTzVVIvbYB!mYQ8*Mtl98j#p~A^$gbMdH%kK^5cAF# zV#+KwkxLu{ACR403o|QCKicGC2z&K+KCM<7H=$XpBH4q8F(FU3h&~NqOiN58+uTsR zzqC-(E@v|`^nwMYI}myqE2+=#WU4pw^!qnfMnN4wc_w-Jkc}6AU0uP*-q1I4w;_9# zW>qG@xy6jmZpDu7S%#ZIRR}&hUwc@$y-xM~=rzDkYwBo1I5{{qfGEQiDzoyTE>i)| zJd$1kGhHkRbBR0i>FqU5jalJ-V9*6;$0_L;#jTN(mP2&WFp6?0 zrzjaSCoaD~K*@-IpRCIib1w;m$`moNIQFR(k#IBE$TjbjZqb!T+x?Vvig}#8gC1UhmPqV?aWj4l|TwzjP&V`{gA9TWhSGXe)@DKNvJh(Y+DGG$;ori&OYShjNcUU}{q(hZ=XyCxoG}za@!#o_W6%%t}UiF8y(wsI&)`H^0GU@=0>B_a9jf!EPSMUX8y@)eQY2M##2k?sWz`)+KvnY zFYvBKgmQ$@UV9XAKmdp~*bYyc@S}*5z+X)^_`y-$m@G=s`L@K}!?Q26CVukz>yp5? zND{n=l?QsCS0@|npPD}jjzWah=tYWY+SjJMewrbF&Q~OIbdeeOpq9Guv2?>}+5_Wd zQE&u-700}Co$o&Wn6M&Ii`#K?5x{||YpRe{heKN#Kc70k$}ck!=KbwrQqkTE6TVX- z(C_BX(x07m-E&o4P5D;kQDp+d39koW@~l(p-{JtW*-(<{#`$(8%f_I>40O(AGNzW8 z7mV|NDp_^X5iPMc&}<#8ulO2mKFw+~9pT(O^l?B~qrG>RDsjqiV0_Xy9o8teB!TAK zKe}Y|jAi%9ws{3&Al*`jxh;7?et;MjMAkWF_tQ{omhT`|9*bcQ)e#}K3)PG&Jq>w2 z53PTl@(A%~-vQ-keJeg(b`oewHyhRNR-!t8?xIjSql-G6*@F#5`R{5sHOJdLPc=gVkD=rj$533&9wWA@SB8D3WJLSrl&$2!_86HcjDJO5g z6U^?v5vbjSt%7Pw&ZQ>Q80(4@6}>@&VPoyLqWTfc)L0@CT=qpg-@8xBQMOtcq2`u< zR*6e_?Ay(wzWRrK8nFak)8&;`RE!;>L!G?rYu%$bR{DuNeiuGyY5ruAQK~%x{%6s5 zsbxX5%ROmnUylzy&6=!9FQF52rOY)`GBKI%ddwQTBbC21jKhl@CpnC>*lw+z3UgJg zgvX)a-(~_F%CV150w1zgyf*#ab=(YpZC+?g@qR>ojHsvVeU2sNMPh@ndvkn0i?G_7 zOD01|24Ic7?*0uL$g~+yW&4&GUHJvik*Ag5UBMqM*ZkjvU`O$Bm@BL1U}HaZoF0L$P^WgHOF|BHe5EE`PdXu;LBX_*c}P6_u~y=^+Qs# z$lc*AV@Dcq?+ZRkbqKvq0?dKOFTb{Zk0N=bqn$U|75qt zSzGc2J%cS%qQ+fD>p%pufDqkR>%e_IbK?l4Wm1^}Dc+NMe`V{SS4Y8ry=S7k(kWyu z)zn;d`XmohAJE=iq3grh;I%QU5p;F!YQwdjLXA=>$HW)uvyVt4*{oDrz_d*E1o&T*~S_93M^6T8GI_^tUPvEe%x}v8Xud z$VWwGn07#I%xLElhTN2KSJ#%;=40N zmP~ofSLZI;9D{RpTa@+(6inSKeo_uX@E~`YEg;pq7$wtk+cAT4K0k1BGB*J_@gy%1 z-MLxd!f?0sNGIWc;VUqUAj#GT!%w#51Tks!E6y7>%B|`2mK6oFNK*aZTTAltuus47 z-d)yo4|*{YhE9hV7YAK?2c_ztkM+*a|PZZ z_(4iLix3=uUqNJ(7HqMU18Urzz`8LR0x2{aoY^yfZe&)_)o0nqN?ZOA=d0|H!QhvH+S%(@VBOBM^M-DBrReb zz8^Jz<-*8g{7B~!H~MNY>}_uA+19Lb>V$z*Rk4O-l-#4SuO|PDuy*9A$sO?^eRVWq zuzJ3f6m@#sG2rTcK}gkp_N!r`EC+X!eSAxJ&!sWhI)XOg)ECj-H%70Wv^l=8ykcqo z>CTbZl^jJXOs^3xb%VoYX82(5e$U`j;$#Vbqd7`?8Eh|TeFIWJ#SvmlcZ>YSze=$x z>Xpi<3D3iLoH`V@Hi5Bd*;t-dD_XpS9_%RIIy%N5AkCnFXdGt|NjBAWe8_qi?zu6a96x}{4*^pZYoo2@q2m1kIFFV@#cEyYvuA3IhaxSZBjFsns1&4{)@@Zc0;{Qj6czFT$#Lw3>3W7`LK^ zMEc1Y`YB@7#ys zpKUV|%+*|8Y0OI1>3u|FJ3@!zi7|qaS{2-xwEc#9RJONK^U?ml4qb zveXC!yhP&mejQb$1)*?%uW{ez3>Op0z~~vnU7cI{=iLjxXmxG0_c>?b=m;ka#Uo_+ zT@Xvb1L+Z@r?^dA=LS%wyCj9BCuI>68l!Xh#DoUZeZAJZx;Ue6m{6DUu8K&=yu4lZ zMA%27QtnaoT=0t>uE`E~Dgb=%OoYqPrg@XHtcS}_wt+FikkVX#%Ohh_a#s-fk;f$ELlTu7wgkv1dqFUwOz=hIJ_bqA8IYdFt#PqG4}jZ zIDuPtb^?_`!00wKN=}8kPzHX_Jrvhg6wsHwyCrz4-T4T$syZh|o$o|`fRM*FdefHQ zF>!57hO|zZ;9TgAPn?{KLNL@HwRi8a!*TR^TQEu~_*%n%L-N9});-{;+syvzyVx`Ru9?GS@j^2xE+Amcs$J6X#QMmZnFIO7+_37$R znc4k*18=5(>~j&7_w7yFQC5rSk1Cnomn#IZd=}K~)sAAAemmn#=ctm?abj{1l5_Dk zp^cP=#%G)VR2*@cVHfSDc9mvI4q(E zEnK=`nl2zc>2pSHFF$sn&(Vh_ zm0oYfp&_V)=Jxlsi(YR$b;2{ONoNI`K%7O8#a+M`RrreMMj6C!JVYWofv)V7seIb4 z@E?(X1L={on zQ>;eYJgz-bXW##fUm^bq(+Qb7^d|kjPhSsz(feEE&|LYp_@0yc#NqI)FB2wB=NmD_ zQ9&!BzF<1HXMfW0K&XKXwDzrH#NhSC%cjJ~N=2HltdfKHqo;Bnz;vmMVJ@WiSfl|- z2}OeO1Z+eNS^Ew8_QZeI@u?$7iI7RCZs?@BN2YLFL#nG_VijV1gthy$RW2cjrKGh9aeZ3`O zwEW=>h{1N*W0cKfCZ{>I)VWdHtb6O_C<;+;L@HHbEFD!}wkyp9*U!~yvb_(d5!88% zo@ZWJesG_VT=*jHA+BYGvXadFW2ei1xrdrbK^mSz3X>wQ16z58j)fb2IA5E{mg>Ry@?{K`*5BStCDfS&Fdb*I@<|BZ}5AcaC z0o7j3KUZchVsTgRt1txBxi0#guwbM|UYt~$L;MmMJ^jKwlVb~?EIT+3W!IX2Xzfq; zf=+D4Z?X#mN1awRk)D@N5sg)s?JMU1ouXAnG7-QZmK;NPQTLp5EJbxt^GEn!{I;}D z@QzpP6QAGN^!F(XNScg)qFc#+#%OCDx_4$^2P%vu>u zBHtX6H}kjzHSyT#@Fx@1Sy3&2$}Dd{atknEBd*{v23$~9zm+p!T@P!(sMUoEpZGp{ zC5?#G`z}UzVOFPp;x#1mq+rI^jE{Cl9@&De1lN$}A=m+`yC`(?Ee*si<}s;GRo`+R z$Ey4~5XMQ)DKdtV#FdNd>ilX#hRatHmXamEig1cr1#uxzp)h|Pq&nJvA>(X~6T+Rv zu23OTax%kCH%NS4rBh6$L6A^#Gf}pbVj9yiK0@k@PTD+>#m^8Dj8ut{&%&(W;g@*h zE6G4{w_u$bd5E4Ve?Dhhipm~Uet>W)86eLD6i~eiPC__K(j(E1)FE@5jWWB{cEwl9 zCZ5a{uT}Utdi!o|ccmGBp0wQRC??ILxH>ixF6S%yFio|rkV9>S1AFuce57G^qmsY+ zU152+l2v0XV?xMJa|Cs33MMb}y-A0x3XJw-icU5)fEpja94Ip@Z9IIn9{UX0y=(DO z^^SdC6$P@|yc-fP@fLco{Bt_Tti~zphVb$Fx@4SpadQPu$R`hf*T#HScwdNeqs?o@ zPb6tlMioR7HA~+HanqVxW^GRBUXi3W7}n^zF~@-zkdA__NGd#?ChPge>QJ|LOqkR@ zFopPxhE`XZ(4sJR`L}<+=;mx*x30VBaC}tKh5laGX}wC|*l}*&=7`NCFMyGRYK`V8 zCN)6=p`iJ_^QTyUy(s1#<5zZjrLZRSncf=(gw^1kc5D3TP7hVblmV#w6r!NeFI+Qy z3xT=B`Dd=&b|o!_Xl#fX8zPBJN`Wvue(2G6($H7URyh+yBx|y8bY{DEyA`%5i3-ZI zkyTPp3T#bJx>O+^G9i=~MkxF_n+GT`G^TAEz9h@#nSQN*NNzq|GfNh(sp`gf?~!hQo4K$haMy2nMjrUq_mJ03^6rfnBa>c^o2EwTBS3>@7#8d`eXcL z?_RAxl1fH@V}ABa`8KD)$@pH}d@yvUo~W?2%|u8(2+fk18#HK7I{kuYAUtT-r&$7RvE;9_HgG zW{k9~pcXQ@MU6N0CH?+loN>84#ET~j+(gs%dWnd$_Ne2^uA+)1G7c|(5S*~4e5D_N z*K*EFQhhUI6p3`aR66yFZde9=J{2&XqmnDzF)^m*5T7r3Q$dkFS;IAGWoOw{>zHSg z-Y;=~d-#F)w)m2Hx^G*lv)uGa^YpQ*8fh5}ALCly=K4P^sVRCqT=l|R)0|xgS-*^& zQJJPF)Z0~0qDkMLb2Ae#tc64g&aI2dgNVc)3bPMvd^Ki>M#(ky7ZgU(ye4SouJ3B*Eq|xLZ zYYmV_Nvez_^2W!3L`Y)2Oly~!n|~~_rIpA?hNF6&8X-XV6E4qXTmIc5MWX`O%=!F( z*o==`D>?VB4<>&J%)vj}B4e_xooxFX>q?3>M zPQFcilnI78o|hM;8W0Ig-JJ8NCYPK#5H?CTcNn2t;jiH;>ZzD>f1G+6BCYm8qUvHN zgynn-1oWz(W7a-;TQJeuN>m=Q0)wDwewTK8=swDV9TlJzT*0#83>s1Ip-hw=G;rdKdN zKAyJ)sDHi|A)4=uqy@H|L^bK={QOO-Ji96*A4Z>rnqw3( z-jzL?tg|`{HKv-LV`jgZ368+>+rXX44o@J|%4(S*%us7&_2o(5^5WK_{>U$CY=hu0 ziMc72eE@YqM*U6V7QNG1*5LE5H}7~W3ql(raJMPQU$_GwQryO<-oH_-9rD^ul<3=*xc63s=A@njHGC#7j znWeqOm$8SI(vouubGB)pSh)7?sg2ezYWVWB=t#wwGC1^ts`Weyk-~o-l83V9uVdes zYn5@K;=|R*S~?QJh0q&+%4ncbylufcB9Y&r=3*7Q(|~xsf!X@X$qjh!T(}Q~(RV9^ znw~VVICKn~UZl90rl$Uu1J+JyCBs424Ch&SQhWQZi)J7RCYDPLX|c$`FbFTF7Otv0JTd4(ohHUYN~03$y1DJs`G9@X z4j6f2In`lq^x&sn>NQkV1%x&NA2?I1x)=)QM2fL4+Y`dtSKSc!{Fs0oI#GQZEZDfw znHQjjw{j|KH+es{x##_>uw#v!=gX^t{fJEe`xopP9p=LO<>6A~x(-c2{P~2(_T3{$NcGJ9h5Lk299h2xZOY~{}*nH?&FzbXllcbYhv8K z5zV&O`8(g@MuSE5?DU@ih+dVx;7Zq)#tYymahg1TKsiM+0Hb(CW#KoF*up~&7|8u* z-To?$W7a`=&+wHzCPvhUgKOVjuG3rZLexNCF#Hw`OU-2(miJ8)UcnGcXn3#{#a>wI zwBFcRfga>Dc*`NXuqIdcZHB|()&9}D6wf0KF9rj6Nq#1Q!3#`*N+i(z2mS@9xfB3) z_@ySgND#dl^o-|f{P$mq_{IM49b7Fb3Oo^4oKX3yD(Z#rc6u?fR3y&S2IgK9gp7;H z%0xym_SI}PcknZ2iy6sLd^NDC4ZKYGKX?c)tx&{*gmngY(V;t@#L0_h2HdV0+1~Hb zKnY*+72np@;|d+_M(9|3Y$oEi9Bly7_rV7ucQ6iyUcaY|88b=57B{U})`EK-aS56g zd7mGbcTcGH^?7T{?N-brm9fRW(_Bqj>&@W^MoN72RI7pjwrGzftt&k0XiDzKsQ|Q& zVICP_JuecBBgJ!qzh^uecQqi&r3NVVWE@?GH> zkx?GhrXmQdiv7wy!$vNTG8dp$8P?LQ-~xO)UoNRZrhH;vxi2t?q52i^>&a^RO)-%` zwY3$l8NKAEp{P^gOCL^t6gU|Z^{Fbj#Qx8^4lX}(#6(RV z0)1i$cEV@j)zV4w3=K;hd+D8sA$6~tw3NI*hr=`see1>^%_L?}wE*CRSMTc^U*^AK z?*%hy%W_roBfpM zfBh7+VIWHaocP2X+lzD#qhvt#-^Y0l9Exu`o$>dw2R^~qvhvBrYx`l+n?sG}tkPY5 zj2KQ~L^dDkr#0x7O4$JfiUk2S96p;92>erB8oZxe1z8dzPR|X(pHxad^yjd%2}CIY z=+0C>JQ63pRNEk=OldIZF<|r1OaVdBPQ|K8e5jZ#e81?T?EfOMO=4Op=yeEVo0A-s zNlf7>)`v)bz0xp(e*MnFT&9D04Rn2>XzlgbcZTVPb;a6xhJpcg{+*w}d{ay&xj<~# zY)sI{!g>ZiTIicT)De=k_fU;-D2UMXhYZg$T7WY4ht5x>(I~}%rSl=_eaU;0vmOjS zgWIf?U7@xD_-7EqIa$3LV$snA?m`W(O^^eCL+@I90Y4@2zSCp=wEYqAr;cq=mr(*yuqc)d-gPYk~N*JqR(-An#^50n@fxcgKh2R}J9K6DD>g1)ZxPkQUJ z)_jV*I+9)h4YDh+34&qga}##_jlWgpw8+9_3Sam5ma5RsgS2^IjNw!?9A<)rjuEZ4 zSXUNI3#*D6=40oPpP#5&s|B*4AIe8N=1l_dsX%3WEF-{8sAt7<%Pb4nq?1D8^=F3U zB}m%BL4Z#NIHf)gcWHyr18s*`MX6+)dnonRVhrj-(aqYt-m!5$NxkFj+fd%uGEG@;n9T+Vq zio+rh`R_cMI?Wnw4n)#{!?Gk37V(~-R9CKSWDtNgee|S@)KPY8!p`JR)DWD6@5x&^ z2XjXO?3qnP=;T->2}_N4V_ypQ<|n>-<;Su?eH#gH_3%W}vY|CXhy973WLn1_{yiSw z3YOg2qFZDOi_ZkPY1yDrSE^c~eETEM2metWe?C~quuN3g2$xO=o5^Mk=P6rJ?glSB z2M@3cCAMpbWbFL(tAeCh6p2PRJ_D+<-IcDjLExn8Qo8?(BugOKYI$NA)T6C&7IBOz z?A`UbBfWj!8#RLvzn?P?s$=NIeID7fas_yoX9?+Fv8uP7S#k3u$gH>9x0;k0e{HM+ zA?&e5MRoQ3f^pqq!6mwEEdLvkyVw`p8w}9MTl8K4Q&cvwN~U4VNeF*Z?r@p3;QpL0 zug8uusTg?osxT3kw%K$(HpY%M0e%dU;#FOUu@77ec4@{=m7ZR2I(_|9u=9o;-w$JX zK$stu>FL5JOYRcDs8i8+=K@4*VUzMMna)XcQN)hT$31KTJa4`) zn@T<;Cxo*sK#@Kx3mmLvFE;XP=?o)SZNJh?i3x|ZpIM{rG#2(~`WGTS+Z!$pr>%vhyiqcnV9wlaRm2O%)|hS`ghCWlHIh&;qIbN3{BpL z?NvWXAaK9^Zoe)~Ri@E!_Ugb&0TV424fRaUZ5l6%wm{i|W0KB=wn#4@E@?))LDaL0 zAKUt%^DC#{UddTBVkl8$pFZSuWV1N)Pyf)1k{#Du(~{Y&2OPcNllEMVJHYEd2uf+o zK2|7$v*P0{w~yzlQnc-GVIB3DF&gEhOez@gCmRZN(q`eMZlT0@4qchs@s|cy z=8VkeOquG>)?(XeY96vi6@bKBViTsW>79lucgNrZqQ9*~OzRbHZ9WXu!x;4WLc4g; zW+n~_uCPG0oVC#~;|cp}BgnU(VStNlTa(K9aojqwNRk`8QUjMCA=rRXl&@xqr;r`p zaWNlt%0R)U053n)R1^uDcKGSC-u}wA>Ej}<=DwH$<7_lb;Q7(n7@+Epp+O>vd^7(o zKdy>h(osN5_N@0&Tx?&+R^D=Tq zv_^EtySMSj_u5}Ex?3yd_Unn|0qZUSyDx~pBYz70XuBQVC38&3$tQ+Zm{pMpErtoX zq~-X^rY$m#ozw0wg6?ehj~Agy2vLX&l(Ag9<~3$xnqN!F+5m5;5)g-*UL3~QUwdfR zB_#2WDdyQ6(?P&GR=?L;kadTiFS(9r~;iKT|{nJBn3H878 zQ1>a29EhfWA<~b=XTiyL&IdadPcB?#!IJT%D1m6RY5{Wm4Rj{y`+{&ljxXtFAG@tf z>BETVh4@H^jbZz(XlbQwBgyaQ*wTZOFpV~wZR)xI*)%QA0gYO8lj=-#H$Niw zjJ|)T0A6+Am-|*zeV^zm(Y6q}tn+gXbYjI1b;oG&XZ@g9*Ywe*CApyZ$DDDn#ryMV znBmy}0suB!{i(gON~M&C%@RBp7r=_EQ=n;BEXS1MmGpo=tf@{7AJfHdif8V@;v*_X zTUL{FWM%(}4f(1Wn}2h|@9Okg;%!Z)ky49uq7wA&$Zv*kPD3oJZdDMh@Bc7CEn(ku z+y{9*b<88 zhpxPJ<={dc1pWZUepgaqDkq`Mt*)6VRRa8q->l(70G@X8>E2XSXN!*I_j2421Bs^b zZxv1QKmrlg20}H8R*wX${E4O-{7qTcyCMcUB$)k)6-PZ8@2#gRMdg=(IS5I&4#pQj z7^E^M&I<2@HG$sM3FTV+{%OQD7N$6PrW7W6DbRtB2i#!Vy#Ji4`??5F*{?Mnv4ErK zF>OLt3!o6SZ1%uD_NaH!H2JEmwbD|D34|!XloTo>vVN%IEHm6dxjUeSE8Q)7`Wn7F zVrQ%1qQpC`d?fBGvWrVu8PP1iyaR)@X+t53g8P(>j3lE=q}IFxDNqRejC07eMwOS#6(!vmy`8PyvSy1_8 zHnG+)Z1|Vrygw1?8$zw{ksC)Z#SbTPf(^BMp<70#=3QqIzvs%8R6(XY_+k0Mus$CD zAJN7k{u2=tV-ZugdcSh^39lT@$aKis^;l>dTYE3-`+@Cx3j}0MEJK)V1wgh)i-Eq= zG#ne}`N3iY?v+w+Of|+`Vd&VOKmTOdeg0y4x?1_TjYa(PZ-~xe&t;1L&b{#gm#06Bt&pya|dI)n1H2KX6q3xy6fsMXQ=O$Mn8&zSo1Xe$Fxs=jx7 z6fIysj+^~dr;SN5JQA2e50I?SJr2xxT$Rpl zuQoOO#a~Klq44<>ElB&)QQ@2fv&x(FSJ_<}B`@-HuUO?855p}OD~Ab|rZHfPBkVR0 zKVg?FmcHahiFdRxq(fls9~6^e6CzpClMF>n4jck4PFzn6>x{)Qb+!~^j8L% z1nhEPxDga2Z{2Yc8*LKAen2Le^DC+jcrs2B%ziV2I+`NWl=!iP}k| z&37f^lON)oajO1XH1=>X07)?1a0g!5EA9YgMUYLj%qL!-8bKqrvrHnks^;3X4EN~3;rw$^)ENyarP^uWUWjy4+zPU) zj)ckLJ5lD^- zl~2&p?LLWZfnfj4)Uu*V-(B}q53-G&FE3CxB8{_etkJNs1bF5&4?SNBH=-A@_dU** zhxqqNGHL$XkQKuBoFj5u8oW3@#W$gpW78SuVZ2k`dC=f^0p|+}^6#8x*sVMoszGTS zEtyn!1K5n}pF0D|(fUVHp52~hAL`^l+_nw<L7tnk!2U>C81|e%L;Y*B23wu=BXpzPdfwaGa-Gl@Dja{dbI=iz-5B$AE6;# zn!zP4q~xF$X!4*S@~G$b&s7E2yxLq){5UuG3I7_0RX)GhC7!K4$2AGvWu)`8`CMr3 z0W`NKb7e*VACjIqK#g{AUl~$7W-8i21RpGg6IRUXk5I}x=bGI(jT0Bgs%JC07jA^e zb(C_*;$SSs11zoZ!o@QLaSFPl1Ju<`WQxnn%R+@&zx_?e?4V_@tB@kyg65QIAL~ww zpV3BhTd#^`>vSiJ(>U|-eD7zn9=rvGfQA;ucC$T(Jom;YiI+Z#`{3RO<^5@TVB``; z3?ZQjP#{v2k8LIJuT(Jexk4mUO${9g3qsEmRS%+$BLC>Z1<*#{HGc8|7SO5YcNFv= zk!DWCN7)2e1PSGEK@X=GBhYOENh5k6nu&h+86oe{wP(42`Row8xGPtqt_)0NK=O7- zV^=&Mg5iJDf-s8*Oxo5=XX{Se8md>YeYK@pMsYOeFLJRI6PgY@yhG3H{Nmq}$$u>9 zLy@Wk*hd|#>IW^;2Y3vpa1dvb{2oYRPwCQ13B`s< z_Gm*}0Fd!9Vxq%+WK;G(y!6LGBV52TETqftC9#319xSK{^#@$q*i8cl0160|+#;@B z3iXj7Z89v1*IDUXr1FtkaMSAZ&mT?bgsctCi14$8hYk{#J6)$YcOc-4cC{nUQz5wh zv>>sRquO&LA*H3=4RX^0mh&%ay|CG+w-($QH3t3gA>c8Qvd|n1=cVpVUIL{WU%PZP zdAh$ZFW04c+4gNDa{fPY;t!C6|8T;og_(p8Lm2ic7#%m*Uuom(UMdGvC1U8aY=?lU zP#7g*=OqFLsT9H%nBiUCmQRRf&epe*L_XEGnVXCTH#SrIp@8{YZ^D2f2~u|%fT>ZK z**IAKM?uWN&cXeEM0FcF*~~@_iBbTsJp^XAO!KXsx0jfG7y| zCvAWC@HYbTl=oE;AOeCy+XDu9zXznH!{twSALK#2DZ{{#`=!T=NhNdtk3 zAh9CZ17df_@>c}vqa+)lq=Nthc?%Gl?~Q=cVD<+Y`>*RfcLZEUyobceXXY6k)k?dx z101n&dMgQpn}**FOQGi`7E5qm6TL3+;=y^XPq0@$V4nD|3E5 z`CineKnLKp{0aXz(QBeIL_Pz~e~@7QF0Ns3pFgGhxwL!& z0{--9(O_#rSNRTI07=Pyq|V-zvY$?oZlDvPq^~!iK7(2Szg8ZaS(N`^*RTBVwvj$J zsEQUV`HUd>?<5sv*c|}m&FL`;q)j};A4otzfY`sTj;QZ9*U?32PSEo!td?dA0T}6< zR&R;>JG)_&5Wemk8_BIt(Abh#X(9w@?T7w}Qb?Ex>v`lAkn(At`kOle5Pvra`Ps#$ zZXY!4y|w`${}A$yVZ%KB3<^=N;zwkF$b(s7?ET8KhkmhlWB`zK$~qqbI%@GmOKf8U z*MA~UPQ0f;eZDXeTvY-9F!1gMi!z`roIVARFE*jjrb7r#3gR zbvpF;*o99euZK?}mO#Ad<3BS&J5l4ox0AUgnJDu+vuJ3riHk4{tj&%sX()a1?g(MuiR;k9dsA zd%W#4MgitAHC0{X_&8HYT-2(!wa66+l*J^Ee~ia)WeG}16erZI-9(M!QTb9C6=h9| zXxtFYwTA03^uL*PxR!F*==OFjYRL&*6hGHDDPFyT_qt5Bs*d z=r&`^IZd&*SezE7OR|I1efi13cmcWju0AMEYXQV8*F(x7K0Zq{v&@M>QgTZPbhSrK zDev!filhg`LIr!0P!|H`JEPaJdwWx)K>sPTCSH^oSuk_ebjI-?9K63cA!%DaFoFBE zEIyPNH!&Vy^}9$(3ZN!gETngH)@3eL(RlpC4uy;Ufzm4N@jq)ZQXG>_gP)t69bB@! zRR&;iCL-%)8ObrB5YaFZX)(>MNlY$vSkquo;Bv{zNnN;TD!g9!CeLkRCiK%MSds+v znNO;Wx}&+gqK02`+@8PqjyA|OIr5(zk2b5$-m*B?F)SOYi3%tLb6k__-;SlvfZ@Z= z)}Bmm<3MP}r|^3x*kitu{%pQz9scQwumSiMVbjqxds7%LUL5OmC^Y7KY)s{pfBz_~ zG}$sHk5oEO87pW0F|GeQGH0Y|suF0J`89#$nUw#IBvp7=1-{yRTdlXa?(QS-2zx)O zBg~M(8>21BAV`xlK@D_+TF(#~0b`?X4bc$(VRRsg15SnHgW9eLlwk#Tk{kB;U%YmW zec!gfXn9u!?IxXdxJfK=$$+{OFZXq^=3mS5{6hu&r#~Z8WKgo0pT`-L&)b-F0sYg6 z4#vEm`TK~p)5We`iE>kqvVMAVEYfQX@>q^DF%*3Ygn_Ts@6-i zD`&rZ{$hzfz-N<6D;&8%z<9lo-d<3vqgLQK-^0o-`)Cc4x@InadSRl5GCFxTbD@E{ z^ckU!@9Ag}BZ}GC6&>%c3<_XwTGjRtN{GA$1dF5ODiT>cxQ;mzHGw-?Vg%09HzcV?(rLG7#FO9|-CIT&Cjq`4Aq z6QXXf8azGeEtg9oQ7KBMv+$(*hhchGu0K>mk0*3pt%HKRP%%xgA*2M3mh;UwD2L_7 zsfyiuMx!-*N`8J`zKyvXPA!W99)@U+q7%}irG@KcY25kvqropK>uLApR`pQ2Q;FNG zK3HpJFs|u;F0OpBw*(ka)DkTd*!>gN<#$y?FYW1|L(OUrCB^Uwbf`TqOf^!a?B^x| zNF5fYivC0!{Ne|F`59Jw96Fe}LKX9_I|flZktjTHaq!{pJx@Ditse@EB0oXznD>@I%X~+5gRhCcJB)B7vMnBdPhDb>0B3w z82s{v+zDVSnLA4esFsM((yzF6B0=M_ITT37QsycPoY_<(cbm%rT)egu#)>09&N8;*jwfJ5$<}BU*O>{wQfwdmpr+Zdu@us$JD)wXM*t( zljw)o$N)Bb1JaXi^G&BhmVb;SXL<#`qg1|~1ZOgKfHyzerDcD_&5VdTuAZlRoGo~@ zufXOp({i1mj9#Yw-i>Lt6>X1}^TBs!rN5O?cD(tz07LI|^;EfjL~8ZOc)vH#C=v}P zb2}jR&)oRK1WwFwhuYu?_&r6WyLZE)mkybKv;bp-y(YPPNR)!J1@W~)DJ=Dr9LbCJ zohi1J%N946+D%Sc=yF_|+p!~QQ|8O;yB9(aVJwA=*29PO4yf`%&^oU{KTREXq%?#( zh|lt}0<1XSX8C^Ae_-6t!U&vEeGMRK2-?`hRWi>FnzJSlY9&?oC02U1O0{j`w`FXv zuK{8M9Tya;b}&=(aDiQ06l}2P11<$zIQl|F$I#?%HaQJt-|oh-x3RR{|%XiJ_@bkp%C94QN=a@9xq&zQSfI@9BxFwjAp5q_Q#68 zUlPqZ+qp%3Dg9?`8KU|pWsubSGSCk25umZ9sDH|#N*N4)R5;Y)>fhy2mX#dvK>f&_ z(0A6-WPM)DDFf!q8+j?b!S&Z=?b~++HxqaasU9m_KwcCDz8%*=)nQShn$bj)Gd%7< z_w1;*G*%`f9@=C+)f?3y$AL96iNN-%NRLS5Ifm$YO&tHAD%q&4814pLit!V#9iW;} z81iuVa5)?`K3LdQQSURED^(XkKvsFcFz5Yj>=f14+w~1c;?L~N&R18D3k6Y700k6X z+W3nnmTVR3=47@0IftkvXj!YS*9_$0xum1RR>C}Zx2K#43X_HTh(SHzTTaJ9$-!UU z$!@YV$KXs=>z!l6kvy*fDHQ_Y36Ni<+j4!$=2gwK0s=`hryAShUwWoP%qG&UeSdg6U zwuIN5V&$RUdOA?R0=(V>Tx{xonBgvUqjygVaybcsq`3qVWc(7WTjW&O2NFaAzXl4|p}|>rM$r z>L0(fD`lKn8SvE=QvfBntU%dKvvFS6<3Ho7#z4qS_f1r9A{oV^7&z82jz+2{TOGQqsy`>u;{?KH_F54_^yeWW9N8xg(PQbO_ZI~cI_LmJk_l2 zgN7O5oP>N*mm+o1dm*yuUv|f+#HtE$Fy7)5@;^d}e*34nC4h6;JBf=uE}N^WVD1za zgh`K%eXiDB!bQTG_AL zWDRh=U=bZmny&e&7j9j@EyLOc$%R`EO|i+;;^6|C96N^=^A3c5G=?O_>U*T!MGi<* z<*wLnrHc>>LIBLu&!mNsB>6~3>0o2Z5^IyK@+qA?lzL>}h!$Un%V?MSS=!~_@jcuBDO4iHv@3ey>AYOj*f;*?mcQl@gA{k zR+SypM7J2?EVCG#S=>HE_uf52Cq>ijrlZidXSM#MaR4q&kGdF2-EkBR=5UJmu9Y(| z`kOkk6Un7-LT}?QdIsOM&Z-D*Cl5#&m{+sI@Q-{NED_NCc%|p-Qa>MPX(5NFRT71Q zc<)e)z@~Mp7NHqyT)2B#(Y<%ping_^r-e5@B=(D6Nn56ItWREh(AkEH;qW`2+Pj1> zTG?w?SOJ~3?J_eJ+^cD%!_B15M^E0~wyqmo+o^IIa<$~+Wr7flM>4k?6Hxx^5%gd* zWsA`6rxvGkY20kzY8Id6jXh|m5tExey0b$#j;`lL700B`UE>-g`4l&?U}5d^#ES?? zT8tb=xkat*b;jzAxyHLE+Wb=#)F!o=#@5{v)BwA#((?7tRZT*fJD0Jb;&QVm5x?t1 ze+=!!&~%;d(ty}bdz26z$xV~%Vg-FT%Gbw>2av(EXr5yG&{Ur2>kHKV{j6ks))GCW zzsi<|I* z)&Y0LY<5kRaGxz6p>UU484Bhq$WHs+hRQVFsWk<4E=FSX*G_?l{Mqv|C5;nRWa|W5 zoP1=M0lqyh`gv77Wrs??a+UpE;3}?5R-7zK1g~rU1Lm$HH#aYO5$jJ&YnOSvD{+5z zCn9|wt*Y=jFKOjge!Sf4BLW?FAo-|a$pGtf2ks5DVA&*F%fa9|kVv;2SsqolZn@xP zjJTgCRx>p)QjBCn$<{fVKA5Z}D3ql49%)z-SrMiU#Ifi!uT1ZDs^!p@AaOGt6>Tm8 zLBfB?{7>~8afby)+Vh83D*u^`TPB`udUK8k!t>7u)C6QmQQMDaIK)m9;d(~bm;+M4 zvd4sRv{pMnu&fu44W&1p&$B7bF{9o|n{b5ByoteisObiz$dEtUI~(HKI=&BIOBWrV z4yJFeq75#FYX#0qi(frmV(|?Ci2!xR?P`pLnarvoDw8o4*rbgS3Bkj!yc%9ym?9&* z?CPwPE!dBX7t?2=A=rGg`W~hKWJfEH+EU&jqk z+s^WoczX6{7+K#|Jw9XJpNnTgFtNgZRb6|{4VB-a#4kYgdpae-;nA8Hy&J(JHx^sw zmb4S-I#DE^*qvbD>}weWxhrdU)bYi{nbtsowTU5jwUFExs2D*VXZA6K!2nA}ia(M( zs1HLu(X|3SmF7F*+{qDh2@XC_*sm$<9^QFDwHYq)b&^}Z#Pg18sMG$Zd!8Ki;!+~n zPoA1@6y;hg#$L}-pHNc|{n-UQ54I%A>1(<{6{>xBv}alIo>JSh+8W!x#`~GmsO}+m zTS-(RzbYwxnZU?@ax&i+UI4bZR*2k8=Ke;UrEEXphSFrPa!*r5YLZqkb^tdGHA@}2 z4#f11wD4;CGJaqJ5|^V?cMirM&2oA=^dl3WV^v+vod^LlkAF46B&p$DiUV~| z&w(oq;Sd8Wj_bAoO8#6TFoKuJ@XxDHmSmOE8T9Q`r3DV#^(z=0c7PPys_@&qVd*O8 zOXnS^3U5(^h{p}ggYhWaa{e+Sx%t6*`Ndg#LN5|sso5SAW)o_JGd@i91PQ)0JclJ> zlx?nZv#IlD#rP;c0$%2}B4;cB1%r8cW}aRS$z6A*=uM80Z#Zukeo(omylc3_t9ef{ z2glLM2ma2WTuBc5CBP71_s2Okt_}-f1T*S zX^v9s!-kE*Ypw+jb$lEMI6%RHr`+#=6C=4n_Lb2d0!dL10l=0GO+=bO1870#QV&jj z`eaVw@DbpZ%Nm^|Bw(h@T@H5}lZ@l+R@9&E2}eS6BQfZd_Z-6WFHHCXi>aKj9=M&V z9+|$((|;dL;nc=eiR4gbicr)ZM|7euoi{s{d68Z@tzDV&(O=0#H;jBt zxr63h1BM@{eSbylrO9ab{qoA8atlO(%%0WyQfE%bf5H!iyyzJV*8u|Mg|tb2jW z-wsQ0S;AIYdysX+u?@Y4#m8HfOORL2T3bES8_?Cw8;=@aLtdu7@M8M*ZZ8gm5*G*u zIi3^iisZH~TW7mXr^ieTs(ns2v9rEII+rYJ-KRNJ42I9K*Ane*DcqI^oRfx=Pr{mB z0R8{`BLg3jh5tS2h&`tS2ZNcG{jJVvHOD{daeqW;@{x_o*) z28uXhhFPN;4GD^pluJhtnNl7iD1##60(|LEGV?if4|46|arUEhJrW0`ma46{UP#0~ zPc~f^j1g>e32piIQdA@ztcs~8pEtsWhou*SzxBrX_dm-^5F2o27CNYkn(Zh>GN9m zcJTVw{vF%drg6pAk}&@S2H+$)A;)%MmpBsUU{|Q%&jSRjW1O%M@GboQedY35?T+Dq zv@D@F&TSnaeb`CzCSSoSbsm&*>3L*ZSXXU$@oPB48QQ7+V zC2Pd;Vw6#~?39MRoyXWA+irF>cl!6yQO0C6mHt0;q)aB>oO6x-9jTNkY#W(=OI|a0 zwlaO_f~`a3cAr*JXF!|Ena#!NS^b0omD=tw)2lq=l?Sn^45cEv#m6{O(99HPNG8@< znd{PdVI$bW&)Aoh0o~BzJEVA8?eSzAr}@~?o4u3ZsD2zS(?9%#@O4Ru^csJJ%GBeb zYioTkh9$epQ{#iJur%%%L8FI)m*q#owm>R6MkdNt2vd{ESwJPq9vf@DvV@%qABxth z+-*;tLpPsOw+hYe(*`x?H7oFIANzAj1aO})Mfd!Sfnepa@w}|@um28zX3RHe49#F; z(!xwmeomf6Iw!5)jJ;`uex9p+6Ec$%*N`@+_(@y#Jips=j6Io-g_fVvAxR|HtS9Bg zCsyN|S2C|@l)9ScKuRHGq?o`+o&!kF{kJH`|bVW^4E8 zRg=L{89}6$39?MO$5Xl)6-`x|*Fhx*)VSlp`XT1d zemXuu8%@$p#@#W~d;L1{9Hvn+&a%SAjzghD6NgU@T6Y_daCUrhO~kO1x7PgtnPPWY z7RiI(Jns(okHZEGjQYLkbotoK*gjsKhvL$rWT@lEt`9mNX5BU$R;?RTC%TVGGk(2a zKhHWep9ba8QfStK9vaK0^CI>$iIX6OZI}uH`H7}dl*43F-IvtzxteLFY z`l;4<#|N8}h2k>OSf+>KPKA^JOzb67Ox~;(RBAHh0Y*2S4{0^m=E}(C%_Z73#R>jh9+|Ki3tKyjQoO5DZ6^%ZI!e4SSwc zywpH4)HnAdK6%q%$*~>4508wcfZF~0i>B;G+L#PdZ_2wHVGF{zN}P(;l-+4G@QXAA%HMRrj&bYs2dfvQmkq_j z_Qa0n>hg}OS_f^d-X%{TpNsEnfAcm-P3>fi_nNBf61WpdwsCpCQ#-a8T7o5lep$KX zcrHmppDfh|auXJNH9FE{pJ*9TQinb>s!<-t)@w8}IFj!`Fc4oGmiF9#1-o zXpA7@a6UW^`Qs}9Ik0>-xP_ICu&yG)o1>9qLr_4kWNFed1xImyRw1=-#F$e??D)bU z_n)*yLr*Q$Tnp9)*gSxkL=u_G!4Gnr*)OwEzJeN3WAV8bY_xzzFwTlRdmND{f;v9r zV*kj=9dL*qs))Ca^EejQg@ML&$ClsMh0pqkiN*IjCT|#k8&Yogjw7s6>Bktepi&Sf zbL+kRB{Ac>dh&?rXY_@Q(z8awpEHZ;t*1b*=rx`6wG2#J%ek|X<1fUEnvUJ;r5@XD zpij6?)g)`}bVE-I5z@lop)M=to+siYJ3WSf4UkovQ0WV|S?ro|m(`mMf|2QmsERvQ zg~^AkC+8txX`fCPe@5i9vtezfOg??@e30^uXB)F_C2heF6DykDSK#il0&E*9-4o9J zwbS=fr<&y+!U1=rj+$HGBMHx*S86mYv*q6X?}@t1VQ5GXcU_)Gr7LA!Nr|$1PD7n z5bOOHfvV$rOZmUHemK_KD9xS-hR1bcQp55TUKMF7z^pBwbH!C>88}a{8g#YYn*~_?QZ<|s?Y)$E0(3M26+>J-EP3K{!g`5&15k;%vgs`TX+3I#?Pr+ z$loL=6i+qO&zfEld#v9&WGYx3wsWK17SrwI4lQk4J7ItO3nPrZgP6~~&Phajhm|$; zwi4VqT7rSH`y$VtKdC(Y&ytdC2Os>?S3kX*D6*3 z8dNjZq_8;s%|Gk*26}nP(|dWH;*+VAil#tc3Wo@XyPoZ#~V5 z__nTADtK{0?EycT8~Dc{h`q0Q6!f=htIfP;5I(#XD%C_R$s;!^VVPtfK@&Zo(qzm} zKlT~_Od45!mel}^_g5sU5gE?Gz>*0d(T*8dR=P;OdTf?ee zs@ydYBrEX!%klZ-*E#@q@k2H-LaARFWId4{zv)F!G}a(?AyqVg!ge3sS@@1dcL`MY zt~^+94R{}J3&IL|FgBqt%wta&4UA?cH|Q>|UUo6%X9#tQ*_}=LP0$}OcHz{4B~En-0hdbN|=v<4U+{ z>e>B_g6n>L%`1RWa~ObN3~3kh+{S(c!_533CctNqpH#beHCs|~?*Q(Zg{AE*jOISU zx$o~B>ACvn#J5O^N(uO{mf8E4wELbKL;vDlq-oK1(`-)QpC6GSpb2JE5Vr)&y6cJ!p>90Hm zJ!|`Y5{8kRg4LdY|0=!o1JY9KJ1wSpkM-M5xN_sM(hzIgZ5SuLO_1!WZh3JrDSe{~ z90|sgj-FA~-*2(o{2Par{x5DA-=fP@J%lUVm>x}a&#M~-_hrD6KgzaW7j^5Q#25;$ z_a)USYB6HS=k3%Cx*6J&en-80QFa8R-NS!spPSs_d3e&#Uq0HSqHbRNxF+~q&r#2Mr_p~Ees&LJMQ z@EftxPgVxOmmRjU)jv>SlmPA5yyjfTU(DdUdmWh60VrUU#C|Jk6m~A=|2dCjW@7#C zKJvZ~1Hi__^}puhm?m(gEFBE`XmEE*%|n!}?d|RA000qf5l^XoyO!s1DW|I^kxMF-l1-GZ@g+qR8PI<{@w zdONn$QO8Edb~?6g+jizVbJna`|2pTc>Y{F|_Ooll9=;BWRz%PEVuL`B3`E-5 z7#oW=3vYtXF_F-$K%KxTLH7}eFiqpy|C$2Pk3htMxc{s{nJ__ON&f@DP?xr}a6``w z27`k&r5PE6dj%UKfe)ORxk3HP0bki?4rLlZIzkKy0+|N0 ztVJAI++Q7>U&Mld6tILop{oSt*c7P-a4SE}d!b%@c|aVHu7L3O_4jxYqh;ajKrSv6 zZ0@{D=9NVvBWMpOP!0fdfyYRQg$rb6@d;TxuL1gCmG}e_f*-sp7x9aM5Jo9s2?`{a z|D!_~8J}ha@#xcdJ)5O%VY!0r!bo@3PSJn;2=OrLjnQP1}-ARg_H$Q z%-p+!f0iG7iGOT}=k?$ZAR0YyK+&MsLHm4(KR<)`1cI=XQPa$P=SF@1IN8_$(XB;9 zFhZ<{?kM=Cerv!nd&Umv2545Gjm943gdISZiF<(DiCkO@cxU&g&-m9|%?Vn@n$oJG zr?czS@2Zr55&O%ROr{vJ?Tx)z7^;{VEGo=&|H%rM&zZ&CHMHD zCaLS|2;_bnz7Oo>S_?11@+b&o;+wP`7h5=O@;?0iJL3vy|M;%^h^P71EckYmgv*(l z0?snN*;2~B- z^G*O@qYUJm-T4dUGxDqK*ZdQ40)8*-8}tFB)7m%q9Vids7ig|{;5TR}NY>Q%uRaik zwC`TaFqif(a3SiT5Bxj9b)lZjZzW;Npf7MZ5FX?2u<63x5O49X`~Z*VFZ8eFGCP6% znPcdEMK*>Wmt$i(A7NVDRDcAe!_F0pWi`9CfT>)S|MVZ?E=rDzV@A2OxSnJ zxUi^U;i%If+(5Pz`FXF}Zk*llC!@0P8*vL)fkbn$P0Kd4fELxc+;wvy@P~{joq;#i z;iOce&}cb%4c^NQnFYpO%r5j=#hAwF8KZBBj;!_eO7+3|*ba_o1BrLLT0cVFVFrqPSB}Ns(r)E9IK0MID#IdK%fJ6Et{drNm7V7M;02U zSsQH`UgnNE<9Y16ZYG|MXh+2f5+esJAeMchA{<6}lykcEAEvfp?Ch*d@yTprkbA9b z=K7YkD=Iv8Xo0Js{giCof2P(es~&`H=5q~(AaY3Lr4O8svSFUP{I7XFm4hSFa>yMX z{Lnp2a1UShL;fAWc1ig%@sx0jL7)k3ORtK2Fn)naw36S@wdEu#%JB#MwtoW$EOu)T zi8oO+c5ut}sysHna6|V4f7TdY$g|`#!X=>Iea)+95@e3}mI?Bsp+kj&c2l0Rt7c&l z2iDM#xg#VInp!fZE?}rPN$xo&EiPO3cbg*#Nk^Hdf_e53SvJo-%^1 zOz=d99N3IA;GAbbwLBtnzv63*S8WPLbwmD{H}5c}c-j)rETLXP|-O*e%SAm$qnw&4|Ur;MP z!e}Qi6qL#ys!~caK)c9FOUbL6pr4`)%P=$ZXxopQDK79n zlcL!*w&x?2`r>ntB%%f=Oi~uG-sZJ??kHtsTU}<0i^@GI`^KwS@i~4Z`&Y8npGJL5 zHN~eBHOr8M&LL3kVQIv7f&a}YR}%a$^ogxEHc4w^8CA9f*0k5`t>x));}Y3}hsFZ> zltwSyDrmd>7hf`#*Tgl^f;7SH$q#G2&SkH)(=~mm{67z%bv>oP<4sRxeo=9z;;Sa! zZ|%?S{qtibxo0Y?>NRbonfBd8-g-mphwfUBGmV$@@IcfGWp#^VnoJ}5pJ@kj?=m|@ zN%hM_#>}(dPjK;%9+wZkP^%nJpns~Lkhm1BeP{hK$yM8IIWscUyV^YLywXQNpO$QF zYksk3(5E%s;A7tdareY_!&$P2*OM`)kOrCEaEod2`S@0ms>}-l#zUEZj}!i5CMq}I zL~J|;+iBhRhsV`4#&~`+Dd7c7CD#QJ%n#n|VYdo;J1nKId>F;5Q()}Y1EGDs#QEFvXAQx4&~L2FXk_(^ zes9FG6vNdt)tlmEZxNofq=75)@jt89N00~oOE*MHoKZ=)1(pDf&$`CFoS1m`-i;q) z-#eKEkep|?`ibzM<&Q+c@T#@?B)|269e9sKvfSctu6qYDs?O1pUyocOWV$cJS>08C z{NC?oBIFT2I{T+5) zXD^eP1thI?%#$u8fy(M#$PxAk^J_mvu_>jqCwn+m1eYAGUKII25r6XA%sMdqo=P%dB$MYCg_vRs*45R*g-t>B zbH)=U1L5EFR34~8L(|{O`(QJ;T%djOl+){;Ki{U8zDGZ)R#QR*)hj!%R6Yo@ct(Ax zb^Xf3WZQb-a6SuRMkh4eUQ3W3bM`p~z~$Vx?3aGtgwqY9hX5m?0quPc|J=)*Z;Dqv z*l-pJD^O$9hFWJ`alp=s4N$Aa;=;v&P->QCBfK@A6Z-9l+>Gr>i`@$7iEghnyGj>R ziw{xg4wYGMh-36zM)s@rAA4Mq(ZY;%_f^^my&KkLKSn?V&!N69^xow3{O+ItA4ry! zI+$*YP50Y26R6LMf)`o`E|$B*qo?wnXgSxMCZ!Rz^G4Jqzf_;W;ptfC#h2}|=9_;f z4zTzcbqv8X4R8}ddD-e$(VjS6@R8R_0}{dZt2T@lkXzSlhxOL(9r7vAS<5``CooO0 zT>2_Mf3X%M6lR`_fJ9f{gk|Xgu^D7=4+)vId8R2wwap+joT&e)5cYNk3ue3M!xpT?PM&sPAqpX>Rumm>i1zJDpin zqN+@bo@$W<8&<1amk*;byW}-NwI)ayWs|nJmHACejep%O7|65wM7Uuvtv)RO`BLc$Qy zraw0)cxWi7ml|tmEjDijSPvrUyBNrs3EFyw1KIMKE#h@6PmCofVUa~t@Q%X4OnWv} zL0ImkOH0Q&FKqTG?bjoYv(zy!qT<7OqL7w7Iw%s2x9p=$IlE@AcjSS$BJIa0c0wsz|{By>RhT9+jWuMr0A@`f;fXS4; zX)pC7aSAgV>n@-8je=k*woZ@zj+TPw!=~cIPa3&_C-VWXVk;>m{=Ea?-7X2~w#rdV z5|fbzSkWSSTm&1LzL5yr#SP!UP#CfFNQF2vFs3t?o_Ai@D2R(kIwLO=Z>?X}Kau0f z{P4SySLQPNf@aKs>FrVo`%{D>E%(|)VZOPrE**jj75Av&xg+YxDO_cw_Z^-$lJBGN zCZcg#1x5u>`;R|RkyO|H>NW3SlOR55NZo~M8s*x^qvmcm@(V@ydWG)askj)71~|Iy zcjIA^D^<&t$mAnUHue0Mr|30fv}vIzXt3KV8*f7{FC$X`1JVI|_thM;BC;Nb>Xtt) zWbqVX8$PLW9rf_UH~8 z37Yfpc(;arz9aQ_3~7SEzNq8Z^S2p(sw6Y=7@Hzc_IB)&^PddqG_OnypafhsR*-2 zZxa(9n-B8!hDF=CzCDT|X6UAD0G74PkS2-{2GV5@Tcx=mG|@n1E&4_Wcf0z>C}`;n zp<)lyN$%7^6%_wWaX1ZA`bjL;hR==%6}Z^(z^4F6RP=_*lrgL$tpr>R@CwFg$EV%< zyuN<@Z-s_J_9%M_lxvur%R-}V;b}8ePG&lB3321t1Dzvff6ZSm4R3% z`13G#{{0coTT!Rq`li+oKBhD45qZ3c`9^0AU%v|j10W$Rs1aC*@nIYd?$!Nz9+X$V z+yf#-bc=Vz1cvaz>`6KPUL%^MBM42!F(jf#Y&zx3RqMf+428t za92@6api4p=o7L9V(NDKO+MzhE74;3xb=UAVLA0$T`)3$Okq4?*EOv$w&k_I*iXff zL=NAi*v^kHtF}(g6L)&QEIDD5wcGPnDFTN&w%VE z3MqPj<-5B_6G63;Y^(;zso*tof7Qr3uaa8-E#a&#+6OIFk6-iS!X=SC4#m2b+qsFH z2WdC*+EJ}}YyZZ6(u+P_yTZ)xms9l5DdcF_5HMJ-eF7wz(D&bsXfK|x2shSIhSF;= zg#4>Gy9$wyxYTZyLQcB`=841V7QmTC{JLkReapkvuo+>E0(qAU%3cIT5iXN$irm*E z_RF67_sWgA@li(A#fo44$s_A;6T{=-y@aH|0Cc|7A&j}c|FUjy^%6S#Dj|@>(&E;j z8EIgWQlC6+;lVA71{Vb-TuyggWZzg>(EB^Zu?IOu_8Hp zv*gOhb6uqeY6p>9Qo5VtbHeE7PrrDHez24VYlgU#%wky)G7(~waj?C297km(-hLXn z+8k8>&~{<1QKbb+s-rG-Cg6%9gDbH0qne_oB*h z{a<)|?)#lQ2GTl*^2?$exve9U;U)c?jge)9)0@5^JoMv-0MVaVU4pDIXiPSS3mna% z!0QiU?uUdfUeQo+5Nxdk>hecotpgs4;p5$-P<|KN%NMt5Z=ozoIRL+@InFrWXI^<% z>+B`5Ff+!xzSYs;1^f!8x~@jao3PnkajD_CDT3?f;K!S)UxIdslBMFCk}B>IyN_pb z8txdC%uN51Yf$uSfa0p zV6odu)L^9q0VfQ$GLWC-wHRGS>6M(Mz%BE;?7m{~2hfnDqUea8!y6yk{wiv)*yoXv zU-#$fIN5)zkX{A8K|UFEo2QCrjS~V#9kPWgEiLY@n&C zH`X&dW#-3EP;c$G8F-c*P6%W*2>i0dZU+~5jf<&DuD80eXdtP2J1!=9Pg@j6pbRF= zodOp(;-{albb$~Ku0LjXcb6;4kv5%FZxHD6h+sTn@oI~U+lM`|&&>WNmrVWlRa z#z>n0mLc$2UvBlz&Rk@)jmBZ^x@liuq1<#LF zf?fmNojy871bAZx@4%|=GNnBiz$jDCP}tFc$qSsAeMmIU4x1ct*h!KzxH6pA(yc1b z)ILNobr@4YdSg-A8y6XS)yfZvB=UNJcZ!>|7wTEiFj6hL)Mhh&Devgir|!%UAu-1h z$vR5Z?cwyWq{#M*$9~(OI_$A%$G-KkhY5lj7;SCM0q01d`u50o2HpSh<22G4#mc|K zmQRNNtB~|V;NiS9?0EU=@nJJY&*MP4v;70g?yUTOpM8#v^o@E^LYw_(;UFm1& zx_LGwy=0W_iO5gGV#s3-1zNINaff+NyYxef(U*o@`rJiO$52lm&RwgJt!; z0@cZ3QdaW;y)v@Rj>gkr1`^*}RW*k7=HGbOr-1C|+tRNGviV(lI8s_eL;FqBY1Gb! z#-HRpr2=XFk_Ne<<5snF@_tR>mKSPK_ICXRJSl3;Q_^>RZR8C86C^7$OP=l-hLF_d z#&5mWhw0~DZ&2bbRhy!o>P_y{ImMwTk}&EceVgHFv#0V?j7xurjt_`)KX&6KQ$F#l zZ~)MD2Sryy*7MzHwq)Cw<%@9?$`JYh`B-o#&AfdN4r8)Gc!@3i>XilA0-mbVU*fc< z{OXOKNl&m{(s-j+j&W=WFFR+UPTFs1k6ZDDkL$he`!%VSXD7`H6>%}q1pK#{hA7o1 z1>J~x7>Ag?9ex~h6doy{Gm9-E=@IfFt$_X>*H?4lVOmn0B>mdE@uh+ngrkDqoPrscd~ON&Gkha=riR75$ii6#MSX2-29k5@5HLXeJ?Wd;~$nx>qA0dza_ zF~th?@3y?j4DRv{tnVq2N0Toa&FNLIwjvAtNNhix4xqbFJRzd$NC>?932eYw%=w*{>CB)i3@zIxgHbK5okNtLo+nTb^;=Zf#*< zeer{#st2L65h}7OJsQckQxHuiXiM5AqBG)X>^UdwxB@9ZC>OKhwcI_G#Z9UKIrRND zD#~$U(cl6YDj%t|$Qm*_H@WC62jJqJdVCK+M+=otE&?@_aGMQq8g4FY$PxZtY3t?* z8EXGTk$Z9j`*g2=AXy)JG^?M+)7c zDvHw&-6#C6JdCaU!Y|GjJwcokKHfeLPnAr9YY=;rmry-{c6yKrGq?_w4d~nK(I!Q! zgAT}yEbCo=Ec!d_a;gn!Ef>~%Y)LBZ91Uh>cBL4h04|>n-;UP`xEcv0K-ZN{SgI6{bdWN*Bru`xWGt#anuuihSuFaY7I}x@@X}#we_xP#yZyA{> z*FNql*Xk+9Zo0mxX39rXJ0MBq1L2c_zx-di1%q2eXn)7<(~~HS;#4-HdtUOb1?F&y zCgHuyJa`*2*Yr=8*ZfjRWL39sj>B$TDUB4GNj-(?sbpJB&|)0dYKixMY8%W4)(2f0 zq?HwayM3cnLG^T2xHc*B54u&)r4Sgf+#89vuQ6%e%7l>c=uDO8&j1|woHSgarkaV~ zNuo()KY=)*@wFo#O3qo9(w2&RZW`~OXqxqYcyM-_DdQGC6cS!V9Rss9_;ppr;6q_7eG#yPfuhl#I@iKcz%>2_~=6KV7fv+_E;u5Y_ zuMJ~oiC`;_n;-qNRZgcbl7GJR7oo>wQD5LB#jVH>^`hE%HUQ3>BJ~cQWqUlJnO|{V<53*wvX2D;Vgm zg{}c58rk6WyWe-o)TMslv=cNl!nIXxQkYz+file}XXG$djV{gom|Weg$ZLH}^aJ#X z>Pss;PU9P1+@_c{iUk8cVOGxY2|Xpp8(gtBYN{53546+EhOT!@>m(v z0Xal8{!|@1?D~NLF3c-`?)kbGkqioL;D|kY`gyRDb&!UFS@>NNJe+v^z0 zB~#zHU(*A&R8cqn2c@$R+Mm5-3xbC;@i(YtkKk?b!r}tqCU1z1Wm$ZbCAQ-5+?+MR zsnXZ*Y+wML74~lN&57jQrLe43t~v^PQ56=-Y zWwktQ-8Ciw5v|aIzxcq6m(904<{0Goc^m!n$=0vQc7nOIDphsVYG6Sbuj4FPx^vN>1c6Sj@s5{YwZT(EemN8fh1FRr48Ncmu4dZ3n& zC{0DXU*(ytkWb{rmUQP>o$`SxdZ4)6nVSW*+#EV!`yE{+N7OL-Fw2kq;dhQd}f)*&Y77o2`Bh;YfG=7%1~Oz zw(E#*%`D*b`$w1(X#<^xN~p3*q;gF85*YkH!`&h6##=wHXv;5A?llzE{M7Hzm;qDf zLFg%j19{gmUrpFe?ofCgqzopQkPt#hV}KcB*J3-yaAXI@gCotjQ+Cx^NT`S~a(nkP zsVIW+o+*UBDtJ-SF>$NXwxS_Uxw*8=Jvdq6|5Nw(1F3g@Qmc_R ziE$N+FEiNQ(nC30`aJ>lcblbwo5IG)fCZZ@14c!Zkl*0h#%6b zme>PD+6jllEMpkkqjtvA!NEj&D{YCL25d@_WPP`6HLLE+kloc)iy>(k;GZujk7t2K zq>#om4R=u8TcZvv0-Gk80HG8j`y6jT>UmC=oW74V)xzvcR`=rcm@mR?xfA6UHNLhE z72g}ky2lfBRlaOFVj%vd*H#{cEaVrY&2^p%c>5E&6QliCQAY=_*`AXggWX}!LC(wH zyCe;f{8&iCpAr#DCVxq%y9T7{Cu_=$N;G6yXgsC?iW%vwphe*86lw*u|{6jA{E!z{m z4aeTBlPombBGN8R5W~#+WfulG>6~^?!y#!z>Nm~~_Qz5m zO@!_Bxni8Jwg|jV`0r|x&r&7jG!aG?S`-xaH%K+rT7>MZDYgDbqe-|Od9spJ>=sEj>snO9y z<{JsDj*(a0YMXmca`E?}tq@XE^LJmkC_>L4*3 zpkLpYeNpBey?H-h3WC>PHQuz6NZ(wn;AEHZu>VSFXhhX@)i!IKg4+ zJr?QKvK*Tlc{m_fG(X^rRV?Bcuc=wH!|q@8upjT4%|^}iq=xB@1F(9Iv7#ccH)Rpm zEhzMWCyZ$P?!-sk868D{KhwQA%X>zrvGNf9r@nsmhX_cqeX}UssqDS`fAMH{FV=O} z0sUNLe9SKyx_ruzU2R&(sf<6pxYXz!C%WIfpL*!p|1HxJ2mM7jLfbw2S~wx)p*joM8T}AP?vT1g#!!M zJKZneu-SQ zmangaMU4&@yqgu{5dn4Z$P2RJv*E%aA(fxs(E3R>k%@Wqn&DISik?*_|O&sV!w&^am`-y-`8PQXCHfbGSdkpYJ(r* z2L^6MOVSZtTvjuIDx<2wMQBQzLl)H)kS_Y@S0ZmV#`*Zw#_S4h9f2rUVYf{NsF#0d zJvL1SRWn5}^3F2~;8C>mEi?*CwfU& ztq=`8UivbLsan$UYN~JcOzdaAV2^86QAnAODYRmHd61>>CM)nP=;4YcfRRTAaJI>P zi+hN68SvF=aMXJi#mXJgJ&F?cJ%qPEUoa)1v+~!TcW!0FggoSUI|SRW3ztPibwjiN z{i$DdAFD9HX(}=-VyQkA#j(^#*_`fXn$GPh)MSNE5u!GgX7=~?23I10LDTADV$+Z; zcROkM61+M3L+V@EZizT)&5ktzbjXClO50>VmCw~HWyv+9Gtu(?^MsX>tud)l;)5!x zzTp>Hk#GZgJ*Nej^l%iu8=}1G=qztL7%ENVs4JODWVS%Fq!Up^Ro>wQr{*c>(yqhA z8(2c7#yxe2$OWUoG=|$_ilEjAb)%2dra+4w+|aKJcZPr22qQ;#*snYRaPCGcnay>5 zWLv!&Uo3d5F=E@e%12_nQR2rO%*VlfFHgV1N8%kLO5YAhL6w!G~W)Ze}j zc*-YDCJ}jl6#1IbKK|%~*%jbs`?+C#M5l%SrXkGPl(OK-K%r~c$uAIbTP4-X?4mW- zY_zQ0`K{p2&WK9>Vz@M(GwoFFDx0ijJxG+>*pCR&ritT4A1gRx^j`6Yazlx0ggk!X`2c;1Wq-15 z{?CIrLUI}eqZhET3LTeViA+D5HeI9tT9udB^t9}BZgXlHBjxKq`jQ(REW5_5m`oM6 zBs=1WsCvCzUhPf!fhO_-9!uK$0|!(V*&F&t*((dKdm`ldqla_#!{SA&N#6=6mw|>N z5hHAS92tv;M|*Dvj7ju+zm<(MA_k`N;Hh;mHv82r7bDX0&#QOkg?@s@#nlFf`T}KET3CZ0VklmAp+* zQA|n>s!wODX(P`oCCiiNX4~NamdO#Vi*4Q{vOo5XGBY@sbpLWqFS2Wmc9`@aKeD5c zbEgjGzlhZ1D`;eDGwjn2K#KuC}IUga^k8B{?)|_@Qd!OGtO7> zp3mQMp|8RRo))dVy=k%9G=kE-E%DEsUNYo4;}D)Nb50mBf1JxAjt3xUj<17Dc1&CO z4rMiGgDKGOZ9)$jur;Z{7Ly^B!4^gn^+^BLD-G|_v~-W-v2Vn-BfYd&UwU-bzj(J_ zJ|cE|a5}gud5O)h6k?aBo&op+vu6Bx>VS`zvK%AJO_K?#sN0Xj_2k%KxxST$Z@=Bul{2aZ_rYMi54NP5|Y`ob(+w!pi@fO97qUk=T2OPs?uz9msIVfTufE; z-B#ts{f%FJrNYdj0AIOtrgX*vsAWyo4&np6frURB2VQ26bUfYzVY6vc^Iggd%-8gq zl0IS7@e-2N4>?`F;9u3OM4sEH?YNaQYpj#NaJ~Q!sl>vhjkP@GUJBiQh_$8UGstM} z0=u)F`S_fPo4>}|VZN6H`UDPNmR&WEv;F&B zWH&dzejs&qK)?nRcI7G=PXzrN$!N8|B5_c#5djC#Fjgl% z$Y~rwHHi0?lQL?)fy7jf31C=H<6)#LQ(TP7WrSvB^;FkdV#jt+WtfR@#9s{{B6%Qh z7cJ@jpnNv{b0jhVFQ!5>f<@KiE8&EU#KP(aOC^~v0Iq^?f{#=C)C_Zreh*{AIm0UH6i1b6D?M25oK)Lid4fAe!px6g$9C+yy{OKTt z|GwX|-=mMN8=<~KjV&U723T$H9YOEO$tMeF!zU?`5t8UIYv*Joqd2B8uIxB2h`4Xe)Ym$9&|@WC#4FEtywwo?>=)Is9gFRN_z-nkhaKwW~L;Wes=9B z|3!@JjH3)^?qKHX=3)+JY@cR)0m|G`x&TIopQiE(DuMBT8VWf%(u5(v@Y4og|8o?w z^RoXB#q=WHXx#qLN)M z3hCc8GUWJEk!H8Ii|Z|9Q#ou|pZiGR=iArU-JgLGF-B&!q^qB%C6s#^Xn43#)0G!# ztLLt5Oh@oTD}TK`xBYo-GR!|VPxQ}y>pkX{S-TfR~sjTFV{r!@?ENKuV<$I2=d?-sLc-ciicD%-ix?HvPu>+O;F+!6L$zcqTpz$uk8gAbw@ zSrpw}upkKJtA{xg@kGwvjwcV4R9y47gQFd-mxOp)!iSNJ>eVe##Dne!16^-niNjhP z9J(cH0Fm+@06IjHhW}DS!V=)kntpnOxe-m$!tZG6^wOR$k}%u?MqMb;F%YI4PUMLR zqW^?78Tv(xpQC`csG~bXnb)mPVnb~Gc4gBAa3#j|yI})4w?ls)j}1*O zbFnx;8)D?%Ps-w_uD1wdDl=fxNXuA+kdQ+(5txj_0%RnN!yqt7BV=k5TZiLk`4gAJ zG813y+#AEsAt|-d6MYaJAID2lFYPOwhflES^L9@bNbfX?%!__l8cn7`);+7m5M5q&dj3rho5F`z)VM%!6^c2~Y}WLv7f6T(8#dYjd_PC{%(aUil9 z{-S9NsLQO{_1rJ3-x8sBGbZhVOhmdZeYT*$N}Hu7&~Q9j;LdFbQ94B^fe?#!{gfik z_v%;|H{p&uNZBNL6z`46%N)CZGorLw9Hc=^g{idvF&%uW{O7~--F<&o1Qb>$l0+J2 zPUStT0NhVwyix#&2#b`!TJ$IRgUUyewE^z{6tgidIG$RCBJ+*>p}-2GnMDu&jR&iN zr~J=EP*5xPbx+;NF`LB`-c~b98K2#tmvLl5lB|+}?LHOhR!lUNVrwZ_7yAUZ_(T&b zDL*!tV7Hm)9sNX6hEo)9;;#^n4Y^9%S*Ji_*$7tMPQRu9D?&(K3OtgwRWpqM*y3(unmiF?6sN zi!SEA#6r371MD@*tl22Rnqnb+2P0x$sq1)sCg9DbUsJKLTu*$4pT1N`aC8YJN}8QC zS(cXBRHzMi!-Xzhg*RH&dt*_&bQ?n#plL_rz&)zi6Ru8=^t&eee7+UogqKVQ`)}$? z2b#VR=DJpHm-w+)>g3#f21qQ@&mUiAb|OKQMT`>iXCXV4a3d1qQbA09vj4;ELt%nu zWJE8qwGPz$2gPXLxe1Et2Bi|;*a*hzU~4px(k=D~ZVux_&c8y6XIw!|tEr$2gk}9j z2uNg`h+yN{(+I+N``mx+Gas{3Rvyrqo1*R4BkOcCD?(^A5;H2Qae0yi4sj5E3F-?QF{TIgHb9 z9{ziOsJDg-igOfaC{v&oRJXURn{}guJ@RuZwLNn}rqc6Jfgy!Hc~{7=sxP){X0?9p zD${QrYw@PQCmz-ne1+^Uhh!J5=kM<^d_0B+q*-+yiSWl9$zE48)TjHg8i%|1OE++h z@u7Gh)l$6IcE5UJK$ZweEgd8Lj`*t3hR~=28oNYjWxho55-Z8mtn<{vZTxVGeDrg_ z-6giaelWGCbK&amfA805;k2ntAJnT$Th0Apn#ho;Ej}x=N0{n$X7jif=I(UJ?_;PC z8^NP_JrGgG*V&)AEsPqzDnmQvRRWSc)bBzBos<(${Ent%fZuHc;XmE6Hn2)qZVec{ zX%BOru3*XvNwd;vxkOo(Tq2qzO4;7i0zwz951h^x&y;^5-Aj*JfRx+kYyE zQRE^r`^3@h)nN4_zjkOpLRnG%wtTVhz+G;%uU+yYg4UJs*NQjul0bztQL zq+J0207Q36Kxk<*E0GdjTJ!k>iMEuYjB#V0uP3Z@faZK_3=vewXs^yF$2WsCBAHXq^e82X!7{G;v>iHZru zeZIO#UpmD4j2X{gC6ri2O$2p%L}XOlqF~`MpI_)FfLxMa&5yGr#S)N|%FQy3tO}gj zhl4Dki-nhnn|PzNH#GFT$f^jy|JTH3msB50k!qg=2cC+!!1&(2(we?(PV#;%;`F{S zt=YxvMZYekU%?XS@EBxX!tk0Ns_NAU-00 zODfME5RIx0xP{8x45R&{2*zM$!a6e0@2yk0jnbaBSR!4yV0DrLMY%uOcRneB@tGvf zX<{aFGfh&GkR|q8%^?>G@5F6+3?g3x`e`BDbbM5mo(kGW!8a}{X6(hef%#@`xu=H+^^6kojg z^&ze7@P`BjB@turSt`0LO5(wRwC~lXiAOMvDk(_U*u1eFRK>Y?j)tAL1y17pB&v$b z0hd~%uKwJYdjl-Fp<17r5~y5{s@B`~6ijT9=O+7I>q9bHdzyMToR;m?J-VaT3yX$<>+Rc#9fUObmhd2X>@;lW{NS6;Uc}OwqYgP zwjpQFyF@6FmlX1e@I#5sPiKqGge%IRy7~XW=IJy7p=m$+Tok zRz@S@CLE#`j33;}53~v`X{3ZVli{wNowj*V=Z}*Gq8tYNA>LQcRNtyo`I}dGR>txL z$k&Ip&T%8DJ39IbH#|RjFwv&d1yRBgZWE>uNR0kF+T@u^`d3#)!S<+F zlneSWT{#xyHK6DsY5uj_HWQ31*ODj_UYHJfpcAnoZJc1qgxyQaQ6wE6K64rUC>E}( zl4ScIGSc1rP77@kCrITDJ-9`Yclx7sg+DF3p$r6wL)*etd{2#oTpljZu1@8#q_iuN zR%YO5`?^DEGgI0RHsP_>C%G%`CN|u6p&&P$bG8vvKHZys5a#x;zy&|io4p2njpbw3LcPDc*5PO;~$}okEBUo;D$#% z=l|cNWo-YyR*oh%|GAo5qJzNBLDLdj!RT5ZuEB~~(ta&~A*24d#6xs2F81U+NbIz6QgC5_lZ5%F1c|PInJJrvF)s(Z1q+WU zI|~W^RqG}xwY8AmsEMZ3kNvGPN fj6OgWjqeCVOuj^ef(U!TTqjF|iKShWfn)wZkuCy` From 734772d92fca8be4c8baeb36abd96fd075ec5739 Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Mon, 13 Apr 2020 20:09:43 -0400 Subject: [PATCH 023/869] typo fix --- gtsam/base/OptionalJacobian.h | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/gtsam/base/OptionalJacobian.h b/gtsam/base/OptionalJacobian.h index 82a5ae7f4..fbec2f1cd 100644 --- a/gtsam/base/OptionalJacobian.h +++ b/gtsam/base/OptionalJacobian.h @@ -112,7 +112,7 @@ public: // template // OptionalJacobian(Eigen::Block block) : map_(NULL) { ?? } - /// Return true is allocated, false if default constructor was used + /// Return true if allocated, false if default constructor was used operator bool() const { return map_.data() != NULL; } @@ -197,7 +197,7 @@ public: #endif - /// Return true is allocated, false if default constructor was used + /// Return true if allocated, false if default constructor was used operator bool() const { return pointer_!=NULL; } From 83d0b9d3ff14773e26e4fe470ac26aad9e562a24 Mon Sep 17 00:00:00 2001 From: Frank dellaert Date: Sun, 10 May 2020 13:40:13 -0400 Subject: [PATCH 024/869] Inlined derivatives and fixed one issue with Jacobians around image center --- gtsam/geometry/Cal3Fisheye.cpp | 138 +++++++++++++-------------------- gtsam/geometry/Cal3Fisheye.h | 16 ++-- 2 files changed, 60 insertions(+), 94 deletions(-) diff --git a/gtsam/geometry/Cal3Fisheye.cpp b/gtsam/geometry/Cal3Fisheye.cpp index c6b43004e..f7794fafb 100644 --- a/gtsam/geometry/Cal3Fisheye.cpp +++ b/gtsam/geometry/Cal3Fisheye.cpp @@ -24,7 +24,7 @@ namespace gtsam { /* ************************************************************************* */ -Cal3Fisheye::Cal3Fisheye(const Vector& v) +Cal3Fisheye::Cal3Fisheye(const Vector9& v) : fx_(v[0]), fy_(v[1]), s_(v[2]), @@ -50,76 +50,73 @@ Matrix3 Cal3Fisheye::K() const { } /* ************************************************************************* */ -static Matrix29 D2dcalibration(const double xd, const double yd, - const double xi, const double yi, - const double t3, const double t5, - const double t7, const double t9, const double r, - Matrix2& DK) { - // order: fx, fy, s, u0, v0 - Matrix25 DR1; - DR1 << xd, 0.0, yd, 1.0, 0.0, 0.0, yd, 0.0, 0.0, 1.0; - - // order: k1, k2, k3, k4 - Matrix24 DR2; - DR2 << t3 * xi, t5 * xi, t7 * xi, t9 * xi, t3 * yi, t5 * yi, t7 * yi, t9 * yi; - DR2 /= r; - Matrix29 D; - D << DR1, DK * DR2; - return D; -} - -/* ************************************************************************* */ -static Matrix2 D2dintrinsic(const double xi, const double yi, const double r, - const double td, const double t, const double tt, - const double t4, const double t6, const double t8, - const double k1, const double k2, const double k3, - const double k4, const Matrix2& DK) { - const double dr_dxi = xi / sqrt(xi * xi + yi * yi); - const double dr_dyi = yi / sqrt(xi * xi + yi * yi); - const double dt_dr = 1 / (1 + r * r); - const double dtd_dt = - 1 + 3 * k1 * tt + 5 * k2 * t4 + 7 * k3 * t6 + 9 * k4 * t8; - const double dtd_dxi = dtd_dt * dt_dr * dr_dxi; - const double dtd_dyi = dtd_dt * dt_dr * dr_dyi; - - const double rinv = 1 / r; - const double rrinv = 1 / (r * r); - const double dxd_dxi = - dtd_dxi * xi * rinv + td * rinv + td * xi * (-rrinv) * dr_dxi; - const double dxd_dyi = dtd_dyi * xi * rinv - td * xi * rrinv * dr_dyi; - const double dyd_dxi = dtd_dxi * yi * rinv - td * yi * rrinv * dr_dxi; - const double dyd_dyi = - dtd_dyi * yi * rinv + td * rinv + td * yi * (-rrinv) * dr_dyi; - - Matrix2 DR; - DR << dxd_dxi, dxd_dyi, dyd_dxi, dyd_dyi; - - return DK * DR; +double Cal3Fisheye::Scaling(double r) { + static constexpr double threshold = 1e-8; + if (r > threshold || r < -threshold) { + return atan(r) / r; + } else { + // Taylor expansion close to 0 + double r2 = r * r, r4 = r2 * r2; + return 1.0 - r2 / 3 + r4 / 5; + } } /* ************************************************************************* */ Point2 Cal3Fisheye::uncalibrate(const Point2& p, OptionalJacobian<2, 9> H1, OptionalJacobian<2, 2> H2) const { const double xi = p.x(), yi = p.y(); - const double r = sqrt(xi * xi + yi * yi); + const double r2 = xi * xi + yi * yi, r = sqrt(r2); const double t = atan(r); - const double tt = t * t, t4 = tt * tt, t6 = tt * t4, t8 = t4 * t4; - const double td = t * (1 + k1_ * tt + k2_ * t4 + k3_ * t6 + k4_ * t8); - const double td_o_r = r > 1e-8 ? td / r : 1; - const double xd = td_o_r * xi, yd = td_o_r * yi; + const double t2 = t * t, t4 = t2 * t2, t6 = t2 * t4, t8 = t4 * t4; + Vector5 K, T; + K << 1, k1_, k2_, k3_, k4_; + T << 1, t2, t4, t6, t8; + const double scaling = Scaling(r); + const double s = scaling * K.dot(T); + const double xd = s * xi, yd = s * yi; Point2 uv(fx_ * xd + s_ * yd + u0_, fy_ * yd + v0_); Matrix2 DK; if (H1 || H2) DK << fx_, s_, 0.0, fy_; // Derivative for calibration parameters (2 by 9) - if (H1) - *H1 = D2dcalibration(xd, yd, xi, yi, t * tt, t * t4, t * t6, t * t8, r, DK); + if (H1) { + Matrix25 DR1; + // order: fx, fy, s, u0, v0 + DR1 << xd, 0.0, yd, 1.0, 0.0, 0.0, yd, 0.0, 0.0, 1.0; + + // order: k1, k2, k3, k4 + Matrix24 DR2; + auto T4 = T.tail<4>().transpose(); + DR2 << xi * T4, yi * T4; + *H1 << DR1, DK * scaling * DR2; + } // Derivative for points in intrinsic coords (2 by 2) - if (H2) - *H2 = - D2dintrinsic(xi, yi, r, td, t, tt, t4, t6, t8, k1_, k2_, k3_, k4_, DK); + if (H2) { + const double dtd_dt = + 1 + 3 * k1_ * t2 + 5 * k2_ * t4 + 7 * k3_ * t6 + 9 * k4_ * t8; + const double dt_dr = 1 / (1 + r2); + const double rinv = 1 / r; + const double dr_dxi = xi * rinv; + const double dr_dyi = yi * rinv; + const double dtd_dxi = dtd_dt * dt_dr * dr_dxi; + const double dtd_dyi = dtd_dt * dt_dr * dr_dyi; + + const double td = t * K.dot(T); + const double rrinv = 1 / r2; + const double dxd_dxi = + dtd_dxi * dr_dxi + td * rinv - td * xi * rrinv * dr_dxi; + const double dxd_dyi = dtd_dyi * dr_dxi - td * xi * rrinv * dr_dyi; + const double dyd_dxi = dtd_dxi * dr_dyi - td * yi * rrinv * dr_dxi; + const double dyd_dyi = + dtd_dyi * dr_dyi + td * rinv - td * yi * rrinv * dr_dyi; + + Matrix2 DR; + DR << dxd_dxi, dxd_dyi, dyd_dxi, dyd_dyi; + + *H2 = DK * DR; + } return uv; } @@ -157,39 +154,10 @@ Point2 Cal3Fisheye::calibrate(const Point2& uv, const double tol) const { return pi; } -/* ************************************************************************* */ -Matrix2 Cal3Fisheye::D2d_intrinsic(const Point2& p) const { - const double xi = p.x(), yi = p.y(); - const double r = sqrt(xi * xi + yi * yi); - const double t = atan(r); - const double tt = t * t, t4 = tt * tt, t6 = t4 * tt, t8 = t4 * t4; - const double td = t * (1 + k1_ * tt + k2_ * t4 + k3_ * t6 + k4_ * t8); - - Matrix2 DK; - DK << fx_, s_, 0.0, fy_; - - return D2dintrinsic(xi, yi, r, td, t, tt, t4, t6, t8, k1_, k2_, k3_, k4_, DK); -} - -/* ************************************************************************* */ -Matrix29 Cal3Fisheye::D2d_calibration(const Point2& p) const { - const double xi = p.x(), yi = p.y(); - const double r = sqrt(xi * xi + yi * yi); - const double t = atan(r); - const double tt = t * t, t4 = tt * tt, t6 = tt * t4, t8 = t4 * t4; - const double td = t * (1 + k1_ * tt + k2_ * t4 + k3_ * t6 + k4_ * t8); - const double xd = td / r * xi, yd = td / r * yi; - - Matrix2 DK; - DK << fx_, s_, 0.0, fy_; - return D2dcalibration(xd, yd, xi, yi, t * tt, t * t4, t * t6, t * t8, r, DK); -} - /* ************************************************************************* */ void Cal3Fisheye::print(const std::string& s_) const { gtsam::print((Matrix)K(), s_ + ".K"); gtsam::print(Vector(k()), s_ + ".k"); - ; } /* ************************************************************************* */ diff --git a/gtsam/geometry/Cal3Fisheye.h b/gtsam/geometry/Cal3Fisheye.h index 5fb196047..e24fe074f 100644 --- a/gtsam/geometry/Cal3Fisheye.h +++ b/gtsam/geometry/Cal3Fisheye.h @@ -20,6 +20,8 @@ #include +#include + namespace gtsam { /** @@ -43,7 +45,7 @@ namespace gtsam { * [u; v; 1] = K*[x_d; y_d; 1] */ class GTSAM_EXPORT Cal3Fisheye { - protected: + private: double fx_, fy_, s_, u0_, v0_; // focal length, skew and principal point double k1_, k2_, k3_, k4_; // fisheye distortion coefficients @@ -78,7 +80,7 @@ class GTSAM_EXPORT Cal3Fisheye { /// @name Advanced Constructors /// @{ - Cal3Fisheye(const Vector& v); + explicit Cal3Fisheye(const Vector9& v); /// @} /// @name Standard Interface @@ -120,6 +122,9 @@ class GTSAM_EXPORT Cal3Fisheye { /// Return all parameters as a vector Vector9 vector() const; + /// Helper function that calculates atan(r)/r + static double Scaling(double r); + /** * @brief convert intrinsic coordinates [x_i; y_i] to (distorted) image * coordinates [u; v] @@ -136,13 +141,6 @@ class GTSAM_EXPORT Cal3Fisheye { /// y_i] Point2 calibrate(const Point2& p, const double tol = 1e-5) const; - /// Derivative of uncalibrate wrpt intrinsic coordinates [x_i; y_i] - Matrix2 D2d_intrinsic(const Point2& p) const; - - /// Derivative of uncalibrate wrpt the calibration parameters - /// [fx, fy, s, u0, v0, k1, k2, k3, k4] - Matrix29 D2d_calibration(const Point2& p) const; - /// @} /// @name Testable /// @{ From 4f07aeb8595b9d21b8ce1ce7726e14703be065c0 Mon Sep 17 00:00:00 2001 From: Frank dellaert Date: Sun, 10 May 2020 13:40:37 -0400 Subject: [PATCH 025/869] Re-ordered and cleaned up tests, added derivative tests for image center --- gtsam/geometry/tests/testCal3DFisheye.cpp | 129 ++++++++++------------ 1 file changed, 56 insertions(+), 73 deletions(-) diff --git a/gtsam/geometry/tests/testCal3DFisheye.cpp b/gtsam/geometry/tests/testCal3DFisheye.cpp index 9203b5438..9317fb737 100644 --- a/gtsam/geometry/tests/testCal3DFisheye.cpp +++ b/gtsam/geometry/tests/testCal3DFisheye.cpp @@ -10,17 +10,18 @@ * -------------------------------------------------------------------------- */ /** - * @file testCal3Fisheye.cpp + * @file testCal3DFisheye.cpp * @brief Unit tests for fisheye calibration class * @author ghaggin */ -#include #include #include #include #include +#include + using namespace gtsam; GTSAM_CONCEPT_TESTABLE_INST(Cal3Fisheye) @@ -30,12 +31,27 @@ static const double fx = 250, fy = 260, s = 0.1, u0 = 320, v0 = 240; static Cal3Fisheye K(fx, fy, s, u0, v0, -0.013721808247486035, 0.020727425669427896, -0.012786476702685545, 0.0025242267320687625); -static Point2 p(2, 3); +static Point2 kTestPoint2(2, 3); + +/* ************************************************************************* */ +TEST(Cal3Fisheye, assert_equal) { CHECK(assert_equal(K, K, 1e-5)); } + +/* ************************************************************************* */ +TEST(Cal3Fisheye, retract) { + Cal3Fisheye expected(K.fx() + 1, K.fy() + 2, K.skew() + 3, K.px() + 4, + K.py() + 5, K.k1() + 6, K.k2() + 7, K.k3() + 8, + K.k4() + 9); + Vector d(9); + d << 1, 2, 3, 4, 5, 6, 7, 8, 9; + Cal3Fisheye actual = K.retract(d); + CHECK(assert_equal(expected, actual, 1e-7)); + CHECK(assert_equal(d, K.localCoordinates(actual), 1e-7)); +} /* ************************************************************************* */ TEST(Cal3Fisheye, uncalibrate1) { // Calculate the solution - const double xi = p.x(), yi = p.y(); + const double xi = kTestPoint2.x(), yi = kTestPoint2.y(); const double r = sqrt(xi * xi + yi * yi); const double t = atan(r); const double tt = t * t, t4 = tt * tt, t6 = tt * t4, t8 = t4 * t4; @@ -46,32 +62,42 @@ TEST(Cal3Fisheye, uncalibrate1) { Point2 uv_sol(v[0] / v[2], v[1] / v[2]); - Point2 uv = K.uncalibrate(p); + Point2 uv = K.uncalibrate(kTestPoint2); CHECK(assert_equal(uv, uv_sol)); } /* ************************************************************************* */ -/** - * Check that a point at (0,0) projects to the - * image center. - */ -TEST(Cal3Fisheye, uncalibrate2) { - Point2 pz(0, 0); - auto uv = K.uncalibrate(pz); - CHECK(assert_equal(uv, Point2(u0, v0))); +// For numerical derivatives +Point2 f(const Cal3Fisheye& k, const Point2& pt) { return k.uncalibrate(pt); } + +/* ************************************************************************* */ +TEST(Cal3Fisheye, Derivatives) { + Matrix H1, H2; + K.uncalibrate(kTestPoint2, H1, H2); + CHECK(assert_equal(numericalDerivative21(f, K, kTestPoint2, 1e-7), H1, 1e-5)); + CHECK(assert_equal(numericalDerivative22(f, K, kTestPoint2, 1e-7), H2, 1e-5)); } /* ************************************************************************* */ -/** - * This test uses cv2::fisheye::projectPoints to test that uncalibrate - * properly projects a point into the image plane. One notable difference - * between opencv and the Cal3Fisheye::uncalibrate function is the skew - * parameter. The equivalence is alpha = s/fx. - * - * - * Python script to project points with fisheye model in OpenCv - * (script run with OpenCv version 4.2.0 and Numpy version 1.18.2) - */ +// Check that a point at (0,0) projects to the image center. +TEST(Cal3Fisheye, uncalibrate2) { + Point2 pz(0, 0); + Matrix H1, H2; + auto uv = K.uncalibrate(pz, H1, H2); + CHECK(assert_equal(uv, Point2(u0, v0))); + CHECK(assert_equal(numericalDerivative21(f, K, pz, 1e-7), H1, 1e-5)); + // TODO(frank): the second jacobian is all NaN for the image center! + // CHECK(assert_equal(numericalDerivative22(f, K, pz, 1e-7), H2, 1e-5)); +} + +/* ************************************************************************* */ +// This test uses cv2::fisheye::projectPoints to test that uncalibrate +// properly projects a point into the image plane. One notable difference +// between opencv and the Cal3Fisheye::uncalibrate function is the skew +// parameter. The equivalence is alpha = s/fx. +// +// Python script to project points with fisheye model in OpenCv +// (script run with OpenCv version 4.2.0 and Numpy version 1.18.2) // clang-format off /* =========================================================== @@ -94,6 +120,7 @@ tvec = np.float64([[0.,0.,0.]]); imagePoints, jacobian = cv2.fisheye.projectPoints(objpts, rvec, tvec, cameraMatrix, distCoeffs, alpha=alpha) np.set_printoptions(precision=14) print(imagePoints) + =========================================================== * Script output: [[[457.82638130304935 408.18905848512986]]] */ @@ -134,21 +161,18 @@ TEST(Cal3Fisheye, calibrate1) { } /* ************************************************************************* */ -/** - * Check that calibrate returns (0,0) for the image center - */ +// Check that calibrate returns (0,0) for the image center TEST(Cal3Fisheye, calibrate2) { Point2 uv(u0, v0); auto xi_hat = K.calibrate(uv); CHECK(assert_equal(xi_hat, Point2(0, 0))) } -/** - * Run calibrate on OpenCv test from uncalibrate3 - * (script shown above) - * 3d point: (23, 27, 31) - * 2d point in image plane: (457.82638130304935, 408.18905848512986) - */ +/* ************************************************************************* */ +// Run calibrate on OpenCv test from uncalibrate3 +// (script shown above) +// 3d point: (23, 27, 31) +// 2d point in image plane: (457.82638130304935, 408.18905848512986) TEST(Cal3Fisheye, calibrate3) { Point3 p3(23, 27, 31); Point2 xi(p3.x() / p3.z(), p3.y() / p3.z()); @@ -157,47 +181,6 @@ TEST(Cal3Fisheye, calibrate3) { CHECK(assert_equal(xi_hat, xi)); } -/* ************************************************************************* */ -// For numerical derivatives -Point2 uncalibrate_(const Cal3Fisheye& k, const Point2& pt) { - return k.uncalibrate(pt); -} - -/* ************************************************************************* */ -TEST(Cal3Fisheye, Duncalibrate1) { - Matrix computed; - K.uncalibrate(p, computed, boost::none); - Matrix numerical = numericalDerivative21(uncalibrate_, K, p, 1e-7); - CHECK(assert_equal(numerical, computed, 1e-5)); - Matrix separate = K.D2d_calibration(p); - CHECK(assert_equal(numerical, separate, 1e-5)); -} - -/* ************************************************************************* */ -TEST(Cal3Fisheye, Duncalibrate2) { - Matrix computed; - K.uncalibrate(p, boost::none, computed); - Matrix numerical = numericalDerivative22(uncalibrate_, K, p, 1e-7); - CHECK(assert_equal(numerical, computed, 1e-5)); - Matrix separate = K.D2d_intrinsic(p); - CHECK(assert_equal(numerical, separate, 1e-5)); -} - -/* ************************************************************************* */ -TEST(Cal3Fisheye, assert_equal) { CHECK(assert_equal(K, K, 1e-5)); } - -/* ************************************************************************* */ -TEST(Cal3Fisheye, retract) { - Cal3Fisheye expected(K.fx() + 1, K.fy() + 2, K.skew() + 3, K.px() + 4, - K.py() + 5, K.k1() + 6, K.k2() + 7, K.k3() + 8, - K.k4() + 9); - Vector d(9); - d << 1, 2, 3, 4, 5, 6, 7, 8, 9; - Cal3Fisheye actual = K.retract(d); - CHECK(assert_equal(expected, actual, 1e-7)); - CHECK(assert_equal(d, K.localCoordinates(actual), 1e-7)); -} - /* ************************************************************************* */ int main() { TestResult tr; From 5abe293cdf48bc47c76938ed71512cd296abec4d Mon Sep 17 00:00:00 2001 From: Frank Dellaert Date: Sat, 7 Mar 2020 20:57:08 -0500 Subject: [PATCH 026/869] Setup and simulateMeasurements --- tests/testTranslationRecovery.cpp | 126 ++++++++++++++++++++++++++++++ 1 file changed, 126 insertions(+) create mode 100644 tests/testTranslationRecovery.cpp diff --git a/tests/testTranslationRecovery.cpp b/tests/testTranslationRecovery.cpp new file mode 100644 index 000000000..45c882cc9 --- /dev/null +++ b/tests/testTranslationRecovery.cpp @@ -0,0 +1,126 @@ +/* ---------------------------------------------------------------------------- + + * GTSAM Copyright 2010, Georgia Tech Research Corporation, + * Atlanta, Georgia 30332-0415 + * All Rights Reserved + * Authors: Frank Dellaert, et al. (see THANKS for the full author list) + + * See LICENSE for the license information + + * -------------------------------------------------------------------------- */ + +/** + * @file testTranslationRecovery.cpp + * @author Frank Dellaert + * @date March 2020 + * @brief test recovering translations when rotations are given. + */ + +#include +// #include +#include +#include +#include +#include +#include +#include +#include + +#include + +using namespace std; +using namespace gtsam; + +class TranslationFactor {}; + +// Set up an optimization problem for the unknown translations Ti in the world +// coordinate frame, given the known camera attitudes wRi with respect to the +// world frame, and a set of (noisy) translation directions of type Unit3, +// aZb. The measurement equation is +// aZb = Unit3(aRw * (Tb - Ta)) (1) +// i.e., aZb is the normalized translation of B's origin in the camera frame A. +// It is clear that we cannot recover the scale, nor the absolute position, so +// the gauge freedom in this case is 3 + 1 = 4. We fix these by taking fixing +// the translations Ta and Tb associated with the first measurement aZb, +// clamping them to their initial values as given to this method. If no initial +// values are given, we use the origin for Tb and set Tb to make (1) come +// through, i.e., +// Tb = s * wRa * Point3(aZb) (2) +// where s is an arbitrary scale that can be supplied, default 1.0. Hence, two +// versions are supplied below corresponding to whether we have initial values +// or not. Because the latter one is called from the first one, this is prime. + +void recoverTranslations(const double scale = 1.0) { + // graph.emplace_shared(m.second, unit2, m.first, + // P(j)); +} + +using KeyPair = pair; + +/** + * @brief Simulate translation direction measurements + * + * @param poses SE(3) ground truth poses stored as Values + * @param edges pairs (a,b) for which a measurement aZb will be generated. + */ +vector simulateMeasurements(const Values& poses, + const vector& edges) { + vector measurements; + for (auto edge : edges) { + Key a, b; + std::tie(a, b) = edge; + Pose3 wTa = poses.at(a), wTb = poses.at(b); + Point3 Ta = wTa.translation(), Tb = wTb.translation(); + auto aRw = wTa.rotation().inverse(); + Unit3 aZb = Unit3(aRw * (Tb - Ta)); + measurements.push_back(aZb); + } + return measurements; +} + +/* ************************************************************************* */ +// We read the BAL file, which has 3 cameras in it, with poses. We then assume +// the rotations are correct, but translations have to be estimated from +// translation directions only. Since we have 3 cameras, A, B, and C, we can at +// most create three relative measurements, let's call them aZb, aZc, and bZc. +// These will be of type Unit3. We then call `recoverTranslations` which sets up +// an optimization problem for the three unknown translations. +TEST(TranslationRecovery, BAL) { + string filename = findExampleDataFile("dubrovnik-3-7-pre"); + SfM_data db; + bool success = readBAL(filename, db); + if (!success) throw runtime_error("Could not access file!"); + + SharedNoiseModel unit2 = noiseModel::Unit::Create(2); + NonlinearFactorGraph graph; + + size_t i = 0; + Values poses; + for (auto camera : db.cameras) { + GTSAM_PRINT(camera); + poses.insert(i++, camera.pose()); + } + Pose3 wTa = poses.at(0), wTb = poses.at(1), + wTc = poses.at(2); + Point3 Ta = wTa.translation(), Tb = wTb.translation(), Tc = wTc.translation(); + auto measurements = simulateMeasurements(poses, {{0, 1}, {0, 2}, {1, 2}}); + auto aRw = wTa.rotation().inverse(); + Unit3 aZb = measurements[0]; + EXPECT(assert_equal(Unit3(aRw * (Tb - Ta)), aZb)); + Unit3 aZc = measurements[1]; + EXPECT(assert_equal(Unit3(aRw * (Tc - Ta)), aZc)); + // Values initial = initialCamerasAndPointsEstimate(db); + + // LevenbergMarquardtOptimizer lm(graph, initial); + + // Values actual = lm.optimize(); + // double actualError = graph.error(actual); + // EXPECT_DOUBLES_EQUAL(0.0199833, actualError, 1e-5); +} + +/* ************************************************************************* */ +int main() { + TestResult tr; + return TestRegistry::runAllTests(tr); +} +/* ************************************************************************* */ From 146f411a99df7d82648f0c1ebbeb27833f11f041 Mon Sep 17 00:00:00 2001 From: Frank Dellaert Date: Sun, 8 Mar 2020 01:45:04 -0500 Subject: [PATCH 027/869] Built TranslationFactor class and partially completed TranslationRecovery class --- tests/testTranslationRecovery.cpp | 323 +++++++++++++++++++++++------- 1 file changed, 246 insertions(+), 77 deletions(-) diff --git a/tests/testTranslationRecovery.cpp b/tests/testTranslationRecovery.cpp index 45c882cc9..330a507e5 100644 --- a/tests/testTranslationRecovery.cpp +++ b/tests/testTranslationRecovery.cpp @@ -1,3 +1,211 @@ +/* ---------------------------------------------------------------------------- + + * GTSAM Copyright 2010, Georgia Tech Research Corporation, + * Atlanta, Georgia 30332-0415 + * All Rights Reserved + * Authors: Frank Dellaert, et al. (see THANKS for the full author list) + + * See LICENSE for the license information + + * -------------------------------------------------------------------------- */ + +/** + * @file TranslationFactor.h + * @author Frank Dellaert + * @date March 2020 + * @brief Binary factor for a relative translation direction measurement. + */ + +#include +#include +#include +#include + +namespace gtsam { + +/** + * Binary factor for a relative translation direction measurement + * w_aZb. The measurement equation is + * w_aZb = Unit3(Tb - Ta) + * i.e., w_aZb is the translation direction from frame A to B, in world + * coordinates. Although Unit3 instances live on a manifold, following + * Wilson14eccv_1DSfM.pdf error we compute the *chordal distance* in the + * ambient world coordinate frame: + * normalized(Tb - Ta) - w_aZb.point3() + * + * @addtogroup SAM + */ +class TranslationFactor : public NoiseModelFactor2 { + private: + typedef NoiseModelFactor2 Base; + Point3 measured_w_aZb_; + + public: + /// default constructor + TranslationFactor() {} + + TranslationFactor(Key a, Key b, const Unit3& w_aZb, + const SharedNoiseModel& noiseModel) + : Base(noiseModel, a, b), measured_w_aZb_(w_aZb.point3()) {} + + /** + * @brief Caclulate error norm(p1-p2) - measured + * + * @param Ta translation for key a + * @param Tb translation for key b + * @param H1 optional jacobian in Ta + * @param H2 optional jacobian in Tb + * @return * Vector + */ + Vector evaluateError( + const Point3& Ta, const Point3& Tb, + boost::optional H1 = boost::none, + boost::optional H2 = boost::none) const override { + const Point3 dir = Tb - Ta; + Matrix33 H_predicted_dir; + const Point3 predicted = + dir.normalized(H1 || H2 ? &H_predicted_dir : nullptr); + if (H1) *H1 = H_predicted_dir; + if (H2) *H2 = -H_predicted_dir; + return predicted - measured_w_aZb_; + } + + private: + friend class boost::serialization::access; + template + void serialize(ARCHIVE& ar, const unsigned int /*version*/) { + ar& boost::serialization::make_nvp( + "Base", boost::serialization::base_object(*this)); + } +}; // \ TranslationFactor +} // namespace gtsam + +/* ---------------------------------------------------------------------------- + + * GTSAM Copyright 2010, Georgia Tech Research Corporation, + * Atlanta, Georgia 30332-0415 + * All Rights Reserved + * Authors: Frank Dellaert, et al. (see THANKS for the full author list) + + * See LICENSE for the license information + + * -------------------------------------------------------------------------- */ + +/** + * @file TranslationRecovery.h + * @author Frank Dellaert + * @date March 2020 + * @brief test recovering translations when rotations are given. + */ + +// #include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +namespace gtsam { + +// Set up an optimization problem for the unknown translations Ti in the world +// coordinate frame, given the known camera attitudes wRi with respect to the +// world frame, and a set of (noisy) translation directions of type Unit3, +// w_aZb. The measurement equation is +// w_aZb = Unit3(Tb - Ta) (1) +// i.e., w_aZb is the translation direction from frame A to B, in world +// coordinates. Although Unit3 instances live on a manifold, following +// Wilson14eccv_1DSfM.pdf error we compute the *chordal distance* in the +// ambient world coordinate frame. +// +// It is clear that we cannot recover the scale, nor the absolute position, +// so the gauge freedom in this case is 3 + 1 = 4. We fix these by taking fixing +// the translations Ta and Tb associated with the first measurement w_aZb, +// clamping them to their initial values as given to this method. If no initial +// values are given, we use the origin for Tb and set Tb to make (1) come +// through, i.e., +// Tb = s * wRa * Point3(w_aZb) (2) +// where s is an arbitrary scale that can be supplied, default 1.0. Hence, two +// versions are supplied below corresponding to whether we have initial values +// or not. Because the latter one is called from the first one, this is prime. + +class TranslationRecovery { + public: + using KeyPair = std::pair; + using TranslationEdges = std::map; + + private: + TranslationEdges relativeTranslations_; + + public: + /** + * @brief Construct a new Translation Recovery object + * + * @param relativeTranslations the relative translations, in world coordinate + * frames, indexed in a map by a pair of Pose keys. + */ + TranslationRecovery(const TranslationEdges& relativeTranslations) + : relativeTranslations_(relativeTranslations) {} + + /** + * @brief Build the factor graph to do the optimization. + * + * @return NonlinearFactorGraph + */ + NonlinearFactorGraph buildGraph() const { + auto noiseModel = noiseModel::Isotropic::Sigma(3, 0.01); + NonlinearFactorGraph graph; + for (auto edge : relativeTranslations_) { + Key a, b; + std::tie(a, b) = edge.first; + const Unit3 w_aZb = edge.second; + graph.emplace_shared(a, b, w_aZb, noiseModel); + } + return graph; + } + + /** + * @brief Build and optimize factor graph. + * + * @param scale scale for first relative translation which fixes gauge. + * @return Values + */ + Values run(const double scale = 1.0) const { + const auto graph = buildGraph(); + // Values initial = randomTranslations(); + + // LevenbergMarquardtOptimizer lm(graph, initial); + + Values result; // = lm.optimize(); + + return result; + } + + /** + * @brief Simulate translation direction measurements + * + * @param poses SE(3) ground truth poses stored as Values + * @param edges pairs (a,b) for which a measurement w_aZb will be generated. + */ + static TranslationEdges SimulateMeasurements( + const Values& poses, const std::vector& edges) { + TranslationEdges relativeTranslations; + for (auto edge : edges) { + Key a, b; + std::tie(a, b) = edge; + const Pose3 wTa = poses.at(a), wTb = poses.at(b); + const Point3 Ta = wTa.translation(), Tb = wTb.translation(); + const Unit3 w_aZb(Tb - Ta); + relativeTranslations[edge] = w_aZb; + } + return relativeTranslations; + } +}; +} // namespace gtsam + /* ---------------------------------------------------------------------------- * GTSAM Copyright 2010, Georgia Tech Research Corporation, @@ -16,100 +224,61 @@ * @brief test recovering translations when rotations are given. */ -#include -// #include -#include -#include -#include -#include -#include -#include -#include - #include +#include using namespace std; using namespace gtsam; -class TranslationFactor {}; - -// Set up an optimization problem for the unknown translations Ti in the world -// coordinate frame, given the known camera attitudes wRi with respect to the -// world frame, and a set of (noisy) translation directions of type Unit3, -// aZb. The measurement equation is -// aZb = Unit3(aRw * (Tb - Ta)) (1) -// i.e., aZb is the normalized translation of B's origin in the camera frame A. -// It is clear that we cannot recover the scale, nor the absolute position, so -// the gauge freedom in this case is 3 + 1 = 4. We fix these by taking fixing -// the translations Ta and Tb associated with the first measurement aZb, -// clamping them to their initial values as given to this method. If no initial -// values are given, we use the origin for Tb and set Tb to make (1) come -// through, i.e., -// Tb = s * wRa * Point3(aZb) (2) -// where s is an arbitrary scale that can be supplied, default 1.0. Hence, two -// versions are supplied below corresponding to whether we have initial values -// or not. Because the latter one is called from the first one, this is prime. - -void recoverTranslations(const double scale = 1.0) { - // graph.emplace_shared(m.second, unit2, m.first, - // P(j)); -} - -using KeyPair = pair; - -/** - * @brief Simulate translation direction measurements - * - * @param poses SE(3) ground truth poses stored as Values - * @param edges pairs (a,b) for which a measurement aZb will be generated. - */ -vector simulateMeasurements(const Values& poses, - const vector& edges) { - vector measurements; - for (auto edge : edges) { - Key a, b; - std::tie(a, b) = edge; - Pose3 wTa = poses.at(a), wTb = poses.at(b); - Point3 Ta = wTa.translation(), Tb = wTb.translation(); - auto aRw = wTa.rotation().inverse(); - Unit3 aZb = Unit3(aRw * (Tb - Ta)); - measurements.push_back(aZb); - } - return measurements; -} - /* ************************************************************************* */ // We read the BAL file, which has 3 cameras in it, with poses. We then assume // the rotations are correct, but translations have to be estimated from // translation directions only. Since we have 3 cameras, A, B, and C, we can at -// most create three relative measurements, let's call them aZb, aZc, and bZc. -// These will be of type Unit3. We then call `recoverTranslations` which sets up -// an optimization problem for the three unknown translations. +// most create three relative measurements, let's call them w_aZb, w_aZc, and +// bZc. These will be of type Unit3. We then call `recoverTranslations` which +// sets up an optimization problem for the three unknown translations. TEST(TranslationRecovery, BAL) { - string filename = findExampleDataFile("dubrovnik-3-7-pre"); + const string filename = findExampleDataFile("dubrovnik-3-7-pre"); SfM_data db; bool success = readBAL(filename, db); if (!success) throw runtime_error("Could not access file!"); - SharedNoiseModel unit2 = noiseModel::Unit::Create(2); - NonlinearFactorGraph graph; - - size_t i = 0; + // Get camera poses, as Values + size_t j = 0; Values poses; for (auto camera : db.cameras) { - GTSAM_PRINT(camera); - poses.insert(i++, camera.pose()); + poses.insert(j++, camera.pose()); } - Pose3 wTa = poses.at(0), wTb = poses.at(1), - wTc = poses.at(2); - Point3 Ta = wTa.translation(), Tb = wTb.translation(), Tc = wTc.translation(); - auto measurements = simulateMeasurements(poses, {{0, 1}, {0, 2}, {1, 2}}); - auto aRw = wTa.rotation().inverse(); - Unit3 aZb = measurements[0]; - EXPECT(assert_equal(Unit3(aRw * (Tb - Ta)), aZb)); - Unit3 aZc = measurements[1]; - EXPECT(assert_equal(Unit3(aRw * (Tc - Ta)), aZc)); - // Values initial = initialCamerasAndPointsEstimate(db); + + // Simulate measurements + const auto relativeTranslations = TranslationRecovery::SimulateMeasurements( + poses, {{0, 1}, {0, 2}, {1, 2}}); + + // Check + const Pose3 wTa = poses.at(0), wTb = poses.at(1), + wTc = poses.at(2); + const Point3 Ta = wTa.translation(), Tb = wTb.translation(), + Tc = wTc.translation(); + const Rot3 aRw = wTa.rotation().inverse(); + const Unit3 w_aZb = relativeTranslations.at({0, 1}); + EXPECT(assert_equal(Unit3(Tb - Ta), w_aZb)); + const Unit3 w_aZc = relativeTranslations.at({0, 2}); + EXPECT(assert_equal(Unit3(Tc - Ta), w_aZc)); + + TranslationRecovery algorithm(relativeTranslations); + const auto graph = algorithm.buildGraph(); + EXPECT_LONGS_EQUAL(3, graph.size()); + + // Translation recovery, version 1 + const auto result = algorithm.run(2); + + // Check result + // Pose3 expected0(wTa.rotation(), Point3(0, 0, 0)); + // EXPECT(assert_equal(expected0, result.at(0))); + // Pose3 expected1(wTb.rotation(), 2 * w_aZb.point3()); + // EXPECT(assert_equal(expected1, result.at(1))); + + // Values initial = randomTranslations(); // LevenbergMarquardtOptimizer lm(graph, initial); From d8f3ca46a4966f0c13250caa929de74fb441966f Mon Sep 17 00:00:00 2001 From: Frank Dellaert Date: Sun, 8 Mar 2020 01:58:22 -0500 Subject: [PATCH 028/869] Added initalizeRandomly --- tests/testTranslationRecovery.cpp | 29 ++++++++++++++++++++++++++--- 1 file changed, 26 insertions(+), 3 deletions(-) diff --git a/tests/testTranslationRecovery.cpp b/tests/testTranslationRecovery.cpp index 330a507e5..f513184e3 100644 --- a/tests/testTranslationRecovery.cpp +++ b/tests/testTranslationRecovery.cpp @@ -167,6 +167,29 @@ class TranslationRecovery { return graph; } + /** + * @brief Create random initial translations. + * + * @return Values + */ + Values initalizeRandomly() const { + Values initial; + auto insert = [&initial](Key j) { + if (!initial.exists(j)) { + initial.insert(j, Vector3::Random()); + } + }; + + // Loop over measurements and add a random translation + for (auto edge : relativeTranslations_) { + Key a, b; + std::tie(a, b) = edge.first; + insert(a); + insert(b); + } + return initial; + } + /** * @brief Build and optimize factor graph. * @@ -175,11 +198,11 @@ class TranslationRecovery { */ Values run(const double scale = 1.0) const { const auto graph = buildGraph(); - // Values initial = randomTranslations(); + const Values initial = initalizeRandomly(); - // LevenbergMarquardtOptimizer lm(graph, initial); + LevenbergMarquardtOptimizer lm(graph, initial); - Values result; // = lm.optimize(); + Values result = lm.optimize(); return result; } From 652302f5ad6d868c6c339bb4e76ae6b4f9c9ea22 Mon Sep 17 00:00:00 2001 From: Frank Dellaert Date: Sun, 8 Mar 2020 03:05:38 -0400 Subject: [PATCH 029/869] Running optimization --- tests/testTranslationRecovery.cpp | 21 ++++++++------------- 1 file changed, 8 insertions(+), 13 deletions(-) diff --git a/tests/testTranslationRecovery.cpp b/tests/testTranslationRecovery.cpp index f513184e3..bd8a81f20 100644 --- a/tests/testTranslationRecovery.cpp +++ b/tests/testTranslationRecovery.cpp @@ -200,8 +200,9 @@ class TranslationRecovery { const auto graph = buildGraph(); const Values initial = initalizeRandomly(); - LevenbergMarquardtOptimizer lm(graph, initial); - + LevenbergMarquardtParams params; + params.setVerbosityLM("Summary"); + LevenbergMarquardtOptimizer lm(graph, initial, params); Values result = lm.optimize(); return result; @@ -296,18 +297,12 @@ TEST(TranslationRecovery, BAL) { const auto result = algorithm.run(2); // Check result - // Pose3 expected0(wTa.rotation(), Point3(0, 0, 0)); - // EXPECT(assert_equal(expected0, result.at(0))); - // Pose3 expected1(wTb.rotation(), 2 * w_aZb.point3()); - // EXPECT(assert_equal(expected1, result.at(1))); + EXPECT(assert_equal(Point3(0, 0, 0), result.at(0))); + EXPECT(assert_equal(Point3(2 * w_aZb.point3()), result.at(1))); + EXPECT(assert_equal(Point3(0, 0, 0), result.at(2))); - // Values initial = randomTranslations(); - - // LevenbergMarquardtOptimizer lm(graph, initial); - - // Values actual = lm.optimize(); - // double actualError = graph.error(actual); - // EXPECT_DOUBLES_EQUAL(0.0199833, actualError, 1e-5); + // TODO(frank): how to get stats back + // EXPECT_DOUBLES_EQUAL(0.0199833, actualError, 1e-5); } /* ************************************************************************* */ From 83a0f515875b666a9cdae1e4af1668d6ec737fc8 Mon Sep 17 00:00:00 2001 From: Frank Dellaert Date: Sun, 8 Mar 2020 03:15:38 -0400 Subject: [PATCH 030/869] Moved TranslationFactor prototype into sfm directory --- gtsam/sfm/TranslationFactor.h | 83 ++++++++++++++++++++++++++++++ tests/testTranslationRecovery.cpp | 84 +------------------------------ 2 files changed, 84 insertions(+), 83 deletions(-) create mode 100644 gtsam/sfm/TranslationFactor.h diff --git a/gtsam/sfm/TranslationFactor.h b/gtsam/sfm/TranslationFactor.h new file mode 100644 index 000000000..626214dcc --- /dev/null +++ b/gtsam/sfm/TranslationFactor.h @@ -0,0 +1,83 @@ +/* ---------------------------------------------------------------------------- + + * GTSAM Copyright 2010, Georgia Tech Research Corporation, + * Atlanta, Georgia 30332-0415 + * All Rights Reserved + * Authors: Frank Dellaert, et al. (see THANKS for the full author list) + + * See LICENSE for the license information + + * -------------------------------------------------------------------------- */ + +#pragma once + +/** + * @file TranslationFactor.h + * @author Frank Dellaert + * @date March 2020 + * @brief Binary factor for a relative translation direction measurement. + */ + +#include +#include +#include +#include + +namespace gtsam { + +/** + * Binary factor for a relative translation direction measurement + * w_aZb. The measurement equation is + * w_aZb = Unit3(Tb - Ta) + * i.e., w_aZb is the translation direction from frame A to B, in world + * coordinates. Although Unit3 instances live on a manifold, following + * Wilson14eccv_1DSfM.pdf error we compute the *chordal distance* in the + * ambient world coordinate frame: + * normalized(Tb - Ta) - w_aZb.point3() + * + * @addtogroup SAM + */ +class TranslationFactor : public NoiseModelFactor2 { + private: + typedef NoiseModelFactor2 Base; + Point3 measured_w_aZb_; + + public: + /// default constructor + TranslationFactor() {} + + TranslationFactor(Key a, Key b, const Unit3& w_aZb, + const SharedNoiseModel& noiseModel) + : Base(noiseModel, a, b), measured_w_aZb_(w_aZb.point3()) {} + + /** + * @brief Caclulate error norm(p1-p2) - measured + * + * @param Ta translation for key a + * @param Tb translation for key b + * @param H1 optional jacobian in Ta + * @param H2 optional jacobian in Tb + * @return * Vector + */ + Vector evaluateError( + const Point3& Ta, const Point3& Tb, + boost::optional H1 = boost::none, + boost::optional H2 = boost::none) const override { + const Point3 dir = Tb - Ta; + Matrix33 H_predicted_dir; + const Point3 predicted = + dir.normalized(H1 || H2 ? &H_predicted_dir : nullptr); + if (H1) *H1 = H_predicted_dir; + if (H2) *H2 = -H_predicted_dir; + return predicted - measured_w_aZb_; + } + + private: + friend class boost::serialization::access; + template + void serialize(ARCHIVE& ar, const unsigned int /*version*/) { + ar& boost::serialization::make_nvp( + "Base", boost::serialization::base_object(*this)); + } +}; // \ TranslationFactor +} // namespace gtsam diff --git a/tests/testTranslationRecovery.cpp b/tests/testTranslationRecovery.cpp index bd8a81f20..8742820f4 100644 --- a/tests/testTranslationRecovery.cpp +++ b/tests/testTranslationRecovery.cpp @@ -1,85 +1,3 @@ -/* ---------------------------------------------------------------------------- - - * GTSAM Copyright 2010, Georgia Tech Research Corporation, - * Atlanta, Georgia 30332-0415 - * All Rights Reserved - * Authors: Frank Dellaert, et al. (see THANKS for the full author list) - - * See LICENSE for the license information - - * -------------------------------------------------------------------------- */ - -/** - * @file TranslationFactor.h - * @author Frank Dellaert - * @date March 2020 - * @brief Binary factor for a relative translation direction measurement. - */ - -#include -#include -#include -#include - -namespace gtsam { - -/** - * Binary factor for a relative translation direction measurement - * w_aZb. The measurement equation is - * w_aZb = Unit3(Tb - Ta) - * i.e., w_aZb is the translation direction from frame A to B, in world - * coordinates. Although Unit3 instances live on a manifold, following - * Wilson14eccv_1DSfM.pdf error we compute the *chordal distance* in the - * ambient world coordinate frame: - * normalized(Tb - Ta) - w_aZb.point3() - * - * @addtogroup SAM - */ -class TranslationFactor : public NoiseModelFactor2 { - private: - typedef NoiseModelFactor2 Base; - Point3 measured_w_aZb_; - - public: - /// default constructor - TranslationFactor() {} - - TranslationFactor(Key a, Key b, const Unit3& w_aZb, - const SharedNoiseModel& noiseModel) - : Base(noiseModel, a, b), measured_w_aZb_(w_aZb.point3()) {} - - /** - * @brief Caclulate error norm(p1-p2) - measured - * - * @param Ta translation for key a - * @param Tb translation for key b - * @param H1 optional jacobian in Ta - * @param H2 optional jacobian in Tb - * @return * Vector - */ - Vector evaluateError( - const Point3& Ta, const Point3& Tb, - boost::optional H1 = boost::none, - boost::optional H2 = boost::none) const override { - const Point3 dir = Tb - Ta; - Matrix33 H_predicted_dir; - const Point3 predicted = - dir.normalized(H1 || H2 ? &H_predicted_dir : nullptr); - if (H1) *H1 = H_predicted_dir; - if (H2) *H2 = -H_predicted_dir; - return predicted - measured_w_aZb_; - } - - private: - friend class boost::serialization::access; - template - void serialize(ARCHIVE& ar, const unsigned int /*version*/) { - ar& boost::serialization::make_nvp( - "Base", boost::serialization::base_object(*this)); - } -}; // \ TranslationFactor -} // namespace gtsam - /* ---------------------------------------------------------------------------- * GTSAM Copyright 2010, Georgia Tech Research Corporation, @@ -98,7 +16,7 @@ class TranslationFactor : public NoiseModelFactor2 { * @brief test recovering translations when rotations are given. */ -// #include +#include #include #include #include From 656f4ad57725110f5f24d2ae51b1648f84773fa8 Mon Sep 17 00:00:00 2001 From: Frank Dellaert Date: Sun, 8 Mar 2020 03:26:41 -0400 Subject: [PATCH 031/869] unit test, incl Jacobians --- gtsam/sfm/TranslationFactor.h | 6 +- gtsam/sfm/tests/testTranslationFactor.cpp | 90 +++++++++++++++++++++++ 2 files changed, 93 insertions(+), 3 deletions(-) create mode 100644 gtsam/sfm/tests/testTranslationFactor.cpp diff --git a/gtsam/sfm/TranslationFactor.h b/gtsam/sfm/TranslationFactor.h index 626214dcc..bf65b9bc8 100644 --- a/gtsam/sfm/TranslationFactor.h +++ b/gtsam/sfm/TranslationFactor.h @@ -35,7 +35,7 @@ namespace gtsam { * ambient world coordinate frame: * normalized(Tb - Ta) - w_aZb.point3() * - * @addtogroup SAM + * @addtogroup SFM */ class TranslationFactor : public NoiseModelFactor2 { private: @@ -67,8 +67,8 @@ class TranslationFactor : public NoiseModelFactor2 { Matrix33 H_predicted_dir; const Point3 predicted = dir.normalized(H1 || H2 ? &H_predicted_dir : nullptr); - if (H1) *H1 = H_predicted_dir; - if (H2) *H2 = -H_predicted_dir; + if (H1) *H1 = -H_predicted_dir; + if (H2) *H2 = H_predicted_dir; return predicted - measured_w_aZb_; } diff --git a/gtsam/sfm/tests/testTranslationFactor.cpp b/gtsam/sfm/tests/testTranslationFactor.cpp new file mode 100644 index 000000000..54928d684 --- /dev/null +++ b/gtsam/sfm/tests/testTranslationFactor.cpp @@ -0,0 +1,90 @@ +/* ---------------------------------------------------------------------------- + + * GTSAM Copyright 2010, Georgia Tech Research Corporation, + * Atlanta, Georgia 30332-0415 + * All Rights Reserved + * Authors: Frank Dellaert, et al. (see THANKS for the full author list) + + * See LICENSE for the license information + + * -------------------------------------------------------------------------- */ + +/** + * @file testTranslationFactor.cpp + * @brief Unit tests for TranslationFactor Class + * @author Frank dellaert + * @date March 2020 + */ + +#include +#include +#include + +#include + +using namespace std; +using namespace gtsam; + +// Create a noise model for the chordal error +static SharedNoiseModel model(noiseModel::Isotropic::Sigma(3, 0.05)); + +// Keys are deliberately *not* in sorted order to test that case. +static const Key kKey1(2), kKey2(1); +static const Unit3 kMeasured(1, 0, 0); + +/* ************************************************************************* */ +TEST(TranslationFactor, Constructor) { + TranslationFactor factor(kKey1, kKey2, kMeasured, model); +} + +/* ************************************************************************* */ +TEST(TranslationFactor, Error) { + // Create a factor + TranslationFactor factor(kKey1, kKey2, kMeasured, model); + + // Set the linearization + Point3 T1(1, 0, 0), T2(2, 0, 0); + + // Use the factor to calculate the error + Vector actualError(factor.evaluateError(T1, T2)); + + // Verify we get the expected error + Vector expected = (Vector3() << 0, 0, 0).finished(); + EXPECT(assert_equal(expected, actualError, 1e-9)); +} + +/* ************************************************************************* */ +Vector factorError(const Point3& T1, const Point3& T2, + const TranslationFactor& factor) { + return factor.evaluateError(T1, T2); +} + +TEST(TranslationFactor, Jacobian) { + // Create a factor + TranslationFactor factor(kKey1, kKey2, kMeasured, model); + + // Set the linearization + Point3 T1(1, 0, 0), T2(2, 0, 0); + + // Use the factor to calculate the Jacobians + Matrix H1Actual, H2Actual; + factor.evaluateError(T1, T2, H1Actual, H2Actual); + + // Use numerical derivatives to calculate the Jacobians + Matrix H1Expected, H2Expected; + H1Expected = numericalDerivative11( + boost::bind(&factorError, _1, T2, factor), T1); + H2Expected = numericalDerivative11( + boost::bind(&factorError, T1, _1, factor), T2); + + // Verify the Jacobians are correct + EXPECT(assert_equal(H1Expected, H1Actual, 1e-9)); + EXPECT(assert_equal(H2Expected, H2Actual, 1e-9)); +} + +/* ************************************************************************* */ +int main() { + TestResult tr; + return TestRegistry::runAllTests(tr); +} +/* ************************************************************************* */ From 7910f00c2c6524a27aef5b513c18dd929d9625ca Mon Sep 17 00:00:00 2001 From: Frank Dellaert Date: Sun, 8 Mar 2020 03:50:45 -0400 Subject: [PATCH 032/869] Optimization works! --- tests/testTranslationRecovery.cpp | 49 +++++++++++++++++++++++-------- 1 file changed, 37 insertions(+), 12 deletions(-) diff --git a/tests/testTranslationRecovery.cpp b/tests/testTranslationRecovery.cpp index 8742820f4..94ee14c28 100644 --- a/tests/testTranslationRecovery.cpp +++ b/tests/testTranslationRecovery.cpp @@ -16,7 +16,6 @@ * @brief test recovering translations when rotations are given. */ -#include #include #include #include @@ -26,6 +25,8 @@ #include #include #include +#include +#include namespace gtsam { @@ -57,6 +58,7 @@ class TranslationRecovery { private: TranslationEdges relativeTranslations_; + LevenbergMarquardtParams params_; public: /** @@ -66,7 +68,9 @@ class TranslationRecovery { * frames, indexed in a map by a pair of Pose keys. */ TranslationRecovery(const TranslationEdges& relativeTranslations) - : relativeTranslations_(relativeTranslations) {} + : relativeTranslations_(relativeTranslations) { + params_.setVerbosityLM("Summary"); + } /** * @brief Build the factor graph to do the optimization. @@ -76,15 +80,35 @@ class TranslationRecovery { NonlinearFactorGraph buildGraph() const { auto noiseModel = noiseModel::Isotropic::Sigma(3, 0.01); NonlinearFactorGraph graph; + + // Add all relative translation edges for (auto edge : relativeTranslations_) { Key a, b; std::tie(a, b) = edge.first; const Unit3 w_aZb = edge.second; graph.emplace_shared(a, b, w_aZb, noiseModel); } + return graph; } + /** + * @brief Add priors on ednpoints of first measurement edge. + * + * @param scale scale for first relative translation which fixes gauge. + * @param graph factor graph to which prior is added. + */ + void addPrior(const double scale, NonlinearFactorGraph* graph) const { + auto noiseModel = noiseModel::Isotropic::Sigma(3, 0.01); + auto edge = relativeTranslations_.begin(); + Key a, b; + std::tie(a, b) = edge->first; + const Unit3 w_aZb = edge->second; + graph->emplace_shared >(a, Point3(0, 0, 0), noiseModel); + graph->emplace_shared >(b, scale * w_aZb.point3(), + noiseModel); + } + /** * @brief Create random initial translations. * @@ -115,14 +139,11 @@ class TranslationRecovery { * @return Values */ Values run(const double scale = 1.0) const { - const auto graph = buildGraph(); + auto graph = buildGraph(); + addPrior(scale, &graph); const Values initial = initalizeRandomly(); - - LevenbergMarquardtParams params; - params.setVerbosityLM("Summary"); - LevenbergMarquardtOptimizer lm(graph, initial, params); + LevenbergMarquardtOptimizer lm(graph, initial, params_); Values result = lm.optimize(); - return result; } @@ -212,14 +233,18 @@ TEST(TranslationRecovery, BAL) { EXPECT_LONGS_EQUAL(3, graph.size()); // Translation recovery, version 1 - const auto result = algorithm.run(2); + const double scale = 2.0; + const auto result = algorithm.run(scale); - // Check result + // Check result for first two translations, determined by prior EXPECT(assert_equal(Point3(0, 0, 0), result.at(0))); EXPECT(assert_equal(Point3(2 * w_aZb.point3()), result.at(1))); - EXPECT(assert_equal(Point3(0, 0, 0), result.at(2))); - // TODO(frank): how to get stats back + // Check that the third translations is correct + Point3 expected = (Tc - Ta) * (scale / (Tb - Ta).norm()); + EXPECT(assert_equal(expected, result.at(2), 1e-4)); + + // TODO(frank): how to get stats back? // EXPECT_DOUBLES_EQUAL(0.0199833, actualError, 1e-5); } From f4b2b8bde0590c0c431f9eaba87ba9f1d73e98a0 Mon Sep 17 00:00:00 2001 From: Frank Dellaert Date: Sun, 8 Mar 2020 04:04:21 -0400 Subject: [PATCH 033/869] copyright 2020 --- gtsam/sfm/TranslationFactor.h | 2 +- gtsam/sfm/tests/testTranslationFactor.cpp | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/gtsam/sfm/TranslationFactor.h b/gtsam/sfm/TranslationFactor.h index bf65b9bc8..584b1fa69 100644 --- a/gtsam/sfm/TranslationFactor.h +++ b/gtsam/sfm/TranslationFactor.h @@ -1,6 +1,6 @@ /* ---------------------------------------------------------------------------- - * GTSAM Copyright 2010, Georgia Tech Research Corporation, + * GTSAM Copyright 2010-2020, Georgia Tech Research Corporation, * Atlanta, Georgia 30332-0415 * All Rights Reserved * Authors: Frank Dellaert, et al. (see THANKS for the full author list) diff --git a/gtsam/sfm/tests/testTranslationFactor.cpp b/gtsam/sfm/tests/testTranslationFactor.cpp index 54928d684..da284bfd6 100644 --- a/gtsam/sfm/tests/testTranslationFactor.cpp +++ b/gtsam/sfm/tests/testTranslationFactor.cpp @@ -1,6 +1,6 @@ /* ---------------------------------------------------------------------------- - * GTSAM Copyright 2010, Georgia Tech Research Corporation, + * GTSAM Copyright 2010-2020, Georgia Tech Research Corporation, * Atlanta, Georgia 30332-0415 * All Rights Reserved * Authors: Frank Dellaert, et al. (see THANKS for the full author list) From 98b8d6b4f3f272ee952271329163a269344eccd4 Mon Sep 17 00:00:00 2001 From: Frank Dellaert Date: Sun, 8 Mar 2020 04:04:49 -0400 Subject: [PATCH 034/869] Move to its own compilation unit --- gtsam/sfm/TranslationRecovery.cpp | 103 ++++++++++++++++++ gtsam/sfm/TranslationRecovery.h | 108 ++++++++++++++++++ tests/testTranslationRecovery.cpp | 175 +----------------------------- 3 files changed, 214 insertions(+), 172 deletions(-) create mode 100644 gtsam/sfm/TranslationRecovery.cpp create mode 100644 gtsam/sfm/TranslationRecovery.h diff --git a/gtsam/sfm/TranslationRecovery.cpp b/gtsam/sfm/TranslationRecovery.cpp new file mode 100644 index 000000000..a0f3eb6b6 --- /dev/null +++ b/gtsam/sfm/TranslationRecovery.cpp @@ -0,0 +1,103 @@ +/* ---------------------------------------------------------------------------- + + * GTSAM Copyright 2010-2020, Georgia Tech Research Corporation, + * Atlanta, Georgia 30332-0415 + * All Rights Reserved + * Authors: Frank Dellaert, et al. (see THANKS for the full author list) + + * See LICENSE for the license information + + * -------------------------------------------------------------------------- */ + +/** + * @file TranslationRecovery.h + * @author Frank Dellaert + * @date March 2020 + * @brief test recovering translations when rotations are given. + */ + +#include + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +using namespace gtsam; +using namespace std; + +NonlinearFactorGraph TranslationRecovery::buildGraph() const { + auto noiseModel = noiseModel::Isotropic::Sigma(3, 0.01); + NonlinearFactorGraph graph; + + // Add all relative translation edges + for (auto edge : relativeTranslations_) { + Key a, b; + tie(a, b) = edge.first; + const Unit3 w_aZb = edge.second; + graph.emplace_shared(a, b, w_aZb, noiseModel); + } + + return graph; +} + +void TranslationRecovery::addPrior(const double scale, + NonlinearFactorGraph* graph) const { + auto noiseModel = noiseModel::Isotropic::Sigma(3, 0.01); + auto edge = relativeTranslations_.begin(); + Key a, b; + tie(a, b) = edge->first; + const Unit3 w_aZb = edge->second; + graph->emplace_shared >(a, Point3(0, 0, 0), noiseModel); + graph->emplace_shared >(b, scale * w_aZb.point3(), + noiseModel); +} + +Values TranslationRecovery::initalizeRandomly() const { + // Create a lambda expression that checks whether value exists and randomly + // initializes if not. + Values initial; + auto insert = [&initial](Key j) { + if (!initial.exists(j)) { + initial.insert(j, Vector3::Random()); + } + }; + + // Loop over measurements and add a random translation + for (auto edge : relativeTranslations_) { + Key a, b; + tie(a, b) = edge.first; + insert(a); + insert(b); + } + return initial; +} + +Values TranslationRecovery::run(const double scale) const { + auto graph = buildGraph(); + addPrior(scale, &graph); + const Values initial = initalizeRandomly(); + LevenbergMarquardtOptimizer lm(graph, initial, params_); + Values result = lm.optimize(); + return result; +} + +TranslationRecovery::TranslationEdges TranslationRecovery::SimulateMeasurements( + const Values& poses, const vector& edges) { + TranslationEdges relativeTranslations; + for (auto edge : edges) { + Key a, b; + tie(a, b) = edge; + const Pose3 wTa = poses.at(a), wTb = poses.at(b); + const Point3 Ta = wTa.translation(), Tb = wTb.translation(); + const Unit3 w_aZb(Tb - Ta); + relativeTranslations[edge] = w_aZb; + } + return relativeTranslations; +} diff --git a/gtsam/sfm/TranslationRecovery.h b/gtsam/sfm/TranslationRecovery.h new file mode 100644 index 000000000..5eea251cf --- /dev/null +++ b/gtsam/sfm/TranslationRecovery.h @@ -0,0 +1,108 @@ +/* ---------------------------------------------------------------------------- + + * GTSAM Copyright 2010-2020, Georgia Tech Research Corporation, + * Atlanta, Georgia 30332-0415 + * All Rights Reserved + * Authors: Frank Dellaert, et al. (see THANKS for the full author list) + + * See LICENSE for the license information + + * -------------------------------------------------------------------------- */ + +/** + * @file TranslationRecovery.h + * @author Frank Dellaert + * @date March 2020 + * @brief test recovering translations when rotations are given. + */ + +#include +#include +#include + +#include +#include + +namespace gtsam { + +// Set up an optimization problem for the unknown translations Ti in the world +// coordinate frame, given the known camera attitudes wRi with respect to the +// world frame, and a set of (noisy) translation directions of type Unit3, +// w_aZb. The measurement equation is +// w_aZb = Unit3(Tb - Ta) (1) +// i.e., w_aZb is the translation direction from frame A to B, in world +// coordinates. Although Unit3 instances live on a manifold, following +// Wilson14eccv_1DSfM.pdf error we compute the *chordal distance* in the +// ambient world coordinate frame. +// +// It is clear that we cannot recover the scale, nor the absolute position, +// so the gauge freedom in this case is 3 + 1 = 4. We fix these by taking fixing +// the translations Ta and Tb associated with the first measurement w_aZb, +// clamping them to their initial values as given to this method. If no initial +// values are given, we use the origin for Tb and set Tb to make (1) come +// through, i.e., +// Tb = s * wRa * Point3(w_aZb) (2) +// where s is an arbitrary scale that can be supplied, default 1.0. Hence, two +// versions are supplied below corresponding to whether we have initial values +// or not. +class TranslationRecovery { + public: + using KeyPair = std::pair; + using TranslationEdges = std::map; + + private: + TranslationEdges relativeTranslations_; + LevenbergMarquardtParams params_; + + public: + /** + * @brief Construct a new Translation Recovery object + * + * @param relativeTranslations the relative translations, in world coordinate + * frames, indexed in a map by a pair of Pose keys. + */ + TranslationRecovery(const TranslationEdges& relativeTranslations) + : relativeTranslations_(relativeTranslations) { + params_.setVerbosityLM("Summary"); + } + + /** + * @brief Build the factor graph to do the optimization. + * + * @return NonlinearFactorGraph + */ + NonlinearFactorGraph buildGraph() const; + + /** + * @brief Add priors on ednpoints of first measurement edge. + * + * @param scale scale for first relative translation which fixes gauge. + * @param graph factor graph to which prior is added. + */ + void addPrior(const double scale, NonlinearFactorGraph* graph) const; + + /** + * @brief Create random initial translations. + * + * @return Values + */ + Values initalizeRandomly() const; + + /** + * @brief Build and optimize factor graph. + * + * @param scale scale for first relative translation which fixes gauge. + * @return Values + */ + Values run(const double scale = 1.0) const; + + /** + * @brief Simulate translation direction measurements + * + * @param poses SE(3) ground truth poses stored as Values + * @param edges pairs (a,b) for which a measurement w_aZb will be generated. + */ + static TranslationEdges SimulateMeasurements( + const Values& poses, const std::vector& edges); +}; +} // namespace gtsam diff --git a/tests/testTranslationRecovery.cpp b/tests/testTranslationRecovery.cpp index 94ee14c28..774a999e4 100644 --- a/tests/testTranslationRecovery.cpp +++ b/tests/testTranslationRecovery.cpp @@ -1,177 +1,6 @@ /* ---------------------------------------------------------------------------- - * GTSAM Copyright 2010, Georgia Tech Research Corporation, - * Atlanta, Georgia 30332-0415 - * All Rights Reserved - * Authors: Frank Dellaert, et al. (see THANKS for the full author list) - - * See LICENSE for the license information - - * -------------------------------------------------------------------------- */ - -/** - * @file TranslationRecovery.h - * @author Frank Dellaert - * @date March 2020 - * @brief test recovering translations when rotations are given. - */ - -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include - -namespace gtsam { - -// Set up an optimization problem for the unknown translations Ti in the world -// coordinate frame, given the known camera attitudes wRi with respect to the -// world frame, and a set of (noisy) translation directions of type Unit3, -// w_aZb. The measurement equation is -// w_aZb = Unit3(Tb - Ta) (1) -// i.e., w_aZb is the translation direction from frame A to B, in world -// coordinates. Although Unit3 instances live on a manifold, following -// Wilson14eccv_1DSfM.pdf error we compute the *chordal distance* in the -// ambient world coordinate frame. -// -// It is clear that we cannot recover the scale, nor the absolute position, -// so the gauge freedom in this case is 3 + 1 = 4. We fix these by taking fixing -// the translations Ta and Tb associated with the first measurement w_aZb, -// clamping them to their initial values as given to this method. If no initial -// values are given, we use the origin for Tb and set Tb to make (1) come -// through, i.e., -// Tb = s * wRa * Point3(w_aZb) (2) -// where s is an arbitrary scale that can be supplied, default 1.0. Hence, two -// versions are supplied below corresponding to whether we have initial values -// or not. Because the latter one is called from the first one, this is prime. - -class TranslationRecovery { - public: - using KeyPair = std::pair; - using TranslationEdges = std::map; - - private: - TranslationEdges relativeTranslations_; - LevenbergMarquardtParams params_; - - public: - /** - * @brief Construct a new Translation Recovery object - * - * @param relativeTranslations the relative translations, in world coordinate - * frames, indexed in a map by a pair of Pose keys. - */ - TranslationRecovery(const TranslationEdges& relativeTranslations) - : relativeTranslations_(relativeTranslations) { - params_.setVerbosityLM("Summary"); - } - - /** - * @brief Build the factor graph to do the optimization. - * - * @return NonlinearFactorGraph - */ - NonlinearFactorGraph buildGraph() const { - auto noiseModel = noiseModel::Isotropic::Sigma(3, 0.01); - NonlinearFactorGraph graph; - - // Add all relative translation edges - for (auto edge : relativeTranslations_) { - Key a, b; - std::tie(a, b) = edge.first; - const Unit3 w_aZb = edge.second; - graph.emplace_shared(a, b, w_aZb, noiseModel); - } - - return graph; - } - - /** - * @brief Add priors on ednpoints of first measurement edge. - * - * @param scale scale for first relative translation which fixes gauge. - * @param graph factor graph to which prior is added. - */ - void addPrior(const double scale, NonlinearFactorGraph* graph) const { - auto noiseModel = noiseModel::Isotropic::Sigma(3, 0.01); - auto edge = relativeTranslations_.begin(); - Key a, b; - std::tie(a, b) = edge->first; - const Unit3 w_aZb = edge->second; - graph->emplace_shared >(a, Point3(0, 0, 0), noiseModel); - graph->emplace_shared >(b, scale * w_aZb.point3(), - noiseModel); - } - - /** - * @brief Create random initial translations. - * - * @return Values - */ - Values initalizeRandomly() const { - Values initial; - auto insert = [&initial](Key j) { - if (!initial.exists(j)) { - initial.insert(j, Vector3::Random()); - } - }; - - // Loop over measurements and add a random translation - for (auto edge : relativeTranslations_) { - Key a, b; - std::tie(a, b) = edge.first; - insert(a); - insert(b); - } - return initial; - } - - /** - * @brief Build and optimize factor graph. - * - * @param scale scale for first relative translation which fixes gauge. - * @return Values - */ - Values run(const double scale = 1.0) const { - auto graph = buildGraph(); - addPrior(scale, &graph); - const Values initial = initalizeRandomly(); - LevenbergMarquardtOptimizer lm(graph, initial, params_); - Values result = lm.optimize(); - return result; - } - - /** - * @brief Simulate translation direction measurements - * - * @param poses SE(3) ground truth poses stored as Values - * @param edges pairs (a,b) for which a measurement w_aZb will be generated. - */ - static TranslationEdges SimulateMeasurements( - const Values& poses, const std::vector& edges) { - TranslationEdges relativeTranslations; - for (auto edge : edges) { - Key a, b; - std::tie(a, b) = edge; - const Pose3 wTa = poses.at(a), wTb = poses.at(b); - const Point3 Ta = wTa.translation(), Tb = wTb.translation(); - const Unit3 w_aZb(Tb - Ta); - relativeTranslations[edge] = w_aZb; - } - return relativeTranslations; - } -}; -} // namespace gtsam - -/* ---------------------------------------------------------------------------- - - * GTSAM Copyright 2010, Georgia Tech Research Corporation, + * GTSAM Copyright 2010-2020, Georgia Tech Research Corporation, * Atlanta, Georgia 30332-0415 * All Rights Reserved * Authors: Frank Dellaert, et al. (see THANKS for the full author list) @@ -187,6 +16,8 @@ class TranslationRecovery { * @brief test recovering translations when rotations are given. */ +#include + #include #include From 3a1653dd231d7983cd357761d4a785f6db5cd844 Mon Sep 17 00:00:00 2001 From: Binit Shah Date: Sun, 17 May 2020 15:44:11 -0400 Subject: [PATCH 035/869] Include corrupting noise param to parse3DFactors --- gtsam/slam/dataset.cpp | 17 +++++++++++++++-- gtsam/slam/dataset.h | 3 ++- 2 files changed, 17 insertions(+), 3 deletions(-) diff --git a/gtsam/slam/dataset.cpp b/gtsam/slam/dataset.cpp index 052bb3343..83636eb1d 100644 --- a/gtsam/slam/dataset.cpp +++ b/gtsam/slam/dataset.cpp @@ -541,10 +541,18 @@ std::map parse3DPoses(const string& filename) { } /* ************************************************************************* */ -BetweenFactorPose3s parse3DFactors(const string& filename) { +BetweenFactorPose3s parse3DFactors(const string& filename, + const noiseModel::Diagonal::shared_ptr& corruptingNoise) { ifstream is(filename.c_str()); if (!is) throw invalid_argument("parse3DFactors: can not find file " + filename); + // If asked, create a sampler with random number generator + Sampler sampler; + if (corruptingNoise) { + sampler = Sampler(corruptingNoise); + } + + std::vector::shared_ptr> factors; while (!is.eof()) { char buf[LINESIZE]; @@ -585,8 +593,13 @@ BetweenFactorPose3s parse3DFactors(const string& filename) { mgtsam.block<3, 3>(3, 0) = m.block<3, 3>(3, 0); // off diagonal SharedNoiseModel model = noiseModel::Gaussian::Information(mgtsam); + auto R12 = Rot3::Quaternion(qw, qx, qy, qz); + if (corruptingNoise) { + R12 = R12.retract(sampler.sample()); + } + factors.emplace_back(new BetweenFactor( - id1, id2, Pose3(Rot3::Quaternion(qw, qx, qy, qz), {x, y, z}), model)); + id1, id2, Pose3(R12, {x, y, z}), model)); } } return factors; diff --git a/gtsam/slam/dataset.h b/gtsam/slam/dataset.h index 3ab199bab..032799429 100644 --- a/gtsam/slam/dataset.h +++ b/gtsam/slam/dataset.h @@ -159,7 +159,8 @@ GTSAM_EXPORT void writeG2o(const NonlinearFactorGraph& graph, /// Parse edges in 3D TORO graph file into a set of BetweenFactors. using BetweenFactorPose3s = std::vector::shared_ptr>; -GTSAM_EXPORT BetweenFactorPose3s parse3DFactors(const std::string& filename); +GTSAM_EXPORT BetweenFactorPose3s parse3DFactors(const std::string& filename, + const noiseModel::Diagonal::shared_ptr& corruptingNoise=nullptr); /// Parse vertices in 3D TORO graph file into a map of Pose3s. GTSAM_EXPORT std::map parse3DPoses(const std::string& filename); From 9fc090165524f094ba93393440ecbc9dbdc8c483 Mon Sep 17 00:00:00 2001 From: Jose Luis Blanco-Claraco Date: Mon, 18 May 2020 08:30:00 +0200 Subject: [PATCH 036/869] more precise use of setZero() and add comments --- gtsam/base/SymmetricBlockMatrix.h | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/gtsam/base/SymmetricBlockMatrix.h b/gtsam/base/SymmetricBlockMatrix.h index 1ec9a5ad3..c2996109f 100644 --- a/gtsam/base/SymmetricBlockMatrix.h +++ b/gtsam/base/SymmetricBlockMatrix.h @@ -71,6 +71,7 @@ namespace gtsam { } /// Construct from a container of the sizes of each block. + /// Uninitialized blocks are filled with zeros. template SymmetricBlockMatrix(const CONTAINER& dimensions, bool appendOneDimension = false) : blockStart_(0) @@ -81,6 +82,7 @@ namespace gtsam { } /// Construct from iterator over the sizes of each vertical block. + /// Uninitialized blocks are filled with zeros. template SymmetricBlockMatrix(ITERATOR firstBlockDim, ITERATOR lastBlockDim, bool appendOneDimension = false) : blockStart_(0) @@ -95,7 +97,7 @@ namespace gtsam { SymmetricBlockMatrix(const CONTAINER& dimensions, const Matrix& matrix, bool appendOneDimension = false) : blockStart_(0) { - matrix_.setZero(matrix.rows(), matrix.cols()); + matrix_.resize(matrix.rows(), matrix.cols()); matrix_.triangularView() = matrix.triangularView(); fillOffsets(dimensions.begin(), dimensions.end(), appendOneDimension); if(matrix_.rows() != matrix_.cols()) From 537155dd05a0e21d095212084227438447514992 Mon Sep 17 00:00:00 2001 From: Binit Shah Date: Thu, 28 May 2020 04:36:35 -0400 Subject: [PATCH 037/869] Sampler initialized with noise argument --- gtsam/slam/dataset.cpp | 8 +------- 1 file changed, 1 insertion(+), 7 deletions(-) diff --git a/gtsam/slam/dataset.cpp b/gtsam/slam/dataset.cpp index 83636eb1d..0ed958869 100644 --- a/gtsam/slam/dataset.cpp +++ b/gtsam/slam/dataset.cpp @@ -546,13 +546,6 @@ BetweenFactorPose3s parse3DFactors(const string& filename, ifstream is(filename.c_str()); if (!is) throw invalid_argument("parse3DFactors: can not find file " + filename); - // If asked, create a sampler with random number generator - Sampler sampler; - if (corruptingNoise) { - sampler = Sampler(corruptingNoise); - } - - std::vector::shared_ptr> factors; while (!is.eof()) { char buf[LINESIZE]; @@ -595,6 +588,7 @@ BetweenFactorPose3s parse3DFactors(const string& filename, SharedNoiseModel model = noiseModel::Gaussian::Information(mgtsam); auto R12 = Rot3::Quaternion(qw, qx, qy, qz); if (corruptingNoise) { + Sampler sampler(corruptingNoise); R12 = R12.retract(sampler.sample()); } From 5556db54200d19e453b87b7ba2eea1da106f3b78 Mon Sep 17 00:00:00 2001 From: Binit Shah Date: Sat, 30 May 2020 17:35:22 -0400 Subject: [PATCH 038/869] Using optional sampler outside loop --- gtsam/slam/dataset.cpp | 11 ++++++++--- 1 file changed, 8 insertions(+), 3 deletions(-) diff --git a/gtsam/slam/dataset.cpp b/gtsam/slam/dataset.cpp index 0ed958869..66e8fc4c0 100644 --- a/gtsam/slam/dataset.cpp +++ b/gtsam/slam/dataset.cpp @@ -37,6 +37,7 @@ #include #include #include +#include #include #include @@ -546,6 +547,11 @@ BetweenFactorPose3s parse3DFactors(const string& filename, ifstream is(filename.c_str()); if (!is) throw invalid_argument("parse3DFactors: can not find file " + filename); + boost::optional sampler; + if (corruptingNoise) { + sampler = Sampler(corruptingNoise); + } + std::vector::shared_ptr> factors; while (!is.eof()) { char buf[LINESIZE]; @@ -587,9 +593,8 @@ BetweenFactorPose3s parse3DFactors(const string& filename, SharedNoiseModel model = noiseModel::Gaussian::Information(mgtsam); auto R12 = Rot3::Quaternion(qw, qx, qy, qz); - if (corruptingNoise) { - Sampler sampler(corruptingNoise); - R12 = R12.retract(sampler.sample()); + if (sampler) { + R12 = R12.retract(sampler->sample()); } factors.emplace_back(new BetweenFactor( From 1db0f441bcd91878e562c9ad61c1a958be082cf0 Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Sun, 31 May 2020 21:52:13 -0400 Subject: [PATCH 039/869] Added FunctorizedFactor and corresponding tests --- gtsam/linear/NoiseModel.cpp | 1 + gtsam/nonlinear/FunctorizedFactor.h | 123 +++++++++++++++++ .../nonlinear/tests/testFunctorizedFactor.cpp | 127 ++++++++++++++++++ 3 files changed, 251 insertions(+) create mode 100644 gtsam/nonlinear/FunctorizedFactor.h create mode 100644 gtsam/nonlinear/tests/testFunctorizedFactor.cpp diff --git a/gtsam/linear/NoiseModel.cpp b/gtsam/linear/NoiseModel.cpp index d7fd2d1ea..72ca054b4 100644 --- a/gtsam/linear/NoiseModel.cpp +++ b/gtsam/linear/NoiseModel.cpp @@ -619,6 +619,7 @@ void Isotropic::WhitenInPlace(Eigen::Block H) const { // Unit /* ************************************************************************* */ void Unit::print(const std::string& name) const { + //TODO(Varun): Do we need that space at the end? cout << name << "unit (" << dim_ << ") " << endl; } diff --git a/gtsam/nonlinear/FunctorizedFactor.h b/gtsam/nonlinear/FunctorizedFactor.h new file mode 100644 index 000000000..b990ac04f --- /dev/null +++ b/gtsam/nonlinear/FunctorizedFactor.h @@ -0,0 +1,123 @@ +/* ---------------------------------------------------------------------------- + + * GTSAM Copyright 2010, Georgia Tech Research Corporation, + * Atlanta, Georgia 30332-0415 + * All Rights Reserved + * Authors: Frank Dellaert, et al. (see THANKS for the full author list) + + * See LICENSE for the license information + + * -------------------------------------------------------------------------- */ + +/** + * @file FunctorizedFactor.h + * @author Varun Agrawal + **/ + +#pragma once + +#include +#include + +#include + +namespace gtsam { + +/** + * Factor which evaluates functor and uses the result to compute + * error on provided measurement. + * The provided FUNCTOR should provide two definitions: `argument_type` which + * corresponds to the type of input it accepts and `return_type` which indicates + * the type of the return value. This factor uses those type values to construct + * the functor. + * + * Template parameters are + * @param FUNCTOR: A class which operates as a functor. + */ +template +class GTSAM_EXPORT FunctorizedFactor + : public NoiseModelFactor1 { +private: + using T = typename FUNCTOR::argument_type; + using Base = NoiseModelFactor1; + + typename FUNCTOR::return_type + measured_; ///< value that is compared with functor return value + SharedNoiseModel noiseModel_; ///< noise model + FUNCTOR func_; ///< functor instance + +public: + /** default constructor - only use for serialization */ + FunctorizedFactor() {} + + /** Construct with given x and the parameters of the basis + * + * @param Args: Variadic template parameter for functor arguments. + * + * @param key: Factor key + * @param z: Measurement object of type FUNCTOR::return_type + * @param model: Noise model + * @param args: Variable number of arguments used to instantiate functor + */ + template + FunctorizedFactor(Key key, const typename FUNCTOR::return_type &z, + const SharedNoiseModel &model, Args &&... args) + : Base(model, key), measured_(z), noiseModel_(model), + func_(std::forward(args)...) {} + + virtual ~FunctorizedFactor() {} + + /// @return a deep copy of this factor + virtual NonlinearFactor::shared_ptr clone() const { + return boost::static_pointer_cast( + NonlinearFactor::shared_ptr(new FunctorizedFactor(*this))); + } + + Vector evaluateError(const T ¶ms, + boost::optional H = boost::none) const { + typename FUNCTOR::return_type x = func_(params, H); + Vector error = traits::Local(measured_, x); + return error; + } + + /// @name Testable + /// @{ + GTSAM_EXPORT friend std::ostream & + operator<<(std::ostream &os, const FunctorizedFactor &f) { + os << " noise model sigmas: " << f.noiseModel_->sigmas().transpose(); + return os; + } + void print(const std::string &s = "", + const KeyFormatter &keyFormatter = DefaultKeyFormatter) const { + Base::print(s, keyFormatter); + std::cout << s << (s != "" ? " " : "") << "FunctorizedFactor(" + << keyFormatter(this->key()) << ")" << std::endl; + traits::Print(measured_, " measurement: "); + std::cout << *this << std::endl; + } + + virtual bool equals(const NonlinearFactor &other, double tol = 1e-9) + const { + const FunctorizedFactor *e = + dynamic_cast*>(&other); + const bool base = Base::equals(*e, tol); + return e != nullptr && base; + } + /// @} + +private: + /** Serialization function */ + friend class boost::serialization::access; + template + void serialize(ARCHIVE &ar, const unsigned int /*version*/) { + ar &boost::serialization::make_nvp( + "NoiseModelFactor1", boost::serialization::base_object(*this)); + ar &BOOST_SERIALIZATION_NVP(measured_); + ar &BOOST_SERIALIZATION_NVP(func_); + } +}; + +// TODO(Varun): Include or kill? +// template <> struct traits : public Testable {}; + +} // namespace gtsam diff --git a/gtsam/nonlinear/tests/testFunctorizedFactor.cpp b/gtsam/nonlinear/tests/testFunctorizedFactor.cpp new file mode 100644 index 000000000..7536aadc5 --- /dev/null +++ b/gtsam/nonlinear/tests/testFunctorizedFactor.cpp @@ -0,0 +1,127 @@ +/* ---------------------------------------------------------------------------- + + * GTSAM Copyright 2010, Georgia Tech Research Corporation, + * Atlanta, Georgia 30332-0415 + * All Rights Reserved + * Authors: Frank Dellaert, et al. (see THANKS for the full author list) + + * See LICENSE for the license information + + * -------------------------------1------------------------------------------- + */ + +/** + * @file testFunctorizedFactor.cpp + * @date May 31, 2020 + * @author Varun Agrawal + * @brief unit tests for FunctorizedFactor class + */ + +#include +#include +#include + +#include + +using namespace std; +using namespace gtsam; + +Key keyX = Symbol('X', 0); +auto model = noiseModel::Isotropic::Sigma(3, 1); + +/// Functor that takes a matrix and multiplies every element by m +class MultiplyFunctor { + double m_; ///< simple multiplier + +public: + using argument_type = Matrix; + using return_type = Matrix; + + MultiplyFunctor(double m) : m_(m) {} + + Matrix operator()(const Matrix &X, + OptionalJacobian<-1, -1> H = boost::none) const { + return m_ * X; + } +}; + +TEST(FunctorizedFactor, Identity) { + + Matrix X = Matrix::Identity(3, 3); + + double multiplier = 1.0; + + FunctorizedFactor factor(keyX, X, model, multiplier); + + Values values; + values.insert(keyX, X); + + Matrix error = factor.evaluateError(X); + + EXPECT(assert_equal(Vector::Zero(9), error, 1e-9)); +} + +TEST(FunctorizedFactor, Multiply2) { + Matrix X = Matrix::Identity(3, 3); + + double multiplier = 2.0; + + FunctorizedFactor factor(keyX, X, model, multiplier); + + Values values; + values.insert(keyX, X); + + Matrix error = factor.evaluateError(X); + + Matrix expected = Matrix::Identity(3, 3); + expected.resize(9, 1); + EXPECT(assert_equal(expected, error, 1e-9)); +} + +TEST(FunctorizedFactor, Equality) { + Matrix X = Matrix::Identity(2, 2); + + double multiplier = 2.0; + + FunctorizedFactor factor1(keyX, X, model, multiplier); + FunctorizedFactor factor2(keyX, X, model, multiplier); + + EXPECT(factor1.equals(factor2)); +} + +TEST(FunctorizedFactor, Print) { + Matrix X = Matrix::Identity(2, 2); + + double multiplier = 2.0; + + FunctorizedFactor factor(keyX, X, model, multiplier); + + // redirect output to buffer so we can compare + stringstream buffer; + streambuf *old = cout.rdbuf(buffer.rdbuf()); + + factor.print(); + + // get output string and reset stdout + string actual = buffer.str(); + cout.rdbuf(old); + + string expected = " keys = { X0 }\n" + " noise model: unit (3) \n" + "FunctorizedFactor(X0)\n" + " measurement: [\n" + " 1, 0;\n" + " 0, 1\n" + "]\n" + " noise model sigmas: 1 1 1\n"; + + CHECK_EQUAL(expected, actual); +} + +/* ************************************************************************* + */ +int main() { + TestResult tr; + return TestRegistry::runAllTests(tr); +} +/* ************************************************************************* */ From 131213a983521b2095f15d3ce0d798645f513538 Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Mon, 1 Jun 2020 19:52:50 -0400 Subject: [PATCH 040/869] fixes, better tests, docs --- gtsam/nonlinear/FunctorizedFactor.h | 58 +++++++++++------ .../nonlinear/tests/testFunctorizedFactor.cpp | 62 ++++++++++++------- 2 files changed, 78 insertions(+), 42 deletions(-) diff --git a/gtsam/nonlinear/FunctorizedFactor.h b/gtsam/nonlinear/FunctorizedFactor.h index b990ac04f..03fd47a46 100644 --- a/gtsam/nonlinear/FunctorizedFactor.h +++ b/gtsam/nonlinear/FunctorizedFactor.h @@ -10,8 +10,9 @@ * -------------------------------------------------------------------------- */ /** - * @file FunctorizedFactor.h - * @author Varun Agrawal + * @file FunctorizedFactor.h + * @date May 31, 2020 + * @author Varun Agrawal **/ #pragma once @@ -26,13 +27,35 @@ namespace gtsam { /** * Factor which evaluates functor and uses the result to compute * error on provided measurement. - * The provided FUNCTOR should provide two definitions: `argument_type` which + * The provided FUNCTOR should provide two type aliases: `argument_type` which * corresponds to the type of input it accepts and `return_type` which indicates * the type of the return value. This factor uses those type values to construct * the functor. * * Template parameters are * @param FUNCTOR: A class which operates as a functor. + * + * Example: + * Key key = Symbol('X', 0); + * + * auto model = noiseModel::Isotropic::Sigma(9, 1); + * /// Functor that takes a matrix and multiplies every element by m + * class MultiplyFunctor { + * double m_; ///< simple multiplier + * public: + * using argument_type = Matrix; + * using return_type = Matrix; + * MultiplyFunctor(double m) : m_(m) {} + * Matrix operator()(const Matrix &X, + * OptionalJacobian<-1, -1> H = boost::none) const { + * if (H) *H = m_ * Matrix::Identity(X.rows()*X.cols(), X.rows()*X.cols()); + * return m_ * X; + * } + * }; + * + * Matrix measurement = Matrix::Identity(3, 3); + * double multiplier = 2.0; + * FunctorizedFactor factor(keyX, measurement, model, multiplier); */ template class GTSAM_EXPORT FunctorizedFactor @@ -82,27 +105,24 @@ public: /// @name Testable /// @{ - GTSAM_EXPORT friend std::ostream & - operator<<(std::ostream &os, const FunctorizedFactor &f) { - os << " noise model sigmas: " << f.noiseModel_->sigmas().transpose(); - return os; - } void print(const std::string &s = "", const KeyFormatter &keyFormatter = DefaultKeyFormatter) const { Base::print(s, keyFormatter); std::cout << s << (s != "" ? " " : "") << "FunctorizedFactor(" << keyFormatter(this->key()) << ")" << std::endl; traits::Print(measured_, " measurement: "); - std::cout << *this << std::endl; + std::cout << " noise model sigmas: " << noiseModel_->sigmas().transpose() + << std::endl; } - virtual bool equals(const NonlinearFactor &other, double tol = 1e-9) - const { - const FunctorizedFactor *e = - dynamic_cast*>(&other); - const bool base = Base::equals(*e, tol); - return e != nullptr && base; - } + virtual bool equals(const NonlinearFactor &other, double tol = 1e-9) const { + const FunctorizedFactor *e = + dynamic_cast *>(&other); + const bool base = Base::equals(*e, tol); + return e && Base::equals(other, tol) && + traits::Equals(this->measured_, e->measured_, + tol); + } /// @} private: @@ -117,7 +137,9 @@ private: } }; -// TODO(Varun): Include or kill? -// template <> struct traits : public Testable {}; +/// traits +template +struct traits> + : public Testable> {}; } // namespace gtsam diff --git a/gtsam/nonlinear/tests/testFunctorizedFactor.cpp b/gtsam/nonlinear/tests/testFunctorizedFactor.cpp index 7536aadc5..9393a4410 100644 --- a/gtsam/nonlinear/tests/testFunctorizedFactor.cpp +++ b/gtsam/nonlinear/tests/testFunctorizedFactor.cpp @@ -20,14 +20,15 @@ #include #include #include +#include #include using namespace std; using namespace gtsam; -Key keyX = Symbol('X', 0); -auto model = noiseModel::Isotropic::Sigma(3, 1); +Key key = Symbol('X', 0); +auto model = noiseModel::Isotropic::Sigma(9, 1); /// Functor that takes a matrix and multiplies every element by m class MultiplyFunctor { @@ -41,60 +42,73 @@ public: Matrix operator()(const Matrix &X, OptionalJacobian<-1, -1> H = boost::none) const { + if (H) + *H = m_ * Matrix::Identity(X.rows() * X.cols(), X.rows() * X.cols()); return m_ * X; } }; TEST(FunctorizedFactor, Identity) { - Matrix X = Matrix::Identity(3, 3); + Matrix X = Matrix::Identity(3, 3), measurement = Matrix::Identity(3, 3); double multiplier = 1.0; - FunctorizedFactor factor(keyX, X, model, multiplier); + FunctorizedFactor factor(key, measurement, model, + multiplier); - Values values; - values.insert(keyX, X); - - Matrix error = factor.evaluateError(X); + Vector error = factor.evaluateError(X); EXPECT(assert_equal(Vector::Zero(9), error, 1e-9)); } TEST(FunctorizedFactor, Multiply2) { - Matrix X = Matrix::Identity(3, 3); - double multiplier = 2.0; + Matrix X = Matrix::Identity(3, 3); + Matrix measurement = multiplier * Matrix::Identity(3, 3); - FunctorizedFactor factor(keyX, X, model, multiplier); + FunctorizedFactor factor(key, measurement, model, multiplier); - Values values; - values.insert(keyX, X); + Vector error = factor.evaluateError(X); - Matrix error = factor.evaluateError(X); - - Matrix expected = Matrix::Identity(3, 3); - expected.resize(9, 1); - EXPECT(assert_equal(expected, error, 1e-9)); + EXPECT(assert_equal(Vector::Zero(9), error, 1e-9)); } TEST(FunctorizedFactor, Equality) { - Matrix X = Matrix::Identity(2, 2); + Matrix measurement = Matrix::Identity(2, 2); double multiplier = 2.0; - FunctorizedFactor factor1(keyX, X, model, multiplier); - FunctorizedFactor factor2(keyX, X, model, multiplier); + FunctorizedFactor factor1(key, measurement, model, + multiplier); + FunctorizedFactor factor2(key, measurement, model, + multiplier); EXPECT(factor1.equals(factor2)); } +//****************************************************************************** +TEST(FunctorizedFactor, Jacobians) { + Matrix X = Matrix::Identity(3, 3); + Matrix actualH; + + double multiplier = 2.0; + + FunctorizedFactor factor(key, X, model, multiplier); + + Values values; + values.insert(key, X); + + // Check Jacobians + EXPECT_CORRECT_FACTOR_JACOBIANS(factor, values, 1e-7, 1e-5); +} + TEST(FunctorizedFactor, Print) { Matrix X = Matrix::Identity(2, 2); double multiplier = 2.0; - FunctorizedFactor factor(keyX, X, model, multiplier); + FunctorizedFactor factor(key, X, model, multiplier); // redirect output to buffer so we can compare stringstream buffer; @@ -107,13 +121,13 @@ TEST(FunctorizedFactor, Print) { cout.rdbuf(old); string expected = " keys = { X0 }\n" - " noise model: unit (3) \n" + " noise model: unit (9) \n" "FunctorizedFactor(X0)\n" " measurement: [\n" " 1, 0;\n" " 0, 1\n" "]\n" - " noise model sigmas: 1 1 1\n"; + " noise model sigmas: 1 1 1 1 1 1 1 1 1\n"; CHECK_EQUAL(expected, actual); } From ea8b319c43ea64b563792c3c2b8d9ccdd298c5cc Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Mon, 1 Jun 2020 19:54:04 -0400 Subject: [PATCH 041/869] remove TODO --- gtsam/linear/NoiseModel.cpp | 1 - 1 file changed, 1 deletion(-) diff --git a/gtsam/linear/NoiseModel.cpp b/gtsam/linear/NoiseModel.cpp index 72ca054b4..d7fd2d1ea 100644 --- a/gtsam/linear/NoiseModel.cpp +++ b/gtsam/linear/NoiseModel.cpp @@ -619,7 +619,6 @@ void Isotropic::WhitenInPlace(Eigen::Block H) const { // Unit /* ************************************************************************* */ void Unit::print(const std::string& name) const { - //TODO(Varun): Do we need that space at the end? cout << name << "unit (" << dim_ << ") " << endl; } From 0bbb39687f5c1b4f2e34e288786a9acd58a7e17d Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Mon, 1 Jun 2020 19:55:10 -0400 Subject: [PATCH 042/869] improved documentation --- gtsam/nonlinear/FunctorizedFactor.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/gtsam/nonlinear/FunctorizedFactor.h b/gtsam/nonlinear/FunctorizedFactor.h index 03fd47a46..82d2f822e 100644 --- a/gtsam/nonlinear/FunctorizedFactor.h +++ b/gtsam/nonlinear/FunctorizedFactor.h @@ -37,8 +37,8 @@ namespace gtsam { * * Example: * Key key = Symbol('X', 0); - * * auto model = noiseModel::Isotropic::Sigma(9, 1); + * * /// Functor that takes a matrix and multiplies every element by m * class MultiplyFunctor { * double m_; ///< simple multiplier From 7486ed7993208fa27f9b61c23cd7509e26df6906 Mon Sep 17 00:00:00 2001 From: Martin Vonheim Larsen Date: Tue, 2 Jun 2020 13:02:10 +0200 Subject: [PATCH 043/869] Added test for Unit3::operator= --- gtsam/geometry/tests/testUnit3.cpp | 9 +++++++++ 1 file changed, 9 insertions(+) diff --git a/gtsam/geometry/tests/testUnit3.cpp b/gtsam/geometry/tests/testUnit3.cpp index a25ab25c7..0f98e4648 100644 --- a/gtsam/geometry/tests/testUnit3.cpp +++ b/gtsam/geometry/tests/testUnit3.cpp @@ -484,6 +484,15 @@ TEST(Unit3, ErrorBetweenFactor) { } } +TEST(Unit3, copy_assign) { + Unit3 p{1, 0.2, 0.3}; + + EXPECT(p.error(p).isZero()); + + p = Unit3{-1, 2, 8}; + EXPECT(p.error(p).isZero()); +} + /* ************************************************************************* */ TEST(actualH, Serialization) { Unit3 p(0, 1, 0); From bc7f5e6da75c9011999ddab39e5d9d7f857703e1 Mon Sep 17 00:00:00 2001 From: Martin Vonheim Larsen Date: Tue, 2 Jun 2020 13:02:22 +0200 Subject: [PATCH 044/869] Properly handle basis in Unit3::operator= If the basis was already cached we reset it to the cached basis of `u`. --- gtsam/geometry/Unit3.h | 2 ++ 1 file changed, 2 insertions(+) diff --git a/gtsam/geometry/Unit3.h b/gtsam/geometry/Unit3.h index f1a9c1a69..24a8c0219 100644 --- a/gtsam/geometry/Unit3.h +++ b/gtsam/geometry/Unit3.h @@ -90,6 +90,8 @@ public: /// Copy assignment Unit3& operator=(const Unit3 & u) { p_ = u.p_; + B_ = u.B_; + H_B_ = u.H_B_; return *this; } From d0bd3d87154f411a66e2cd3ca2e537e46f47568e Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Tue, 2 Jun 2020 15:13:30 -0500 Subject: [PATCH 045/869] removed dependency on Eigen3 since we provide Eigen 3.3.7 and Ubuntu Bionic provides Eigen 3.3.4. --- .../Dockerfile | 6 +----- 1 file changed, 1 insertion(+), 5 deletions(-) rename docker/{ubuntu-boost-tbb-eigen3 => ubuntu-boost-tbb}/Dockerfile (72%) diff --git a/docker/ubuntu-boost-tbb-eigen3/Dockerfile b/docker/ubuntu-boost-tbb/Dockerfile similarity index 72% rename from docker/ubuntu-boost-tbb-eigen3/Dockerfile rename to docker/ubuntu-boost-tbb/Dockerfile index 33aa1ab96..6dd9dfa62 100644 --- a/docker/ubuntu-boost-tbb-eigen3/Dockerfile +++ b/docker/ubuntu-boost-tbb/Dockerfile @@ -2,7 +2,7 @@ FROM ubuntu:bionic # Update apps on the base image -RUN apt-get -y update && apt-get install -y +RUN apt-get -y update && apt install -y # Install C++ RUN apt-get -y install build-essential @@ -12,7 +12,3 @@ RUN apt-get -y install libboost-all-dev cmake # Install TBB RUN apt-get -y install libtbb-dev - -# Install latest Eigen -RUN apt-get install -y libeigen3-dev - From a6e9b0287e1c72384d982226c8b167e79be21f2b Mon Sep 17 00:00:00 2001 From: "Martin V. Larsen" Date: Tue, 2 Jun 2020 22:20:35 +0200 Subject: [PATCH 046/869] Update testUnit3.cpp --- gtsam/geometry/tests/testUnit3.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/gtsam/geometry/tests/testUnit3.cpp b/gtsam/geometry/tests/testUnit3.cpp index 0f98e4648..ddf60a256 100644 --- a/gtsam/geometry/tests/testUnit3.cpp +++ b/gtsam/geometry/tests/testUnit3.cpp @@ -484,7 +484,7 @@ TEST(Unit3, ErrorBetweenFactor) { } } -TEST(Unit3, copy_assign) { +TEST(Unit3, CopyAssign) { Unit3 p{1, 0.2, 0.3}; EXPECT(p.error(p).isZero()); From 92634d152513f1acc8f878421fe17b7c9781b936 Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Tue, 2 Jun 2020 16:33:57 -0500 Subject: [PATCH 047/869] improve and modernize the Dockerfiles --- docker/ubuntu-boost-tbb/Dockerfile | 9 +++++++-- docker/ubuntu-gtsam-python-vnc/Dockerfile | 8 +++++--- docker/ubuntu-gtsam-python/Dockerfile | 12 +++++++----- docker/ubuntu-gtsam/Dockerfile | 11 ++++++----- 4 files changed, 25 insertions(+), 15 deletions(-) diff --git a/docker/ubuntu-boost-tbb/Dockerfile b/docker/ubuntu-boost-tbb/Dockerfile index 6dd9dfa62..9f6eea3b8 100644 --- a/docker/ubuntu-boost-tbb/Dockerfile +++ b/docker/ubuntu-boost-tbb/Dockerfile @@ -1,11 +1,16 @@ +# Basic Ubuntu 18.04 image with Boost and TBB installed. To be used for building further downstream packages. + # Get the base Ubuntu image from Docker Hub FROM ubuntu:bionic +# Disable GUI prompts +ENV DEBIAN_FRONTEND noninteractive + # Update apps on the base image -RUN apt-get -y update && apt install -y +RUN apt-get -y update && apt-get -y install # Install C++ -RUN apt-get -y install build-essential +RUN apt-get -y install build-essential apt-utils # Install boost and cmake RUN apt-get -y install libboost-all-dev cmake diff --git a/docker/ubuntu-gtsam-python-vnc/Dockerfile b/docker/ubuntu-gtsam-python-vnc/Dockerfile index 83222881a..8b6b97f46 100644 --- a/docker/ubuntu-gtsam-python-vnc/Dockerfile +++ b/docker/ubuntu-gtsam-python-vnc/Dockerfile @@ -1,16 +1,18 @@ +# This GTSAM image connects to the host X-server via VNC to provide a Graphical User Interface for interaction. + # Get the base Ubuntu/GTSAM image from Docker Hub FROM dellaert/ubuntu-gtsam-python:bionic # Things needed to get a python GUI ENV DEBIAN_FRONTEND noninteractive -RUN apt-get install -y python-tk +RUN apt install -y python-tk RUN pip install matplotlib # Install a VNC X-server, Frame buffer, and windows manager -RUN apt-get install -y x11vnc xvfb fluxbox +RUN apt install -y x11vnc xvfb fluxbox # Finally, install wmctrl needed for bootstrap script -RUN apt-get install -y wmctrl +RUN apt install -y wmctrl # Copy bootstrap script and make sure it runs COPY bootstrap.sh / diff --git a/docker/ubuntu-gtsam-python/Dockerfile b/docker/ubuntu-gtsam-python/Dockerfile index 0c7d131be..a9a9782f4 100644 --- a/docker/ubuntu-gtsam-python/Dockerfile +++ b/docker/ubuntu-gtsam-python/Dockerfile @@ -1,29 +1,31 @@ +# GTSAM Ubuntu image with Python wrapper support. + # Get the base Ubuntu/GTSAM image from Docker Hub -FROM dellaert/ubuntu-gtsam:bionic +FROM dellaert/ubuntu-gtsam:latest # Install pip -RUN apt-get install -y python-pip python-dev +RUN apt-get install -y python3-pip python3-dev # Install python wrapper requirements -RUN pip install -r /usr/src/gtsam/cython/requirements.txt +RUN pip3 install -U -r /usr/src/gtsam/cython/requirements.txt # Run cmake again, now with cython toolbox on WORKDIR /usr/src/gtsam/build RUN cmake \ -DCMAKE_BUILD_TYPE=Release \ - -DGTSAM_USE_SYSTEM_EIGEN=ON \ -DGTSAM_WITH_EIGEN_MKL=OFF \ -DGTSAM_BUILD_EXAMPLES_ALWAYS=OFF \ -DGTSAM_BUILD_TIMING_ALWAYS=OFF \ -DGTSAM_BUILD_TESTS=OFF \ -DGTSAM_INSTALL_CYTHON_TOOLBOX=ON \ + -DGTSAM_PYTHON_VERSION=3\ .. # Build again, as ubuntu-gtsam image cleaned RUN make -j3 install && make clean # Needed to run python wrapper: -RUN echo 'export PYTHONPATH=/usr/local/cython/' >> /root/.bashrc +RUN echo 'export PYTHONPATH=/usr/local/cython/:$PYTHONPATH' >> /root/.bashrc # Run bash CMD ["bash"] diff --git a/docker/ubuntu-gtsam/Dockerfile b/docker/ubuntu-gtsam/Dockerfile index bdfa8d9a5..c09d4b16a 100644 --- a/docker/ubuntu-gtsam/Dockerfile +++ b/docker/ubuntu-gtsam/Dockerfile @@ -1,5 +1,7 @@ +# Ubuntu image with GTSAM installed. Configured with Boost and TBB support. + # Get the base Ubuntu image from Docker Hub -FROM dellaert/ubuntu-boost-tbb-eigen3:bionic +FROM dellaert/ubuntu-boost-tbb:latest # Install git RUN apt-get update && \ @@ -11,13 +13,12 @@ RUN apt-get install -y build-essential # Clone GTSAM WORKDIR /usr/src/ RUN git clone https://bitbucket.org/gtborg/gtsam.git +RUN mkdir build # Run cmake -RUN mkdir /usr/src/gtsam/build WORKDIR /usr/src/gtsam/build RUN cmake \ -DCMAKE_BUILD_TYPE=Release \ - -DGTSAM_USE_SYSTEM_EIGEN=ON \ -DGTSAM_WITH_EIGEN_MKL=OFF \ -DGTSAM_BUILD_EXAMPLES_ALWAYS=OFF \ -DGTSAM_BUILD_TIMING_ALWAYS=OFF \ @@ -26,10 +27,10 @@ RUN cmake \ .. # Build -RUN make -j3 install && make clean +RUN make -j4 install && make clean # Needed to link with GTSAM -RUN echo 'export LD_LIBRARY_PATH=/usr/local/lib' >> /root/.bashrc +RUN echo 'export LD_LIBRARY_PATH=/usr/local/lib:LD_LIBRARY_PATH' >> /root/.bashrc # Run bash CMD ["bash"] From 8b66960a42d30cb8dfb0e3a7be08e76f9fcfec30 Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Tue, 2 Jun 2020 17:02:14 -0500 Subject: [PATCH 048/869] small logistical fixes --- docker/ubuntu-gtsam-python-vnc/Dockerfile | 2 +- docker/ubuntu-gtsam-python/Dockerfile | 4 ++-- docker/ubuntu-gtsam/Dockerfile | 8 ++++---- 3 files changed, 7 insertions(+), 7 deletions(-) diff --git a/docker/ubuntu-gtsam-python-vnc/Dockerfile b/docker/ubuntu-gtsam-python-vnc/Dockerfile index 8b6b97f46..26f995c56 100644 --- a/docker/ubuntu-gtsam-python-vnc/Dockerfile +++ b/docker/ubuntu-gtsam-python-vnc/Dockerfile @@ -1,7 +1,7 @@ # This GTSAM image connects to the host X-server via VNC to provide a Graphical User Interface for interaction. # Get the base Ubuntu/GTSAM image from Docker Hub -FROM dellaert/ubuntu-gtsam-python:bionic +FROM dellaert/ubuntu-gtsam-python:latest # Things needed to get a python GUI ENV DEBIAN_FRONTEND noninteractive diff --git a/docker/ubuntu-gtsam-python/Dockerfile b/docker/ubuntu-gtsam-python/Dockerfile index a9a9782f4..71787d480 100644 --- a/docker/ubuntu-gtsam-python/Dockerfile +++ b/docker/ubuntu-gtsam-python/Dockerfile @@ -7,7 +7,7 @@ FROM dellaert/ubuntu-gtsam:latest RUN apt-get install -y python3-pip python3-dev # Install python wrapper requirements -RUN pip3 install -U -r /usr/src/gtsam/cython/requirements.txt +RUN python3 -m pip install -U -r /usr/src/gtsam/cython/requirements.txt # Run cmake again, now with cython toolbox on WORKDIR /usr/src/gtsam/build @@ -22,7 +22,7 @@ RUN cmake \ .. # Build again, as ubuntu-gtsam image cleaned -RUN make -j3 install && make clean +RUN make -j4 install && make clean # Needed to run python wrapper: RUN echo 'export PYTHONPATH=/usr/local/cython/:$PYTHONPATH' >> /root/.bashrc diff --git a/docker/ubuntu-gtsam/Dockerfile b/docker/ubuntu-gtsam/Dockerfile index c09d4b16a..393443361 100644 --- a/docker/ubuntu-gtsam/Dockerfile +++ b/docker/ubuntu-gtsam/Dockerfile @@ -10,13 +10,13 @@ RUN apt-get update && \ # Install compiler RUN apt-get install -y build-essential -# Clone GTSAM +# Clone GTSAM (develop branch) WORKDIR /usr/src/ -RUN git clone https://bitbucket.org/gtborg/gtsam.git -RUN mkdir build +RUN git clone --single-branch --branch develop https://github.com/borglab/gtsam.git -# Run cmake +# Change to build directory. Will be created automatically. WORKDIR /usr/src/gtsam/build +# Run cmake RUN cmake \ -DCMAKE_BUILD_TYPE=Release \ -DGTSAM_WITH_EIGEN_MKL=OFF \ From 780345bc2764753aae8fbf277dfe477375eff59e Mon Sep 17 00:00:00 2001 From: Gerry Chen Date: Tue, 9 Jun 2020 02:24:58 -0400 Subject: [PATCH 049/869] put file stream inside scope to force buffer flush This was already fixed for serializeXML but not for serializeToXMLFile or deserializeFromXMLFile. --- gtsam/base/serialization.h | 12 ++++-- gtsam/base/serializationTestHelpers.h | 57 +++++++++++++++++++++++++++ 2 files changed, 65 insertions(+), 4 deletions(-) diff --git a/gtsam/base/serialization.h b/gtsam/base/serialization.h index e475465de..088029903 100644 --- a/gtsam/base/serialization.h +++ b/gtsam/base/serialization.h @@ -106,8 +106,10 @@ bool serializeToXMLFile(const T& input, const std::string& filename, const std:: std::ofstream out_archive_stream(filename.c_str()); if (!out_archive_stream.is_open()) return false; - boost::archive::xml_oarchive out_archive(out_archive_stream); - out_archive << boost::serialization::make_nvp(name.c_str(), input);; + { + boost::archive::xml_oarchive out_archive(out_archive_stream); + out_archive << boost::serialization::make_nvp(name.c_str(), input);; + } out_archive_stream.close(); return true; } @@ -117,8 +119,10 @@ bool deserializeFromXMLFile(const std::string& filename, T& output, const std::s std::ifstream in_archive_stream(filename.c_str()); if (!in_archive_stream.is_open()) return false; - boost::archive::xml_iarchive in_archive(in_archive_stream); - in_archive >> boost::serialization::make_nvp(name.c_str(), output); + { + boost::archive::xml_iarchive in_archive(in_archive_stream); + in_archive >> boost::serialization::make_nvp(name.c_str(), output); + } in_archive_stream.close(); return true; } diff --git a/gtsam/base/serializationTestHelpers.h b/gtsam/base/serializationTestHelpers.h index 06b3462e9..178b256a6 100644 --- a/gtsam/base/serializationTestHelpers.h +++ b/gtsam/base/serializationTestHelpers.h @@ -26,6 +26,7 @@ #include #include +#include // whether to print the serialized text to stdout @@ -40,6 +41,13 @@ T create() { return T(); } +std::string resetFilesystem() { + // Create files in folder in build folder + boost::filesystem::remove_all("actual"); + boost::filesystem::create_directory("actual"); + return "actual/"; +} + // Templated round-trip serialization template void roundtrip(const T& input, T& output) { @@ -50,11 +58,22 @@ void roundtrip(const T& input, T& output) { deserialize(serialized, output); } +// Templated round-trip serialization using a file +template +void roundtripFile(const T& input, T& output) { + std::string path = resetFilesystem(); + + serializeToFile(input, path + "graph.dat"); + deserializeFromFile(path + "graph.dat", output); +} + // This version requires equality operator template bool equality(const T& input = T()) { T output = create(); roundtrip(input,output); + if (input != output) return false; + roundtripFile(input,output); return input==output; } @@ -63,6 +82,8 @@ template bool equalsObj(const T& input = T()) { T output = create(); roundtrip(input,output); + if (!assert_equal(input, output)) return false; + roundtripFile(input,output); return assert_equal(input, output); } @@ -71,6 +92,8 @@ template bool equalsDereferenced(const T& input) { T output = create(); roundtrip(input,output); + if (!input->equals(*output)) return false; + roundtripFile(input,output); return input->equals(*output); } @@ -85,11 +108,25 @@ void roundtripXML(const T& input, T& output) { deserializeXML(serialized, output); } +// Templated round-trip serialization using XML File +template +void roundtripXMLFile(const T& input, T& output) { + std::string path = resetFilesystem(); + + // Serialize + serializeToXMLFile(input, path + "graph.xml"); + + // De-serialize + deserializeFromXMLFile(path + "graph.xml", output); +} + // This version requires equality operator template bool equalityXML(const T& input = T()) { T output = create(); roundtripXML(input,output); + if (input != output) return false; + roundtripXMLFile(input,output); return input==output; } @@ -98,6 +135,8 @@ template bool equalsXML(const T& input = T()) { T output = create(); roundtripXML(input,output); + if (!assert_equal(input, output)) return false; + roundtripXMLFile(input, output); return assert_equal(input, output); } @@ -106,6 +145,8 @@ template bool equalsDereferencedXML(const T& input = T()) { T output = create(); roundtripXML(input,output); + if (!input->equals(*output)) return false; + roundtripXMLFile(input, output); return input->equals(*output); } @@ -120,11 +161,23 @@ void roundtripBinary(const T& input, T& output) { deserializeBinary(serialized, output); } +// Templated round-trip serialization using XML +template +void roundtripBinaryFile(const T& input, T& output) { + std::string path = resetFilesystem(); + // Serialize + serializeToBinaryFile(input, path + "graph.bin"); + // De-serialize + deserializeFromBinaryFile(path + "graph.bin", output); +} + // This version requires equality operator template bool equalityBinary(const T& input = T()) { T output = create(); roundtripBinary(input,output); + if (input != output) return false; + roundtripBinaryFile(input,output); return input==output; } @@ -133,6 +186,8 @@ template bool equalsBinary(const T& input = T()) { T output = create(); roundtripBinary(input,output); + if (!assert_equal(input, output)) return false; + roundtripBinaryFile(input,output); return assert_equal(input, output); } @@ -141,6 +196,8 @@ template bool equalsDereferencedBinary(const T& input = T()) { T output = create(); roundtripBinary(input,output); + if (!input->equals(*output)) return false; + roundtripBinaryFile(input,output); return input->equals(*output); } From c94736b6b6959820efe628d52cc8cd17c0269cdc Mon Sep 17 00:00:00 2001 From: Gerry Chen Date: Tue, 9 Jun 2020 02:39:54 -0400 Subject: [PATCH 050/869] bypass assert_equal tests for file roundtrips --- gtsam/base/serializationTestHelpers.h | 6 ------ 1 file changed, 6 deletions(-) diff --git a/gtsam/base/serializationTestHelpers.h b/gtsam/base/serializationTestHelpers.h index 178b256a6..d29899072 100644 --- a/gtsam/base/serializationTestHelpers.h +++ b/gtsam/base/serializationTestHelpers.h @@ -82,8 +82,6 @@ template bool equalsObj(const T& input = T()) { T output = create(); roundtrip(input,output); - if (!assert_equal(input, output)) return false; - roundtripFile(input,output); return assert_equal(input, output); } @@ -135,8 +133,6 @@ template bool equalsXML(const T& input = T()) { T output = create(); roundtripXML(input,output); - if (!assert_equal(input, output)) return false; - roundtripXMLFile(input, output); return assert_equal(input, output); } @@ -186,8 +182,6 @@ template bool equalsBinary(const T& input = T()) { T output = create(); roundtripBinary(input,output); - if (!assert_equal(input, output)) return false; - roundtripBinaryFile(input,output); return assert_equal(input, output); } From 686b0effbf4e6d222ed26c17d2c00bb7dc878551 Mon Sep 17 00:00:00 2001 From: Gerry Chen Date: Tue, 9 Jun 2020 02:48:53 -0400 Subject: [PATCH 051/869] better comments on serializationTestHelper functions --- gtsam/base/serializationTestHelpers.h | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/gtsam/base/serializationTestHelpers.h b/gtsam/base/serializationTestHelpers.h index d29899072..031a6278f 100644 --- a/gtsam/base/serializationTestHelpers.h +++ b/gtsam/base/serializationTestHelpers.h @@ -41,8 +41,8 @@ T create() { return T(); } +// Creates or empties a folder in the build folder and returns the relative path std::string resetFilesystem() { - // Create files in folder in build folder boost::filesystem::remove_all("actual"); boost::filesystem::create_directory("actual"); return "actual/"; @@ -157,7 +157,7 @@ void roundtripBinary(const T& input, T& output) { deserializeBinary(serialized, output); } -// Templated round-trip serialization using XML +// Templated round-trip serialization using Binary file template void roundtripBinaryFile(const T& input, T& output) { std::string path = resetFilesystem(); From ab88471c2a5383e6e094e8c5674aa86e9398a4b8 Mon Sep 17 00:00:00 2001 From: Jose Luis Blanco-Claraco Date: Wed, 10 Jun 2020 10:06:16 +0200 Subject: [PATCH 052/869] unhide doc section in PDF --- doc/gtsam-coordinate-frames.lyx | 17 ++++------------- doc/gtsam-coordinate-frames.pdf | Bin 80806 -> 121711 bytes 2 files changed, 4 insertions(+), 13 deletions(-) diff --git a/doc/gtsam-coordinate-frames.lyx b/doc/gtsam-coordinate-frames.lyx index 33d0dd977..cfb44696b 100644 --- a/doc/gtsam-coordinate-frames.lyx +++ b/doc/gtsam-coordinate-frames.lyx @@ -2291,15 +2291,11 @@ uncalibration used in the residual). \end_layout -\begin_layout Standard -\begin_inset Note Note -status collapsed - \begin_layout Section Noise models of prior factors \end_layout -\begin_layout Plain Layout +\begin_layout Standard The simplest way to describe noise models is by an example. Let's take a prior factor on a 3D pose \begin_inset Formula $x\in\SE 3$ @@ -2353,7 +2349,7 @@ e\left(x\right)=\norm{h\left(x\right)}_{\Sigma}^{2}=h\left(x\right)^{\t}\Sigma^{ useful answer out quickly ] \end_layout -\begin_layout Plain Layout +\begin_layout Standard The density induced by a noise model on the prior factor is Gaussian in the tangent space about the linearization point. Suppose that the pose is linearized at @@ -2431,7 +2427,7 @@ Here we see that the update . \end_layout -\begin_layout Plain Layout +\begin_layout Standard This means that to draw random pose samples, we actually draw random samples of \begin_inset Formula $\delta x$ @@ -2456,7 +2452,7 @@ This means that to draw random pose samples, we actually draw random samples Noise models of between factors \end_layout -\begin_layout Plain Layout +\begin_layout Standard The noise model of a BetweenFactor is a bit more complicated. The unwhitened error is \begin_inset Formula @@ -2516,11 +2512,6 @@ e\left(\delta x_{1}\right) & \approx\norm{\log\left(z^{-1}\left(x_{1}\exp\delta \end_inset -\end_layout - -\end_inset - - \end_layout \end_body diff --git a/doc/gtsam-coordinate-frames.pdf b/doc/gtsam-coordinate-frames.pdf index 3613ef0ac82176c8a82e6ff0fc5fd7e05ed19c87..77910b4cf3b26b20020515cb885e2b4c1222dd05 100644 GIT binary patch delta 118821 zcmZs>Q+TFb(5)NWwr$%^$4&Tq6F zca1ShpP;UqVH0rB5rl*gSQRZCt=z21I5_xu$dUu6Xn{>VeWyJhoPgMC! zVwtEGIIq-2CQuaz`=v*$XxM1c)Kii*Y|QcC22{8WeyZD+;612UotJKR>zGT?p*29X zKJ+|4z*FMMZ=quaip9d=jWr#^Z9xas1=1Dixi_zA)h_p*9BcO;Pi^v=9D9|}-NQ9O{)sHS6OruHodHEV2kcLh zjSp0b_m1mZC45uN;b~1L*O|`u0t*8RVQ0mpqY-Xc^d`gN_kzDGgDi{zD+HlXPP_J; z2owd1K8j%E*mpnL=sS1}ksqSbVdeN4u9x(B|5Ib~wXO6s?FR{a*$N8P87k*RSkn@5 z^e2G5PrFe4HV_O_eME*s**C7eoG78>YT zxheNd@>+?;j)_)Z$aH)M!}IKHXlxs;D^vbKbi#zUZFG<1k2Qv(WQmFqE~^5;P^ z<mir5ZxF!e^+bEy+G2p$R@KiLDHPorE8hZ-A_=LM=KMnSSpE|?9$OOu9=^k3y0ZTUcoevExDts&SW4n z&?S5kQ7^>5U5gD@fd5Ys5uXKQc#KIZ&YOD(c4MjDY`E-wAVg6piq+s+b7C9Z2Ne=e z(-pOAW>(c|rvLggbaYUUW^AD&kh#W=SpQyW+hK#}(a@uLur>9j7_OaInLKw!r#nFv zLpJpq!|O1?&?}F@FQdD_dj^Reqr1OkMmA$+%v9B^x58Bq#1A)m^v<6St9S{154sp; zIumO?mF&FPU(%)K;CbB1X=HvXEf+qysfDR``lGaJZsO4FfPT1cdIc#E3~5=dTy4&~ zgH>S0;eawU_Pi?xWd}bValj(CaqINCyAWKKnq5(V-0Arv+{71vOV)-D<{9n!`-}9(^P_& zk#TRS73&Z=ssym7Ao-rHEdS?yW9@@U|F-StCl{k;i@FC^vX^!@2z~P+hRw_({v{ec zE{|M*=+Aog_q&uPQsqJC^LsJahEf>AH8NNQrTH|~%?W|q2PttJKQPGJp`V1j-*LMo zp>sYZ)g!d>(b(`h=DT4%Uw>(MdfW+Ox_}M-c|WdYzQk288GQ;-oh9R!r}1rvw` z`caft8+-kHMGg5il{8*uz_(~FTQv30cniY;J~Z&Z=Q|4_YzGi%dD<73Q+8-<=AZR? zg7gxKl2G!tU%=#aRn)L+gNeN@Ek5LPOBu3L(VDczlXn5L5VcBttZUsz=|u$sQAy2pdZR{b?Qx`UsDc^3||uWE3+)nXdhwIndKIQ1Gp zzJi^GpdP{3d8}i<&Qe4`wAf9gdNXqtPTt0}+braOD@OQ^t>Q&JSCI2HJXd@YjCC>i z+LrGY)yNE6T!8f%XqZJ8{o*d1ioD@vgU!dC&;yM)k!qoZ&gBr^ts+x1eCS*Cz{m2(|+^KW{)XpQ!n#?iW*Wvct=6Hfb}fa z5d^f0cY>#deuVZ~a-(~5Pd6vg>HK|etigOgssc**z{_WXs9_{>xM&^vH}-5xLPqs8 zOUDM$A0O|C+eACpBgj@utCPjD!j36CirGj@i-!Y?+cjI82L5*<+=Syf2d1vB0PG-9 zgTSV)V}`1wtLw^pj$iA7|L3{~ZKJ%mi(&rMhX?IEm(r)lrA;z@t^sLOJL_BhadXec zyVpZmcBP6+hGMQ6&Ac5=(|Dc*hs+?y<$_&ALWzyk92aLna}1R*+0k}qi)omg-a*JU zF?m6|ER^mqTd`5dpj>jgLk>g5^P%mBa)?TbU%m0V}HrGYrpS!%2Hq*c6if4)c zWF5Uin4txdAg3Hc5b9H>A|l|>i!)|UzVVG8;nfm&v!21l#=!HQ9+9B)?0i!M;}j&% z;I#a^clE2AqfxOhxzF2@m6(F{*FZU2Vo>V0I!*!2?kks9SPHR#qa z6d2Lxrw_8(&9PD|d^{u_d;wHG6m8(9rU=>ZJ;|d*@^^M69227$r(Leu>HB7H(rZ2# zW@Z1ODdAcW`9U;ums4C>DWj>jhhh|y>7n#mk}(Byx8vGta3|}Vi|uHh5^_tvJaPeM z;+l?U%nmwAziw#?0R($qpy|nEw!?7pdox4t`v&#x`h~JWx*|Nu4iH4^=@1ZNaP{*t zD-CC)ljSPwRE*C5$F`)7yzD0Zc6jAvh4o#x{b?Nd1(U+3LE})i8a}2k2Eo*Xlt2bN zv}R81Y1AyJgl0$psG*OD>{pi0-G3k-j>~!(^bc83rl+H~)#}q@Z8oHX6{=x~E6BN= zJl4e|hE;T}d;IgF0K^3q~gMa5ec?%l%gA_{+Q8NsuJ#(-eqLBK6krs}+}I?QvKv;BdI&nYe4> zOyvE9Ys66^td;-J2Fp)8apqdF2eCD&${y6Ac?VN+_!%!{()*R1=?#<<72o33f2X-H zFmZ!-mB}Bs05=P~(NOvOmzJaE!n(qa>{^XIahxNA_5x|Ox%F{ekD9ZkPH4|(Vg<5fp|L5&e}J!PB1kti{xL%T%@Z^x-8^> z3o)j?uYjVg*e6RR_?1M3t*hsnx}c;o0yq~#jj4oDY_NEL#HP!H+`Ysc14>y?!L z!5^P&k=ccu^ew0}Q^SH|pdD^3Z7uFRKT7nt60$l$6Any{)FX_v1h#r=;+u=7#7T&u z%si~m%+#R?kzl{3%HzmARmF7sAS-K85oVC)&}!ny1m?Z zRYkrQkWyOpgyNre2&C2Y+$|Bre!HbSs)zGL8LB8pC3Xeck zw+M7=_t)R@sdo+{2kqoECud3GFDTP4yZ7Ft^(!bS^vxPqKu1pT(s=B+EN0L-2f5jE z0cWKp+JtAZqPpcdP+q617?Qor1chAm-*@?O$qfr2(g=1DCpCQfvdwHI$tCw%8li|1 zCj2P6y8<<&L|>AtDoULOx!(L4F-p-acf z3_46yehgg`#)R^|h6~NW!Mn?@a{hbB2c}*Y9(B*mN*I8L?~vr*ZzTgR+c|1Za+pq0 zJ0JSF8UBC?<)bVJgQ3N}<@63VdFHdZ@BHFX4Z=dcdSS>mf{vZ~t?pqucNqq%oWM%kt|oAG1V@>PT{a=+3dh(M4!4ZD%_-jDXPbrKZa!W@q`6 zaUnlEoBV1JHe6#230T1}TBL+n;i78HDbYg?xS%S{M)N&4Gsl~C+V7tNugn7P*2RbH zP6pP&RziJP;Jb|xhM+(y_kE>44WRUVh5SqKw%o$yUld21&Sf%}so2NS$Ef0#>~;f_ z>*}d6UQ9ai%WLHV$3tC(nGwK}lNbm!xR;NJ>-5XA>Sx_tYrw0tZB>DdC2}mvDd=bU z{Wz5&c5KP-ipys zaB%SGV@a?@XgySH#N}>w_sXaP){u0Wqy_{F6C@rA0SyUc8$_z5c^HSFo_N%QPx5~< znHIyD)6$M(^(Q@Y-Ek+-9ROW>+B0Z5jHJHm2aY{zgn_IWo$Fm?!|S=U$IetG`mO7t zap@OZ?W+oeF0DxJ0M$VQDOt?GSZ6S4Q`aZg05PU|58tBnIAY^M6u#ZEmP{DKU0ml) zs=LhC$-h5yU@IdjC1GmS*#`J}8vIZ=Olw6!HogRW12_LD!TZ8`$pI*WUpAa6G1i77 zGkxFj48I)kwDWG`c4!n??+_M-<{Fg6uP*QM{#btfiV5(>d^T!J9Hmy4ijkr_PUvb= z&QEGmB`st1sZ+No;86SyBLKeL5LvkC`%T>{p=9&Rm0ORk0WL~3DN~`7>l^W#0ZDei zFEgSsk%f9mVH!Q z^T1uvda@YGm=_83$i^w$v&|vap4}lBnjRzLL6@#)YiUo!Vf-Q@l9uQvT+ttXuI@Ll zvHgglE4xn_eg^ns= z({JPe1Olz&krGV^G|@UhXmVyvaEsGVpuNQ}L!f57ne}%&z%`G%{ln0YkF8>Y9^(}s zN2vl-EV|98PSr`lE$(tXW}(l0kxi}Jq5GtiU0YHrry;=kOVdUpAhniD8tY8lc>PcG zg=lu^rl$LBaAmF#{64g-z;d9g`lkil(OxMDh8`Y9(xk8uD#lFzqJcuIXCPGT8ltBA z7$6j}zbDXAA!a5Qm-y_VAu&N}OMWf)avzXm@EzFKUuUFt3;qtYh>+8o*IhABYE zS&|~N*Cok4h7(AEkpG!Clg3|!mhCa=H1=useF^B;84d}cXw{J*@4L&eB}vN0OcL?- zU7jL~G*k=aE1M47Fe7kD9%0@eW#9i93(!H?{qxI57Of?ajGCSsG}9BL%tv*^&)>5_ z6Ky7az5fs@A1Qc}f*eLVPIDhGThB(oD(SN!~tzoFf% z+KjEln`VgEFI1ilzo$Dib=#*)Spk#4SQB?7JM=kG2!(6TVE0^t^wU)dMEIE3Qc1|LOV~96HVP2DY6x}L-Cj+8zWl&FoXf) z)JKkJCUJBgh0YQ-W?UtN+vpF3(%axtZgx=><{dymZ#Nj&rJXNinUjG(4=~{W17n~+ zRyYp9W0cWVoRb$3KM!@2KyRfmIIg$v=z@2_{0lHej*eknK3%|t?sYxSmWYOUaEd&5`$ zflKjp(MB^QV4+uRn}Hl60uUdl;_)Kl+~-m0lY4!PT{H$qS%n_qNe0m3PoYJTz})2- zh-2B$jPfK?Y2Sr67uEMBHr^zUF_P+P(u}b&HapiNv)|U%Iyh^trMrIaoz=zOxX@^J zqInI)GEd@$!3pw$U2;}`Knnbg#r)8H@N~TFsI*XS&>B0t>In!J1LV+K&W45N|5SRs zIk?{)Tb`D(PKX%AHlrYkVaTmuJt2}!|E8egd&P_vf+(J z_d|||1g&r3yvo=b39l4ZEpPCW9BNWR?_%V(IIa;h-IcK?RULQ^Ih>HtHh9)-MBK>z z8zs80tBY(^B>FD-7pUpSBy{-5HL^BZ^qlnY%ItIGSs-FH*Tw^z z+kdF%Y(70ovFZL6*qGlMbJMY`6TNN8uYkUJbwEXREAh^`oF(L*2L3w zC2d2>-hPh^V$3zWg!9t{;rdUpIOwuRn0&M1pTR)0aATuH1O;>K^SDHM060}LZMLm5&GI%Q1omKlzf zvv~PaU<*y3!CD}Gs2iPnq`HGBvD~EYoY*Bca+K8(;D!7A`|U0#ho2?vNI|XBl-M=f zCiL3!&Es@;DyVS|5G@$-|C}`s9_~8NoPh>N?-BsPP^ ztl%ZU#8Vs>49N$IuhsfsLy1*=W(k%a^~`SBPrDB7YR(eoG9u`hpNDmse`a_g7c2zs z?95^s^uKsrx?gq$?6cf8ZWl&mh~x-O-wIuKqSxo~q7EPzrm`=Cj29eiuCC8JmEPGF zS><8;0EK!gD{&jD(((J7HHN-Aj0`I*w=sv#3~qzY6|HrX5*L7#OZp(G2 z>^rnU#{9gHU9|~$Qd7b_d8g8*1h;YLYFk;q{OUzXL_9@b-h>}oQ_x#^lU)mT?S!g> zDltx{I8C?@L9#|PUCFWB?ocdzGNIgYuErWFFfQ#qI&r@4q9I)&GL243xB4Wj<2m_p zvB?P8DpaXXxKA;m9{(4agBX``YMx7HsWJHRlT=~UC_tn>E^&kFSALMo4Dv-32?5?6 z`U(!y1wObX%wS-nbPi!I=!6>?><2sybQ|CMfth(wEn{RfeSEgg-r}E+7G@qTHBS{u zp#54-Wy?tf^GR39mIfOf(wLY7ETRK0aJMebeNUYK6oyHzP7=D)F>u^d`pq{A#)WS? z1^MYO0=7yzVK)pjZ#Q2rhP?8jQqC{KN&Dko(QX$}14B9~K2c=+-@{?O%kf#>`Fe}u zl*TZ_GGvRO(OMK|ww|1Rj`InUi*7kSRC)#HTPY;#MDFr!*;uu?SV)mKQ)@GF~MRVBz(C~vR z{;_)c?&_PVh-KY=^(VEq(ri+DWDiV?@ebCX2AVJ+`1Hi#q7;GF2jRGRzm8W>RbFfx zrir>J!)FZtlIjzYck56T!NSqp)y>7i#NmIv{+Ara!SR35#dvwx$^PF$V3o14ce8Lw zj+-I?4)hdUH(JrV-*k>~l%<1*2nS72l`Sqb>$B~pe~+1T!A3~R$5@WS|NZ{=^TDQ* z4+>h|OkdeSOBqUDv3U0Q^Y!fT{p5Di^9oC3UQU5wnx$qM&P?v_t)fXN9JW<@c7svW zP4kZ`d~#`v=1DE5;ZnPgV9Qz^1Hax3kv|c1z$vm`Rh#9IsNR?5s{?HD7OIm{2Y)zu z>d;$zm2X3r*VDYNf zpzr-)!bcNb>N|Wpf9_`*J6jA?B<64du&Jec=5_87?wkabsLsk`dohO7ZA`2MDr*_g z&5q4C_B5?&878=BDeby>s%^+6PLvjdbFOXq4CQ`^!ph_fPw!Ym3hySNu?eVk>MVD- zbo*U>#;ar}^TgTLI3C=Q5-Wr1-@0YuI^aYbRRa{vy zw(C(vj05`=FAQ5f)k@9efRA)9J!D^OCCq;BjZ zN`V(N{Jh_NjSxnZsRpXnwm~Rqqc}dE@>p+)<@I#6$gA)Ct8czUj3E?JX6oC^W6&F zNr>Ho3P>aW2*D5OJ(@HKE{Tm?Y8?Lc&z@CWaG|>LS#1nfoSVF*#3-f&&AH$cW@FA3 zZk^fT8@_!%hdL&vbdrPhVdpnYuI>~P> z_Q{*iq7VIEKq1i`({K)zlUkG5P@2%N zpdBUVApQZI4R{dp(S@<$BC=%`7C^$qe{+U90%u#Z^<7cay`vh;5e;X>8)ePW4Pte- zY=D55>1OYqLFy(W>OW;6{QC&CG$OA;UL4>*Nm@x1!o;m?I&Z7Uypzg7j^IObEcRN! z7R|}RaY_dwga@G=`QvT6sA}hYc+Mz- z10hn|-+APBfJ;HXhkeS9nER;IIQ7?+lFv<6o{aH-|EgE7B#-UrzRS!%3sfMvtDC!C z8*4npUMxI&C>0oA3ngG8gLYrl8GC7>u`x)E9F*K!(ALj`47S-9hLnU~VTX+hl%dS; zt`q^mjb;A?XFON#NdV=)u8(8!QypGNTPfrdw#-8XKFgMQl*#AW|GbMsRsMQdUY*^- zoAiiaHaEWG@c+gQadGFUph*T|$NCWD@{|uG_Kgb96kUW${PzbZWNq^_6%jr%Gfrj|heAeI-eh|ejs3?%?REyc zkis`+yR{`kw{@-RE138>8A7327E_5GdX$H+Aj#OLNw!y*ls5qgy16{oXZ1WQ=qT*N zr4Ps1u&e+P2l1U39FC)5x_={_BEZWI&ZMG9*;uAAH5LYnZZ5+9tNk>4yP|Ef%CF|+ z2jSeCUyDUne$GAyHP52mamphec(&yq*C;6#holhx8a;|D@tMJ06SU&6 zyy^W4%bSKyH9ma{7$f;k@LVJRmDHgS&YaX=N2JO6vW?zJ)}E&sgn9jgpGe;b%F5U6rdX6%`< z$-kw}dz~xhK|&;rE6W5XT3b8-bRX=ifY@Mwm{hre>lf&AD^gzfjJ#q+X z(v8magKl94Gde7M8VtJ0=x)5GWQIDs_OSiRBa(*Q8zy!{pe$@o&gRBP?^y(r>h>dG z{n=554BK@GqN3Ix0gz>oux-hQ);;EhQYXli!Jyg^rbv0)=PnTbJ6K(sq`IYbxRX6i zq4|wN``aU9j)Qa)FaH6X`00b&Tbj+04dn^}=JP>^q|?_x%h{`dY&lh!D;+5y|0Ce! zwI5Zu&AhtS3%PP_1v7HGzmNc^X!pQV5_}cZXN66727ur*z~32Se7WmLJw7`6YX*52 zh#+B-ddK~t?vgKa$joH-3X#dG!NF=kyJOs3NA8XEcNL(bm8SXgoFf884{s{bRk|HI zMac$l!3e~Txx8v1clzE99Atk%>=zi$|6jnE|9^ln%zxQBc5e1$bTWEi^1Fi5Iv-m1 zkMQ1S#*I|Aabqm@vpXvOYyo4JrE^yy$0>egP@;W8j(QV9@Ir77k3suidFXu z9ndB4=2qcsnUJVysl$uEOF%Ed8H!DzX|AL7s1ndruG0`?o4UPLA36U}WH9obaQHW) zmDGOrbtPl=?=IxK4i5`pQ}M9!_R-Ns=jeL8+z(S{{N=UVfQ8g(9&b|k-=d_67H~uY5nK5%dIZZXOcql3gg9ivyabpZ@_%vPC+KOdFXW5@+D9Vb`}Yo1y1qo*<3@anD$$Z}yF3WK5dc zs&MeLvW^+bP$fiApF>En_(6Z=;4FilB({sv>cC9oGOBO_G1txH21tq&vB2i_!TBtd zd;+H<@erWA+cCxJSwTC{@?PLF#$Rfss8t|au^5F@GX-{W&ALCvNb+OBO0~S1;|RK#0*nQW>|NWa z89x!$`;}*b*|M^ShIvl8<363F5UbIepE=XPJt^&!1;#Su1J?G$i0i8%>sUDhk{+Ve zf(eI^VlP=d1bVf|{tN9zKx@NYQ;nwA!m34Ewc*{%N#1HL!5iCzkJLBKssd}oR#~mJ zK{Gyj@!{1g0keLhW9)l}p)ex`9_!SYLGABiTMx6q+{+}=l5a%FG4mMS^vbkJGqeDZ zu#rF?)hAwR3R{#k3TZZC#8Os^FQODlZ_B|6bxDD(hm@;Eil-MKXYIXBhFI6pHt#kXKUGauKno0T;~TC_S(YJBM}w)7)JLz89_@KS!u=3&+C{o4tc}*68`Dy9A=>YzyVPGLjVJx zf{;*j+%43pUtz3p;xM81kl;BD;lki<5eW5`G5>;4l4$iE5^p7hh4bvUFzB>NA7ARK z{~ij9QXF>0s=hxvHry05sN@u~>fQ+)yfXeG+=Fg`f9>&G?VqIj&ZSrgDd{AwIlc`h zKfjsY>EABp-*adV{u}7^evt+*(YJOC)HiImIQ6I4GZo>7TXb z9Ij-p^tB_WH7E;F&7Dru19Az_sXYkP1VHo^A76S{2yf0f3&v6l*KI^p)1RFJZ=|Ds zOm6>kJJ8!AaPj<)_26dBPR7o~$Myf`usO(hxH&nKZv?TRdAT|MzeILyBeZ6U9WIX| zr5rCE8^~>PhI(^ulVbvjZ4e1b($n)>xm++AbyXt>1R^72W+r2nqf;mK5xVl7di%2T z-}YJZ$vfIwZhGo^>ZgeWMIh|AizPvfd?i5 zn2B`sAdVG86liNiFs?+n3|R6GjJZi%XisOU?en`QRuE!8GMN0gsJjmjSi07JRcAOn z@EMq5Vv}lKL5W@#Fi9#X6v?+wMyT`{N`ea-YP#c#3uZ8n2LMg1h{(L{1#HW?k+K); z5M0u`uK;934e8cfT`T$v9<3fShG>@r01uP%ZREv+hTOn2*g?bV-y0sn1P?6)tkSH}_ET8Iq8mTaB<{45-7m zpDX3d*-B%w6}59|;H^dd$C4LBGB`)4q3$Uy;_PPTCOo|5h0=T2iF z=>7{6UQ!7FwH6l%B;(x=@$m)!?kf!k0bbw?M_>%=3ZjJjBK#OeYWVL9%mY{(u*UG6 ziKK8~?+@=s)2}ins#N_$Pd)eB%s5;c+8X~^A0HaGfS9y&32JY?ksMSnD-}Hq6i7-+ z8VvaNPXg2nz|KJqd{Nz^S|NuBW01Y*bo0VKcuxHQqV?%&`r0%r2 zoBW2ggW8@cM>lcQk^mkA0Y~*Z4DGD(gRGY%lHz?)BLPor=Hie(alBuzqaX3-XQlCNFCSKF7kQ%c*PN|JB8d7DxeVq= zZpo8?_O3u;zFGJEwvA(NyrXx?HsC|ze8aYAY~PjYY?)GeC3zDk;m=ChXBa^F5(`pz z0!vo4I=7rqR(kaFRDs9nk{Bc1a$58|^&J=OiqFzp-u9w@+Kund907#sUuV(dU z*iG|QJ4yGhbv7mzN^&1r8NV}S8Ozsuc4#Lz2yr7w3;K%eVf~t=o`VE+BkLn*GX7^0 zo-RI&T4f60DSHfsTn^l~CZ+2Lf~l(`3&o3mGe(@* z_f>^FZ1CSF8VzBR++c93uwIopMPh!lDh}XtRvgkHFgn+`VbIBBNV#WWRa)S@V6T2q zIX!rm!>!XVb{Rd0PG`TVNxmILT)5`^oi6#f6nqZYMoFE^P2{}z0>3J4NpU~nKI>ki zxCP5^5gpf>pEPR57C$488EsYfrWV(Uk&%!nbd)%)U?8k=sDA&g`k{u_G@ma2j^$=jEsUX zM3d=dbpq+rPZEp(C4)y!yt9=ZB6AP*1nN5Vp=<$?x$C!T65yq1`00oCt}qsh+Cc7i z@IF1#G86b+dye;Hl{d!v-GF)|!i$omZTI0k@0)4=I|jYOZZ-}E^+OZ;#TkSNJC`2) z2EE6>Q&xJ9Z}i2q^2Wa3xJS|!MyLF7&*V!tY0cy+bZQ8STB5Z`hIINwQ!l^MFs_&f zvBUe2kyoy^PX&+w0iYh|*ek@32a%>us<0{zabITE( zW%2kfX{neH9KExLJ@Cb}HAtaPL^QEpLB1=HO|U<9{{SK>dQa~ziS1Z7t=k4dy%3{N z>w*RB3EmcSGPINKwjhs$6MYs}9RJGdv@$oZUtIq-B&y~vBquiTQ51bk>UUzr#9D*V zU_MX}o`$J`YzPvKI`jK?c_5qbjJvK`Ztc7}QD&o`!~#CNZghpWn*QD6+-(d0R)6Jo zI=?5DLIcRc_*ob-~j{I#WUhbburrGI>IN{cJtr1;$RFjqH?8X zg$YlV06b;hC)4x0s;Vr;ETJ`CR=hAB55Dcuk(uDva-9&u4|$YEQl^p+At7Oa?@b%I z(|Dl*Y^LAtTC3=-e=S07GECAjms1J~Jv?sWio5HW@uqiBv>Wzy~)3ElN zPc(i#{daLBr#S9A5l(7VwxY%-SXH~XE2RzT_?qBbwpvd=8dnnCt?B#)|HSD?6r-9h zMW&m7Pfu%Q7HzqgV%V3Y9^nBv(p~t_o=*$Td$+zvqUVosaMcL7ZiS1O1m1P4Xaear zwXZF>ExY0&BvikCVlAYnZp~UnMoK@l4_%PctS_=BUZ2BH(p6cs$BVAca~yxr`s0$A zRhZ5g)qX?Qo(3@;)%bKDCg@>MmI_grv@tHdkDWneZj*=x7x0rot;Z>3{g{kpqqyo@2C>0yjhE)jjX!@cp93T3e@X857WI%=2Wl z&QRXeala*X%#S8r*9L0wCh~5y0ldxX3IXEy^N5S%r24WdHp=D8tZiy~xV<7eWQjfK z7pl%pp|F&jwDsST>dT$wy7@P8rVaLde#-rpZsf(umY!QgHZ+!q3SOs8aoCyHV$j*53QuDgN^0L!$`X_mo#QMU;ytzz~^e z%4Fc(dUs)EUm0Q_!**;TK2IofGYax_w~shr{aJXScJ0q>qSMOAJmsuc&Kv3V%3`(o z#$>5|VWGRnLTMS9R3+>#+jpGtpEO9NcMvGY_M|0zE$TiPh-WLlu> zmQMV3%;p;C~YGZYzcPec0 zK1=&$Q1!NlI@}Yu`T*yftLUXFswtwwIygav6g}Yhh%uPvNnmT$Mzh_ayJ9^y{B)kR z9kpTpopWR~y-{-LpCH-r4>IfU#FGB6UB2*5`)c8DhnEBhjOSa#wO!(4#h)#rXNPcm z*9b0x)Zig4s~O2Zcu9+83>7^ktk?7u1MgeY=g7H_+8$g^BLRWNn)md#C!Sj3tNjNX z^T~#`Uczq2*Co-S+%ESk0_irYc~I$eTyVBYknio2i0UrFCVc3&1J+$0M8RhY~Xzl6ab(Q#Ra$?)WHW%ppt#A@EIH&}g~7H>=5Y;J*=y z(tSVI&))u#lSffJALYkP6}qK^W@h(ky*}uVU~_5({v8aE7k#%;kzp1Y6J9Hc9!TbDdhMN-SHueR3kv;n(o}j^ z%;Mo7HRO%;2y>6YAB=HN1MjjRv!*>ajM}l(R3GH)=_L4_(u$H84{^Kb`cX9I4h#1E z*xr@G>oh?biy;^G=-{@=sC2`#QFWNCpAQtqW7Q0Xs{6#F7bz6&Qs7rX;^S)ZxPkI^ zJ8PnA3$&xYD|5g}F7a$}VdCMe5tZb}l-;lsDz25C^B7jR>09U+;r6oI>303VvqF|v zr~;Z6M7f?@S@>O-@gdjH-48!#%w}E@H?m!#0<_*)@+3U&Rf-_4n@cm1Y;V`0o`OS7dWzgv@j8POeF^(x&~#F%>h7x!7>>rrOFVk{R`RU|?1V*mGu3={JRD4(c9(#dF z*noZ%vj|@a8%L3bcS2xs^?zrhT$X;KmG(9%D&wm}r##8q?0&*MvH$r zU-yn`TxjNaRvQRKF6%xu7#`_vt{41GV!vFSdxncoEg~XF48!oi7SggX)Cj|Jhmy6!TW#85 zC^QJgNFpA7-qvn^wdIc819Wm zU#z7LUl*&qGaEBEFtcAmU3lIY0cd1ZOzg~WedxI{-1g~>=@hf*lxvGqkeod9;a47?&THbi?yHvKvk>m+V+at7< z4$$R|dR=cVxg>t!+x6ozo;r^{w8CZv^hr~GKD03ZnX!yG#4 zKa$KBlqrXi^;EYqhGie~P8=kuoq`P>5N$6qeS{WJnq<#q+FFn&LbbQXwBHcK&93%3 zQAi7&xM?Q&2I)Z;7ZV14cEbq~Nk@shiFO9-#{BZi=qnGC4NI1v$u-{cJnF8gdP)P+@AiAi2Sxk2~c3ObT^IfLeU3`CFR}E@0Wk;_4zZc$N zK4$bGI3rubXbSqxrb>AJy^{Oeow*bg6Hyy2EU#ZVNM&4X(%0la0iLhhau*WX`nZGY z%PbMAcjKz1(TaDoB3w=greTrd?I1Z580DwftN0YU4yOeXukMuL#54Lf_c+e;JmDfH z$|fjlKYW$$B8z1fvJDR}Vj}SG9sL&hcXibnajC-<)u%quN^WB7-6&gjKK46=sj}~X z{~xx_fjQ7N3eVBTw(V?e+qO2gZM?B<+qP|IH@3O4z3Dg8&a~6^N1S=ioa?@?$5_Fd zrE#2sz4CC05_p7XzLJy}Vj+*{Vp8yoV}J8C2qAR{wsZn)(4FD76*S3;zksi`mB8i=rJeEF+pB4|3t1In z-6sBeFS#PuAGTMxF}Wx;3IvMxUL5>=LG}7=Zz>r9`CI9XvHBZR_T1|V4nS!Z&hPUK zq2IqT%4)NsNhWtUqe7A)I{+n*C1M5yyAfFv(57?qcOXgN#2;-|H_IZ-$@YuFYtpi_ zU45IG(kY#p1{W-lRG7xm*32o<)#G#eaib|86Z+ zg0-o@(7)OQ9(O%0sD}w*I(4P?x%}$<`a(ID%WUeslo+I4D^^yx40v%;K^oSa=n#-*157eV3B*z)k-OCuo_{01i4iU!8v3`egI6m6Fy z&P+L$Dj{=osRh|RYZ(57J^x%AOyq>-+vd=@_{L~l(SK}ZWQ}9r@w~XBG=z_V&X<={E(|i@KwvS8ChzQ zOn|MGu!NO5wI<(rnx6N$1wTCo)DFzCygD0x$nq6mIwfgXeI}i=Wr($^b@9w}BX@K_ zp4aS}s!h~L=Ob+rB4z}Vx`wW@!-h#Vi!At6gBy&1&i-4{V$5p0iwRhSPrd?8< zVy9Zrv7`|RKPRi&yuj+4!SwBj;lUuRsDGI9;(ukew&H=@&u2 zc~ui?&La7(;L;k*`u-7vEsh(``@Ou^7|yzzx3u=JiYW{z0WY@&k=$9R#kOR<5*YVt zV#@)x(6sq^6sNyT{Lfd1KT8*VL7fv$J+mrh$$r+EI*jW+j%H*c6o`-j!GsLg^$+bUm273%sU zx&<#toRl7$PmZ~>4U#ZY?kV;d&16x)(&)aE`Aqq(;{jlUxOVD>L>Zq>JL-2awD*F; zr&#yc*4(?`C6iO@5SeF8ogZySKBfL{3(fce7z6C@D#sNyDE7`@l;0bbHzw=TCkw8< zMUIpNMAPNv?fr3mLikY07xMFg*z0n4lD#rb8046|qp$`3@%pEhR|G}N&sSnk49-1o z5Y8LP>j1va9W5zZorHR+`R=6&QN%A9FBRG>-*l+mWxaWsIpbb?whx(vd-Nj2EwaM| zl~js7JE!^Rcs({~8A44x)5o(9>z}%5>|WFoe{CBJuRZr$9Qx9PQ|fT4ZDs;0eAx4F zo{p2e_>2mTD&tG&HCEbkXNqz%VFhIH9Pej~NCBnM^q5cqpHxAPuV=|baM1NX6UtzYoa?(mtn={qX7DQIktdljm~N#d9kD<>3%at#PhPcEc%g z;|>1aiLh!wz^VgI!btGyVXIW^8Q%Uv@qCi$5RV4C9Y{6jrHGca^R?6Ia`V(z_@qtW ztM|^&j`f8YgIUcC#>t&ze@7UgulU^pO9#A3r`(jJvVfQB(~F)WaW~TIq>9!+VVt`; zG-BKn4lOVt-9bl1#P!P3mEpZGFJ|xA#nrG-2qOFA$8t-(aWDV!kEf0-_8G~BlK~{&*LrmGF&F+PMS=1lhwm(|9%wHMVv)M+qa*l z;}>biKh&>H_a%;k-QKB30ZmBdn_O9L(t`?i#0#y}#YyqMKC9HN^a)fa*Wk8YXw~f; zBr*{%q9+tiy(@+KDejq%TjDWJHUNXnQVy{me$wV$J%w4?>;jc_`j+;imp_`qV@?{; ziyzS}XSTeHi}!kfX_Yto(3^J0_N(OtH<5Wmi1IEWZ`I{UfQLUNMQ4IJsUfZEhG0|o z&i&PWu*~GYYghS<Z`6dzDgEqv|QRCf_*Iifm-!K)txun2q z1HV=`Ts=`iSZ%SsP6>oI`Syc;#GDC&9r~UPNq*l058aT}fMh(nDpR^lfzE#krCXFe zk6k=f)*EMe84%@y6(OhL%fLXzuV5TBtgV*#%rg@xlMpNmC~-Ddi59Dt85@O6mCe}P zZ{I$;6YB?>TUbs9A=b`Hl#MQqfm2~kQ2`tAml~TfyP26d-ur-Z^3I`Ib^e99)w|>+ z>9Y|yIzqDrq-)9g@_bV%&VQzJsmm{-;i7Kig@H$La1iW|x~>Rppc*Jk$yRjhaQGM9 z|Cyq~^>aAfrb`n^WbGlop&T|+RR3?z`yb}z`u}2HW{&@jdD*#>Z+NjFxY^nNXH_xQ z14=DA!EC-S#Gprk5GkW{YRO`R*OZojwcd0>kK_A$4V`91tyJau}tBKYu`i zL5LF?h@r{F1}CjT2Dpd6+f*I12ABaY2w0joB4`SD{Gj2@6cR2zC8$scO95BNfKX6F zX6ai!X=G?(2r%hS1TiCW&?#ij5PBg=-%rm|1j?WGc+~?%mUFbtA-fX zgmHQp>AzGFJ_w}aPy9p3_8-4m;D3j941BjxN)5s=ISUyAyzt8ITprMnhy!>zC`??a z(MVnqEukhLuZy5zxEmn+Z1`_@HD7oGNUtv3APvN?2Iv3849G=@fghrVOet`bl6Mfrn5+32gwDPy{PxXnc5wF!CHSHQ{ZwE3}ZhFcHY0$7{LZPxxS= z!-gQOkO%SjfoQf@8x7$N+QMJI_N4IB4vGZKARrNkce|->=N)qss69$vc6oUr7FMo{ z5H`at3z$*&-;wJIKcRv-l|MJlk;XyAgbzGIN5w%MH9@w(Pe6LO1||SBgzsYrgN!@= zSMOqF%K(Btgbv0b#JKOm+cA-?JrMj8lC9MbL4xls<$ysDT?lxnfT1fCsVKl=JbT~0 z|K;_~1ep*74mr=?5ajIOp+1!&&!~;Mr1`Xezh45LjdgWJnfdTz@xDJNDvBB@pgo`g zSx86<9Reg+Yy{Nf4i4A_PCB84KPwLfjoB02sRzWHqP_31o;+sl0jYs6NfN#QfO1iM zzY-40@jLq*NvMbz`ybpVaPm=~@J%$!*z{R1_k9zkM#RJWeed!O`6=ih0XMY%fCQ$v z9nRGQ@2cd!4f|cIN6gKh_GF(6NFs zQ$axPP~8K60U3bq2&fR7zdrS*K^c$(=@T)yH~l7#=1T+I05C*|F9E~U0`bL$D#CH< z!n05qurt?SvfvBkcr;MvB4FTN8m1izsYVxXT*EUlFtx_Z^8|+KbmJO&;;X?mnem%D z(aW~%d89sIwpDb`w!bs(9(rYq?{+?ZULL9;K+MYl$>jM zDsP|a%l~M0a--{{p6bjUo9$(F#g)T2_@hH6+ZiD{BrN0qB%L7+8>}1r%7bJOGp09PcH2WsjxS=TNEH9DVlE8PBFzq?82GR)b|ziz567K1hE5vNRcvz^J=j2HM0H zfQfQ-(I>ou_}zaa!j1;5+JW&yjG)#hw+^ig)RpEpyFU5oi@j7PeEUYUo8V0edCJ!e z@K3dkMtj~sbwnI=39u&q#kn&fyLz}i^pewOm8cP9E`WXKXr)ADq^y`XHK@7wPX3Zy z9e@7l1EzVHC&5lPbH!#Zc^{+367Sy+Ec_xz6QZQPJFpphk89v(U33qdVdsd(v}toW zJ?xuy(=EHS-Nk|VPdl) zq3j2Kb_m76WUHG)c<>`#($tl6G2yO237(RA9mz%upkeDbN7;K5nl*xy&!K<9oGW~B=->d3SqJmWz}}&Y^p=N|5U&qAI7Bbi_sG{^|})+ zSI7Tc`x&eDyu($7^C}9PVnwsGICl`OZ?5WeR+W4CDEG8U`JoEh=GK1k zS!yeucZz$g>W7(nWWeQI+zr0yJ;lq;FnY@FdDx__#$CIrPBk#g_m!v(yeMc#*kGyI z!r<3BEpZiy&tm+9`ete)qC;ylU)7@OJ+E-PHw_uC9Q1MsTl5|e9Zup=Hx@1+W3o6e zLlf)1L0Mcfiu$w1-|!M1a3SY9k#kFBqFsfyqg1^5HS1nNV$gS*;vH^-RPPen+N%7R zWhV3U5p#y%>boL0H5IM{5NOmgNqMM*dKwmGB7M~0>2V4M>kud0X&IWj4-4FR zc=Z`(-z~^d+PV)}e;A;A?*6A+*HOUTO}5Liaa;(I7lrI(EE@3aDYz?aKy@s|PG}g2{;K(A5%m{t8!OFpqQ>Gn zkwX*j9+D_$SdI-Fpog)CIl=&W*R9kV#~*!C3mKn*11=2j2;k-=}6> znzja`UShjePG$0;c=Kn5x9e9~&TCF#A0AfR#X2J2VKGl-(YIiXEIGSL^6EJHgkVmQo`I)|>DF#0=Z z`?SOTu>`nm&^Gcgu^}~aF^dWg~ zIAa*B6Ew^cfEONlNjags$Zgu2W*c_*HZ5Z%g2sw!iY6osDtj?0&JA!f`*mE@t+|7M zMX(a*M~YN|p0Uiq*=Yd(MQNO7_6Ny(?M8~Rn&q$Bv4PuWO|v|2S?TqjwnvSV^Qiti zm=M*{+k{kZDHONwN#+hH=k;G6!9hqmWJNQvf}qfK0Mhs8I>>QaW%Trnek|x>m)WmK zIT&k`F~heFWZ?pcLbaEKvC>vy^?Hc7AWYy;QHWlI^fcbxn6S=;yXGhlUH!T*HGX+H zaJeT(GWoYy`RhH}gN$OzcsS2^6VW7Lr+QeuY6PL@%002e6uVhw4c|(QNspV<)cDHq zB?QbI&{*)2^|xKN^08e0pJn+Vubt62wP=N?EF<60@cQS2IF4J7jgxjRA*b{Oc;H8S zF}8zQtxcP1#Y2PP?z#&*S&)hp_Y(sAm9 zm!usUllgC_c>QD%@CiFHN)9YV4su}-cOhS(aMdZZEb|egy|b*}Jl~KU7|9*p<(Bpt zPPu6}>L9ZxQoQ^y^DJ3$S08Qk+bXPqN`5@FHg30RZc#Gkz%fl%Il1V?7l?j+POO32 zlCm0&6b%?Jv$(GqgefZM(gY6l;Xs>Q-ZDFV;l(sE=%#FFww3d6ty(XZn{xYjo#9IL zI-G;L6TD%u{$9+(tE>FiZar9^FkJFR00Y=H744fv|BHc||Oh$+Z8HJ1fD}7yzThY&Qtlj-2SC*)iV^%I{srkiu?7)@pdoS5*wD2 zuiWr^M-0VNm|~@W?EYBx_surVI?AXtS9*r3I$`~&pYJwcjj+>oEnUM>{lb4yg4f;kD;fQJHncrDzd`(jC zwL1A*>{7aq_RuUcuf1@O2Dfv$m9|df^@g{r1fowp$OdTk9_>JTjt`}(6``J69M90( z1eXgq{OCPgr4eXKs`iy=;#Ae+ z-AVQ`d%2UTOSIY}o*3&|Rx?zO73p$M%{gBnRp)h^(@KS-=z$N(-Njj>_@N1h$%n3@M& zhc;!&sNovgpjbLO@$=q0Kym>qrhQ8zN(_BwoJalWSJs9LwHLdmOYO98cL~kO(lc0{ zkiWr|CmHMUXVQLozUzKq9EWsFiPhcmMH_pj)Vbc=v()wq+s;@RKvcUdfMY{YXKKJ*Uv%QAF~;O)*-hX}U*MkAyXR zJmB)#g8C2u|LejMBP8fo+aP_W6fvj**^k&v^2e75I6+_ETB|QRV47+r^&n%yPVn)o zi&>{+b`jPmy?2NG8`$H{H$uI>03!JoJ5}BK$w;}w`7s8lkbu#O%E=DiRcK25W?ZZ- ziavg-rK%4_)iE{jU%Yq3u%FNOv52KJrI$B|ecNL-eNSYCPuXN_u0f?U*hwMoATebR zubfMtIWbpHrw^=`+q%fFBTS{;{a*UI(@v<5wi>G%nAgem3I%1XLBRZrmyGfB)G0Ga`^Y+2pzHi!@Yy-x1o2)2AY3T7&jfWgy_W!$dj@@y@FWbeF5+Fk~(MkCD z=!f-ZsNL6zT_MZyQRt!jsm?n$KZz_-a$>O^pGoxF&HT^isFSvQ!AJxn+WlaA^50L) z)Je(f2w6R^N89QXUp(2FEW1_>5|jFtH@-GXL!E0!v#;V+vr0>w=~wd@qJKmM-o9R3 z$Q~lVdS5ST+2cXoe?g&douF{p<$)A%Ri z^X*depEcqEt2k=NZwZx6yt&VNKOq~b1jXj{-aq)stGQd%`mCZh3_JGq`7IX*p3NTs zP&QZrlcGxZk$FH}Tk5D#%nEj%X+v6*6B_D9UL_umR~e&;Sk|w}tVgQyd-{X{Zm_Sp z`sgT+M*@jjv8ox)DX|2)fQ-789<50{*7+EYDd}-OVcwJ$|C}hx5fs6 zO>8?_J=NW47{k$H`bOM6RZ0D)muk?dl7AoUUSx4bBuJVMhC=zEM5oS!1ym-7XLB3iY(*%IEfpLB2}2za1xNp&NSdi;oaI*aTU zRVoW7r|U#Pik};PZTc(oN%0H+wVlC?brj*&rZ~}g3T$S#JK4vh=O}XK^mz-|B8Z-C zdhYot^iXP{+!l4GooPM%af!oU(AHN^aRqk_cDg*&ybIQ_(V?}It z)-=_$le-()jfNRn!P$?*S8LX~qv@Hdjd1%c&O365Co2hjI$R!~hrC1xtAj^UAp(v3 zsP`4#brud|IX&_a^2UzpRj83%ZwHdR`UDwKBsA70JVxc8rmP`%+et~CSqe2AZ)b_= zTu*wU@L6;vQDj?I9(O?RCz!UKunf7_xZtJTf_xWmuexLYVG4oeTe@y#il*a6;elvs z!O;#={$OG&X0I+^a~)Ayg*uwkk+k=ENGA)S`kQ<%c_NyoAchvB$5hU^>VI|DbfgRE zpP|&R&#ZhtLfki2;-id*Mg&hMrOcDn<#x^UBaagz1Q=A9Bga6{aZn!vO>$2ZWrSIy zXVYP2&TZ#YQ?ym!Q!bY!`4Qjbcy74Fuz6fn3jt{0t58=%{SOFs*4W>dL;SG!zozr< z>-!f094~ls3Is}9SrO2eyo0a|YJO_8c8|CBbFZ5fy9y*7qBGeWrhx4R?|-p@66sY` zxnp96IRD)SmBwAC zAi>@eLjzqIG4sypmgN-m85@#)9j;+G37{G(tAMFf+0=pEb+WLims^}$0!gYlN^;paQ3Lfs*M|3`u>%A zpfTtDv;0PSp9|}ggw8=={}0|2I#D2O1_!&-Z-rPCX8C6%#(qLv+@Tm3^DDBlgznv9%~+ncs<~AJ#H{hB z9}do1c`g92M80Uc=ee1$qw>sW!@ei79o0mqe{smYUJbhO&>{HSt4X6=j%f*VF)Sp;~F}TQ7`LhA!w0(ILVSXgUc&_+*Ho<)S40fiI zl*jdGo60}h-yrI{h}e=>o){UB_RlXQ7zT$*on{x{7155!?NJ16^UbsV!W5 zn8R{4c2?sq(pg!Ou59IFV3?QD57w=AX2nCIFs%&b2C0IWgg&>!N}4L4+6-R?&m+}8 znoWT*XI8%GVo0UA!b2D}wO(K<$~I(eIW*2*Fc00imn$lrv1@iqd>4HE}{Gf6?`FZC(WNF4_$|o5Jjyvok2fP;*gQBHRNjZDsFqP5N!zY8G`YRXsU6 zl2)nPmYrIrzellG=-RwDUH#&WiBF`CCG^rI4#U>oXbYE#-zk^9&4s|JJY?3ZO#ITia~b~5Zm3= zlAQhjhWJhVT+g%^*w>kZ4WYlB(lpZ}HxKnF2I^<%%4hb8Zyy51K{SP_G%YvZ?$08t z4Yf^gKy5A_!#{s#6M(;6Y|p_^5)O4sWR7Y+bF~)g%atgJ)+gdxrI^lS>;pC>2EXM) zy65?Ya~lsQ@MPo?7F_FIA~xcO)eG&@-Fkahxv3z27GX9)sJu4eS^ZGH|Cua~DC3wq zq4?_`XB|VGSwy$%Itht0&qHD`?LD}LdlGdf#?hi^4MgTKS3@r6x##bneK+17!WfMv zo@-?Ppt~6fol)uct#Q=^AANvns1=BWn{$;gBAJTAT~YU()6^QP{2HDnET|rz)|-H) z4BzE4?@a zrOb(AO-{Js{L3MVKK#saEMdu}sT09ot!n>jE*<1 z6x=Uf$Jx#|hUe%kRzCbs3nQPdgoDVl%s=MYZ;*YfkoNzV(XliApNuYfp9mA2g@gNl zHZNINIsX@xbN!*Vw7bGVA{8MOJ`&)HL_;$BdwUiHJO+`KiIq(%oH!_enx>K|g%nyP z2{maUmMtl$WQ2FD_vLH%M)%@lrRFKyCGYFf?^)nuJv@1KKuc*7XCE4rWY1E#ARz)? zNPHEV8Vnf)1q~Gig<}7REwIQap`Qt+90wvYh;$EN`Hn6K3JLh5C5I6+cJGSf7?6eq z4}uO3LSYu5!a_<4qKtxa4xpe&;RMjG;r)gGjR9s!vWJWgQw}>cj0EH6CTbG@wu(A% zI06SEBP$E@`Cs$0Q#3(|iV42}PNG|QtC5N)&ZFcl`z5ln8YphB>NdFaO#xP%CZ z76_zU(15ZQ5@QD|1k3;-BGbwe=$Vhu9x%ZJK!XMJdw_$$f_@WR*Z)_%RC;x=Xh=pI z+6ISz2_Dh|Wl+L~C_q|35&0Fe9qy+gV5lB4XlBE zr-eIkb_zL-UeFnwf2SK-d=GP||T6D$sEEpq)a8 zr2nB2z={6)ciA{ADdGpZLaKEI3QF4V|E<4ne0&@eF#P#X^n2UD$W7iYAr<#KKkC~~ zRYT$x3=Cpa93-d+l@w%;F;UtGOZXdrHvtLzCw~aMSr6$UgPaSl8`qy3;P`xFfXwgi z@BR2>O(O)W)`1Q<6(ns(Nkn!U@(=jlRr$WU2UK6{slOQ$zdb~V8L=pmE8Tv~GT4+s!Y*N_9*#A}mpr-{~%R3Q)b zC}^n(5CMr&4MZ?)lWVyU#2^v5;uaA%4k+Lup?m*bi+%*qGeYkL2_=30tsqAxhQE6p z+Tq3g7i$k7d8Y}2a{lxpy-R%jn<3fX@))@Xp=t`4`hp%4$pKRq|NV z{j@TZggak&fPNu9a1vg1@yBg4>`4%O{wg0Ap>`=*4t~KOmwHXjdvy?yn<2L>>cI8f z$FanG2l)oSmZYDmM7Xa|@ZDJU+jTQ6^C=$FfY+oWZ)LAz7FeoKnSCqz)~!|yO&_MTEiZNXsFz&30pem`u;N-fg;vNabt)`(-g&(ii1q<%wzY6#uL)75ts*!_q$-#^b!3lv6vl*X%Gy zCzLO9Y42GExgXGmZ0g*da8z!*Eu2S1;8b>0YH*v_J0Sq|f&fnq3`(u-lHmSeXQG$Q zGmOQ_U$%b)A7j_J%{S>WQ|+9JZ#~Br=H2vaW1p*t@$$IJv z`&L;$mIO54Fuq&Rn+89e%uS}~0U#+WBT%SaYX&un7ELx5)4jtQbZ2cjHLMhWn(TQfw zvBt61!_8C1?9KZ|tkBVMN@=;Z98N%%@s!0a6pT0M7`R-@|~07I`BXq%ei#qOE(^TPp0hyq8 zTH|!M!p|IzhrDhQ4mY>zgZG0S+ZCMW@hmql2lrj|oJC(9wZMMvQ=g51EHf0wQ)PNONQknTMGOB{HB zy?WcAX;J8T%!i8W-?;4T6H9lZL1*O0vHZS6Q?P70U(D#)7)U&jlYLvT8#x&^E6BV(WH|PTasYDdnj^_uwN6Ms6}j6Kq2hT(xi+T- z5ZxAEeRDr(t)mB8X2GYf7}43b1%PCq+Ed!@n*iu@)2cwuNJ^F5$f)j5^7!Gb@)M95 z;-(^KZ-S1HyFMh%#=Vo<>?m8e?_|<*hsT$$j^s2iZ$@0U`R&KKsxh#%CmK*r1CTqn zo?MA-E9ipd`mD~bHMjP@&UU($jChIEKUgW9^IXnRa(%>mye?9^Jv({Xd_exsOXsz; zA2vs9N@%mGM$D=Q>>4X5`l-XeucefX)S6Q7Pve^nn~p*Av!%VRm*lmO2ZTeUFU6d= z7#&HkA+hC&lc;qzOEqqt!%8|@GgY!a$hqf zf`1l1N#xpylJrrn>i^l)ebLPrRr>8l_{lU=NzBUJ!SjeX&rK2d2n~>X{Ze2KBMaV6 znzv5wwd|*o;B(&#|G|VxAPOHpj(UZmcSb&n&3=L~up{~pzRZv9*+KtV8EB#fZMro| z<2|IILv?-QCEyn+G6gqh?j0#K3o~xHFgI^P>qPKl9_E~+o_-2_Y{n`8L-4psi)jpT zXcZUl>g%y^aS%=v^z^LBCAWaYsRKlFftDEbGM3BtG+F)D zEch0aj_e!frRDa#hWiA0DU{3rPZ6fze@E&* zV{WTX(z&^QU0(nh!u{A$Qgd`pTlD!%&sHHY-z+`Z8NXwW!3>+mip5 zP^Itp>E=Kd5-xrYSrcY$33bNgvMPHv5Di#ZC4F5A>ANcuul09ZMJ*>olD}g-Rj7uvS93K^Wq-Xc%F8gG0g3O_nswkU2%4B4>!Hd?n)#X6&A1( ziY!EqdqXwWJDOqjVe%NHwf)-~lc()=6PRB`rh7S8ziuu?tb(S67pQtmZTZ#e4VD>| zC0epBkq2ywn0W9~#Tq#aRv;VwUhCr$Lm`|Al(sb`LPfLT;z%G&-)V}Hl$Jbn=KY!4 zm|#azKBH*%r~=#Gr8FF#OT%6h6~eI3$#Ru3YeCj2HtI(mZS=3C8lSA_q+2ajpgA$W z?Xi@g{$6wK$)LC7?>Vc(A-M9!9BjYy?JysQuPlK7-?yVCuQg8`5lF1y?1f*1{r2Th zT+VItt8UPY5iBQcUgetQ^r=e1BMvDXZDz4QXSi;f_$~`J+8#q7*n4sfyOgm#_>6Gu z9G`iNr4||scAgx8Ww8QpwCv66T@jj9xz*=< zE*fKYxdbw|zUCVrTM??cy z_=9Rv9;MX;ORRra6rnyGtG#^tTHbv|$N7PZVSX{l)?(uU)qZ9bQVtA^l@1UdDpHaM z!|E5^?w{49u8s>oB;%ztQwHHI5C=)Ji=+M}!ZQ$X$H%Wy+e{j%ae@i*%~W)C`%^A$ z=e_6cmi901)=%)}JXQOZHUVCWkJA-IMX)<$2x1|gyNI}mNSW)VDyA(>a<}!1y=E$77)sY~TA^VxR z{44b8+2C4}pez0i-_6uR@ml(r(jKMGPM7bUy+IRCRWXNJ z*m8vEhDK5r-O0>$eGZn+Eb_&6uT%fiL=Uw>`L@)0+`1GF{71+6$DDx07K?0|ipY!G zXzSZ@uGQb|wF@=Hzta=d4p3NM=zRvroxhngr!m=16PlVUr_AQi7eciOSzCbD0pSYf zZ|~S1tXgfQ6(RgBc3L*8$wxgWFa^~hxn8qx6F3314H>bO5}+?cV}T5Li6ppuj9-(u zA-}k_IX=g|RH4d0L;izCm}4jKcy`Y{vCa8$E04V7%WoRqW^_>p^)1D1O;R+zTselq zYjC({R{5q`p&ITb^w6vxj}>s-ZTN7cZjR|IdwT9W;I!UN^4PcLBmK+Y^yS937?$U$ z7{#kfnBfTg7c-~GrcXcf!V_q`#E1$zuK-D=-vCARi=w~n_OxP`ntoIx4PzYW-<1gy@oubc_@kq!WP^pR36$#yY`%xNOmPHNOS2hws<3?~ z31_=(S1Q#Oxkn#cjPV~&>dS9#l8l86m<;3w@AJU6XZNmzDf8H4%MPYCgpWu)545=qH3<@Y7pcKhtxRk$z35BBth zmI-V|eXNz_)gra`s=+207@goqdFhIS8)lsRj;pF#S@btl-toYVEHt6?h zY`Ko;vFsfx$92%SN$z#RJ^Nf9l_JeTMsggo<_^rp1W+lR z1VxwX4w?{|5@1psd(nVt)dBbq0qZe$#t1}n5&Y7@AeG83L%&4FYXud}IMg`5zobGY zb+Xpq&2+~m3ekn!%6CVG3)%N#P3K*5vKew_2*TQFs#VK9B}Bw)dA9vga)eT)-m})b zdIPH8PKJ={xVZ!b+$5+sCpR8BIlC8M)}`;lLpck&0ndAxSdp>`$rgD1V$r*zZPD7B ze`=aHsb+OK<$p{$X8-2ysaC>?{mP;Ins~O#bM}ewKZ9hQs5xJ7Nl4J>Te9&h)Kk)< zJh^yr|GvGPfJdOin}b-iyNNW%$7~Y*rr>=Kou9h%&mr-qjBdRdz5bJ~Ys)~*)}d-c zk^37K5r`JYXBAB!V@J0@71e_rVkBI`g|Rco*Y|V@ckO~xc7DNOY^_>(Q5gE1(>^av zvU;%BB8;o-p}TP0t!VQxD7>aHs?T%!D)B~r{Y%BI^Lht;ek|g9b3iy5^jh3Lz~UM6 zrKtW!j3n|;9V@2#KWof`wlY**?Lpmj<#5P$I)LfF!OSlBxY&`BA~D7@^T3^7pa zolzd9vV!h8J13zH@1xdLjKn+K-WGRMQ3&zwNO$J7Ad~g+R^GQ>|BffpJclj2`MF!) ze!wP+uTm4?#X`3i;nQv203NIf?u1$xta&S+^^m}zI?HV_6 z;F3O^QNGuD{jF9Yh8{xKFm035`Af6#1K`<%=9wz^;CEQ*!T?Uj>mb}9K9cIMv-+tz z^4h@SCHTEaz)rhy9Gk()4An0IRo7KJ|dt80$x@PavHP0fFbpL%vsUIC)&C>GVC z);n{TxS+UsSx=50bvpY$jM?{07mF_XWl37kMvTEROt78p7?&GR9Re ze~O)NZwq-6aEpKs%ZrXHHf*s|+p;=V%7K1~=pq{R{-0V6Xm#|@HP+oLfM3YPb4PH` z5`yGD|W4?=q0vDX5O8%o`;C?KY{w3&g|hPd(oKBWl#N=<>C5-P&-!j+CKxQ zZf=-I!lL!+35|NL`Ep$;T`SUhXN#=txT8RpZ?9Q( zh7xXShj{FW>ZmLjZRBuxg4bnxVV8LKhi~Gb%b2jGQwVTBUwNzpr0Vf>TV|qqQt6Is zJ#?9f$l&eJJ>Ec6YMo>=Fta=@g2rtuP=PJ=OBoIUpH zsGIWGo2--=cKzeGt~2ksF0*3yof>7cGrT%!EMoE7keR9BB!0JTMMk;dt?r<_>r^^S-BD_Dz47x@}LjYv{%f}4X8D-N5#W^8LE$JDxEilxhUBp#BK#ZG#7SHSZ(ur zUPw7qb#oHy8P#+XjC@ymetV7**VX@mDV`(PQP>m!TqIuXZ)NK@>drZ~yWo_{kU)F1`=O(hi(W&q@z#fHZ zxAOZRY@PFSSaH9tW7|n%tFdi1X2UkNtsOSD8{4*RJ85j&J~?OZ%zf|N^B?SAzO!dO zYd!1925g*9!xqsu(YcXN96V{eE$kAHPC)@2+W=v0@}|N96~cezHs#+g)r6wF^Zl5A z!~Pbet>3V-2+pFShA!e}#b(HO{-I}sFYm`DN#dU$62(em`%KEeg?ix@+;b<3 zM@T%0*KoZ5q%mfNe@wyb9R4m5om$_%*l9a73>>u$$~fN~(3n!6d^#1nUT>zVVvii0 z6;T#Zcf7NQC9Z^{Mjt1l%d|UiDpO4HqzHP@e`S%OC-pV+hDT5(j}371Y-PdGWV+rg z-PpK_qm`F4DNh;W@z&_pvD{y>5Ic2twWOXFJ3#c$QFw=y66U~eAf=_jPXXJx$7I(s zK$V&kV^et4TG*kG_UZCDSFTu=JQw-Jx`kuSn&?;!wfz>St~#lCY{|>|xLTp!V2A&Ecp880 zHYI*9yLmk%R{FG?b&8*^9fnlYwo3%7} zqozq`c$P>*IvO81g=~;_hK$(teoxjc=+p6)I^Cr}~Bs}_?-Yq?lO0Y2dB%*n5Hlyz(c14K~U^so? zS?})VzLl}$Y-q5u6HhFL2>St(~F+Ff!bdb6|8UyK|srP)~WN@XY;EGBf zq!Y>WSnY1Jd-@4-N)N~N--#vr|7+c0|NpH!U+b}~9IXF|6|ypaWtdpt9RHUqRE$4g z{4S*=RO;)b=W*E)B62iKf+0*C10f<~e$Z><_pETGOJ;O89h&K`f0(l?C*0l<|!b%7AGA@~oh%#%M%4bICZRnz|shbs4I!cE9v0J zU|?%JVWR}8L(G$Gz))v1!X4$tFd@(&!|ZPdOK@=;+8ck|!(8#gfuO;`IrMh*fvUOU z;BCVQgT0`XvyKyJ%%JW-rR3tHGL>%%Dqqp@8rBeo85jr%2;`!;0uj`3=lP_>2v5Y- zlfJMB;G&*=+1*uspx`0AXH!PG`Fy^qtYEi8HevpT-o$1&zO2n8_`jtP7<%DhgK|K1 z?7LMZk(us%Nj`n=KR^Qgz5-0C5ScgL_01#wP?X`#9u!H*gf?i1<6t2kP`kiy2u$K$kBK5gh`D+6 zIL&{G*ip`YE~o#}6q3-<(b3ZZ^K}Pf(w8)?(LbJeEd@}Q|G5`0$W{=bcJvnOUjV2@2O9l0_^Mwj3~sUbl@RUqaomEJGF7X z>E#e8cT;SD1WNxVNB<{!SwLVONRZ(APUW#af#)X$$fv$N49MrWv2Sk;7Sz>e@E*qw z%T81?W9X-C=_k^27xSA&(kJ%FXB&weBWKg5&Bx})XCI=yWb^Yo`zszQj$9zXh+q-e&BOEgdyI(pDS31aMJfdq zF5u~23sj7}f8cX0I6f(l?qb2ON9m>s{*TI}psWQkfzq@-T6{t*B(WJ=e>6su(V8?A zOiZ^qD%|b6oPp2}jL_a45s)=EVG#Tv%J&8(cXOffv*ge_B6EU{X|wcNA4WorTm8dL zmOnj!*YBwO%Ob@n8B_*m)QX{o(s2ROGTRVr!A3!;+LQ34o*Q{V1iQty^gQ;95)2j778by+N<;;i;XV&PQ?^VBJFE1r=#=pdp;Y@k2ptqEqBtC5>&fE0znbP**stZlPjq3B_$t>?f@jEn zb1(lcD|*ebYe>N}5{+{`YMVAMuAJ&|bZ9wzS30grPgXqGH^R&HFF@CkIWe?D)m#t> zGP4uQ1;wHRMJm9-Gl$Xz8vhZkR4aEK5bTCp&Z2Xju61UMb##M-`SldA*T~zo&Yi`D zDIGoE-Hpw_gcQ00tKZ}q`7o<Qqfv-0iBRDq*?(Y>;`E$W(fao8F z!F`h8(SdpubU5RdM@I;j7XZKXnu5kd>VvOzL;3Ya9TTBbV6fxc57tvbU~{{LDn9e} zzPfiGq~M$&RcTNE^@5@IOT%8(GA_R9fmD@KqhsIJ*H1tP|m`*n84r@Gn$z*O+VpxV^zU9nrU#P*RrUt z7UzUXwv3IYT)`FUY}>rTy}I7~~5N)`$y6li8}-y$s|kG#_(a zMvlw)t$VDCAb~;v$c5}*?FEFI4oCVyTS0hiWKK?0P8A|P=%(UA01XxQR=AS85b2OF zUW`N+XOFhtredYD;7N#xdl?2-fPO(eOa$*@Oh=Z*O$6KaW zxJ4qG1}&O=>E6B>;N#DZ4XzyGW?iY~BSA0NiKVsCQE8Tog@QK3JF6LO3QU2DQ4SjY?H^7Flch(7hd1_jn=YJ4S|o$lPP0}?fLH|p_4klre#*8^i)e=gl7{*jd7}9jQl9-yaKa+_bF`$hN<$H~WbNO}9z#a!BNPnnV9c{*hPy znD9DJzF-}04xs#PG*YPA2z$Vgt|f0oF--a~Dn>0}6v;HePwd1{`Au9+zNNNtyDQBEFlA2AG#tgP`?S7o>jjv z=*RnwZNpb(t0jojN#j2jfUB~0e)g(V@Hjm3mscW9UXf)==e{QaMm5;lS)4D)4 z6)u0t+Y%jdQg!%bAa|n}vVD|K%q-1Dq~~%&5Qt7Y*cF7;M@Lj@Mmj^ygpE}x5OfMg zO_^@ZytA|TVz`lEDBRpU@k5T~UP}2<*AjP+avxdBGlwewkn3qxPCYQ8Qzk9nfj(3I zydZ!}1hIHv*}+7Y=QvW-^Kp*nY@hM7a!Ay{P<-<=kIMF#owQ_(?%8%I`#O!pd)=yd z12+{Pu-~%6_7~brk<}qFWh>dlbiq4DJy_s!&df|>JP+qT=@Z$LjP%9-rH|z>$b2>C zWs5rClTJNPgerEde{oxTB`*x7FOu+iWNJo((m3hKAiLP>ljh`>w@d4>bz(`QJa$X; z6ZQg3bG(??^-0cl$OezS3s8Yn*a)oyfGRP~{mtAwD|0Nl3vMUK#ZbT9fv;2PY{seS z+L-iS6)z@KmF$uMl9Rr1HkYg|^K+Dkj#C`6Gos#|SI5fCxR~r|$;4fKjnBP-vJa7i zOa;HK>zqI}Szi!FR8<=5vMq%KQ7|U~w@%Z`_V}6vr*+(Ue!1<0PG73e`FUy`Flzcu zp+d}g$^2C;C@rRmXk!0}D^o>cg6%emL?aJb6)pjCL#aFRWPGpwPv2`VF!Gg|fo*K?*NiOBd&`Cp2@+*23-ZlpgUsEYo8goayO6Ak z4{h}0L;VPgc1A~xgOv1VAHTg`kEm_+GpFb@4nyMioz?`yxlQo2Qv#6^qemUV=&2$7 zeF6}J8SOKfG4&zNi}~Kb8@lG^oVM!M6tRLtcT8?FNZ6Neh2jc~`##azz=W#C0jeCu z{`TRt8gb23+0gm|x6sa-slFXwTOZv2RoD;zR+doJ>8(c{OVt zB$F_mn-C_h{+n=K;|;t8)oqXs?pxYc6y0ChR|VtM^b?G3tA3ZJwyx?y2i_FQD)-);*0WrQuz7Ot=o(U@G#pI!LbO zdTFQ$#{g0azANE68udm8$X?#>TGecYq^majp*2XJ zp>933>qWhXSuS+<#9?r?yX3;HcjH9E>Mi1!$y&qz^jP@}|JD6jey*0(7`oH1#Z-x~ z0iva9S9EAJuZ6vU1J#;C47YV{5O021-9z3;Ov1xkX#%*}Yo*&RzjF=CwaIS@&N`L` zncXhau?Y1AS*DLB`=pi_3qL`UZ=09#e*V35W<|Pe&NQe(NdHdXL2`^i=zcyMV#-aL zNXQE{S+bnFJ!%ebB}k%tsA2wXo14P?4D{-L?yE4_Fqgv!;M>R*;re*(XEcAW!Y!@O z?IhHp#SX81;h+^lHwT*Yjoa`dM2^%C+>?aKU)dL~ShgPvES| z_-c3jYII63(7b}<&?aX|I51gDch_05GGfmq9e*>rELl@AsFX|#M^RQ?w|r;`#i;&- z2$UxvFc`r%Kh&qr*tFA=m29YOFXvOe=Ly5~VDD4-Q=s$OCc3U^2|gBI!HE>E(I^t? z3%Xhz*`@G)Td3JfYPFg|W(~M>G{&YfkB6cfFy=Y~B7;R6FviWJ?{s7a2M5gD7qbXgGLU#p==gPqa*SB_6o=R5)3CxlBp_B@t0iTxM1cGYL4_ zSg~5tvxF!fM{RC$M}(zMcYO1;@DM$jNE`V%)S)NNzeM-mi_qukO1|}m#if-Hv*8C} zRxghRn9n!Bcj~`JP1foM5nRz26O))t;)6Zw3mlqxafQLQUapPg&q zP44nv$X|KcG6P*wJ{XQapVXxG?KwRX*b!J`z>%s+Bdil)g@nm{?_svTYVLD#K6eXi zZ4w-KABhq@@>zIFfN}gwX+(ViM6^ro?we6+surSNlin&h75o0t-;d0Gd-L;ljz`a- ziC?+XLHxus-^M%1QKgyhJk(|bSB3B$<)|whBQlQf##?vLC>G8#R{qH@5X9}%c#^sz z0Y<+}RvQN}!L$&!I9lC%znS3oVNbdh5P**S`QfO%z7_?m-$C2;%&?(;>>gkfB>+bz z(4uV!wmHWM&fT)0rZfBu&a!noDbSv2AbLLqiNFGZXct`2biY8D>^D(nqkTC0wD2`& z^K}3XN@2`O;)c)A6I^(c$R-KrJ8n6z0y0D!A`2(q32mLKh+Ov8r%$szbzf=+{bpaU znUZ;K`zzvGB%rU-vIu|Xk(-;YZW8&Oz>S9NAnHr;_l58^Q9PFie99GMh@HCR=mEKP zG{|(WM#qN{O*P?#_0Qyn9j&yDjW&Cf^noU7?`cIQKQyXpe^*_7wsV!C%i3U?0J_`i zO*iVW|G4j1;2M(Bqf6uSVW*8bm^x7?csKunGPRtdObxc@Ef~QiZTj$i> zkI9JGS~~<+?d7+2e*I||9NC5c$=UiL)bG7tm`Ln0`}gpL7o_3cf1LhV55jw8yBbsg1?0gPw36u>`tLAm`Yi5ah zYok6hbXCXbov+MzBg&*b4ycP^ss`LiKP2Y9E zh(r&X4JKdm0S7VwseNigRt^G9tTL-N`Pl-25xOt7WViWhUhX=^?HfsL%V_uQ>f z(MpIXh1$=XoDY#?ezWFoGeHU(UEe7$T&l*C`fw~ED;>M2(y4~jpPD}+KQe>TX`yHJ z@rOiiOkMp%eJZw37jPDxoI!?baR@7M5vyM3UGL#7<5cfk95EbAIOcl7lf8nZWI3QO zCnS=;_N;)$kzbTn&=U0ApWrB4LzUONF8Ka%C@ntot%CS`nZqBSqLo**#6!46{^47K znByN@)j0j&i|SGCfa#} z2@czHpbILS+hf1EC)&A6aX6zm$KbN)T=u==OW6cyL_4XmbrAZ(N1TaOpxm&FZAy6y zNsme8!bi^eX-;o)JW&>#f;o%!BoRjQuuB`XM^|%3i4gC~r|7;-pBYVq?69}!XzI0Q zY%k{@44YH_RKTf~Y5%3^9ItPrL%a>y_>Aj&`%%?>Mvw%x_l%RbVHT=R%$=M3V!n6z z!cq$CfOP!IX>1%9KG!mx`Zkf!hf3+Wk>E7WGkwO72J;3b3f3IJ>dDuP_*KmqdoKMz ziBtePEh+?0$?p!eleQ}Gbz2=V@fgQ1W*ZD6p9G?sABf#ab)GqS=RzXi?C#5Q#2-#X zZ+SU#SWOgd>75%K)|hA%%u6|tD!qvpT)S<6gIYqeZcUkEYueDXK3X4clDSVOmxqs$ zdtkoy>Ppm9>3OB)rP}tOF)6gTg}DR2%yl2}S>G&3Ffz(J_*EJ2@XzpjRrwwCTptLU zqM%=*E8shQVEO2+xh#U;mP)rk%tqO5g#7a@56#imFZYz zt*7u;Qb$4aUA-!^eJk>fC3x>i4KC>KZs`mz8*HqKbZb_xnHtH*zlaGN))X2p_6%V{ zuS{KL-N^bBSF=m4tx?5X2DS4ErMAw-Yx=+MO9Jgx@69ejxmzAIfd_g0b{I8~6Fy;! z*fiGKA7hrP_OS2mFy!zG0X8vX(vlwj%??ekVl z#&?P4kB)-BrUL5a$aQH{&i`sr=k?gEQvjekp&nm`mr%66ZrEYO2IUbf&FChz==zjT zUF|$h?QVfg3r;%B2a6AItfHkE6R=(Ro2;awK_!-PK^$iSoB&xT9RZ(}f`%Cs<*9lr z*>?zc%G5zOFvRegx|H@ngp?O2XB6%2CA%ZcT~x5p!;Bt%X&=X=GBYc4fg&DBe&88H zT^JzH!K6-Q#1lS4IGOC4BBn4f+fh{e9ouVy`nO?vdU|chB5VuF@~aT%!fb z_ucZpBAYu*pfvDw+T8XZ{6Qa+r=>=}4V>X3zwYsAlG=6vL#luqv0y+)rAa#Oq{RlR z4&Nwcfycvb0VvrK)J)sAQRPj3v2hpG+(Vs2hz}*i^^PfUCcYN_bdjn1ZwqOWfzL8ll0(0~szRcmM*rO39Py zBoV3vQZcFM1gEOVJ$)^z(tMD}A zKIKGKdLqCc+~`0b4*5)sA^wk-t-GGHPHe%;PLP29uUiD4D81Mz87_oH_a|{kC%ui( zcG_8a8ENIk(S6e1AybvtXTY06>Eln=!jcE{{^ z1~PDSNjyqRMp*tDisowjM;-ltp*$@LtJ=>72@@CHbP^j&SEL_279DAyTPo+6;EjtfOhK^r3UI1heIpPjRvXKmbHLm(AsWq5s(a zlm0WdG5sGABRlJVEOc^ke{FRBw}_F8iHYm~;DBylBc0lF3}CZmcZ4w;;ZDbL`K~c0 zFrZ*0u;flLdIcIZUx=Jkl`;kdM1Hta4CQP-HsoG3;gsvg?Rwi{2c0FwrO!cXD!*su z$_N~ES!b+o9RC_pIZ|*AgcwASF$gV>1Quy8$nW3G!oPnjfgvFo!ob0Oe52Z8f@~ur z0qj!7KMjhT1N^Aj3gN_ZLV4_PwsN2`h)JPPVq;Ka6Hu|BLg3(KKfgfIF%VV1OcYPw zDB>*=d?*PtyW(zCfeRE#Dh!^f&1euC6l5VWEv>lECSIWt%rhiV(BB{g#G|lhVUsXm zBA^m>C=d}h&l)fnukzFwA`()=V`H)?z)=`RU>on~?G<=CF*TJh2@b5wBg87WPa?uJ zWUK#Y0;Nuf75zIL17KooesK?1ae`;F{K@gZa;8Pqz zB-XB8a2g%P5A1w8a8nx^Y(5bIM93)!I1%+p4@~s;vBl z11EiD36!F^GQoIX2#5fGPr(8_d)_|uxP^W_Aa#vaKMKL5b`#qW{*qe|#Ag$`LOy_z z0PPPdpdjxT2l>Sbvixn2{Ep5Ks6hsMTYdT_v4pY}>`MlMbi~pPiUQ5_63~qddj|oo zctN-Y()DTm^cW^22Js6SGzY}xmn2NYR@RXj&e_!x-a6nK!r85i^IZ_t_o`|M$Sj|M zs|)VS7WkY7nlza}G{bEM%pZkR9mcWBD!3elKuzr2Yv4elIxAOe* z3<*93wAqz}?%1e%@MnN9ER+^1YOhO1e1Fwow}A6|66%;a{nBT6&S!R8MHqx~WJwX9 zbtW^$-`k(HIl%~f{+;46X67Fpelx6hm+clzC~F@})uCasAiftDLPTIrRWo$}UxXn{RSX4oLDgCM@(YZ+S_hT;RDB0>(7lK4xU3$H($&r*9JID&rDMoK`Y4?;6@5U z0>J~nM(7=zJ(r{X(j<;??i-lh2JZA3`Ceuf6Wqr8Z@Wog#`Na#P1qAqKT zc!lY(wfZ3(j{<;V^o#tRzMnXGBo@9wZI5wy2QNrvy+$7i%eg=FpjI!6`@(9Bx|{We z>(-?k;ila&0jnni#02*$p6aRypbQf|`MfQnj$0uYx#A~|hv<=QDzN+_^|lJN9!WHK zIHuL9)wa4_NbWtA-#Z{XCh(=peu{`-&j7_NN?2_Pcn0SE6TKnX&3=nx0YmFIslhdc zBS-89DpGGP4xaSuu37A3PvboU1CQL^9k>RPkXrl;Xlke!P6?gJKOKYPUXP3890)nc zn7I-Mrc_5~(N>PabjY}ps|jTpbmg(`I^<8VZ_S+M)nF;-J#TVG@(39|q#2q#k3(i$ z_*b9WPyl9YS%-RbKn|*nMY4f^aAm9R-GbRn5BbYk3sThS_#t76rl;&-lM~6kgc1Hq zt~!1&hI2l!+gwhLs&vZ6U99?fm^_O1qG-||6R@(j@XiJT$qyaWNtwh@b{jS{t?Sb> zm)sEp=a_`CJhGJZcpk7G3vKsc`$HAIC-i{eC%}8z82^`jU`ik^?WR;Z+oGXxTep!9 zwgooc?~i-S@=FyjyActM%v3}TMM_xg!MAvYZ%88>QSjhyz4q>!#gb1+PV`9g z%>keV<<^ zZu8hvPiGU$HVV)h{|X-i28m3Up)p(n@L1lhev40s6+&EdBn}9anxT&gWV^gd!)JOv zLI)SdUy6|?9o9ZB2B322e{+6BP2RT|Ed_je^L1FaXALaXc!bkueU` zO{mu=R+ly)d=O7W3k42(`bRnZN-HZ{519O9Pk-7u3r=N#kN=&db)s~wXJXk)elS8| zdh(BzI{XE(K`onuyD%qyn9k&0r>$?NbOxkTin?Yrh&{X6tTXK!W5mqdZ#cryLnfKD zyt=v}Wgkb%~!DwO9BJtSVJ|C7vMNptZHHi1h)aqJ?H3^(96yP@7 z5VX&JsmkWA3#C^4r|HMD%L)dGjl!dfDsJ9`?WWonHnk$I-n8LX7V;Hq)BXS-pt-3f zEnbAFJ@8mqPyg4xuVXdy53MN7y}P~!I8amn}rVzayF7f$C<%<+9U!fU;f@B`Dl?D_es6j<=XaPEu24l zinL|gqDy?g)n+tJ(XQvdyTJrpS%?B9^4D6r@~1FAulA?CvQ1|(03uKDw0P;zs9x#! zs9qU3|3{USe5w()$hG!P7?xjh0c_$mikv^!4ut5x|8vXJ8_oF+CUj}2h>!cPbO`;c z4M;=J{cP+XK#ni?BcS+7vNq>ZHf+~0_0Ou&iSzJ_M8Pqz_96wCVOP_Sz3i3s zVhExhY{U}K68*gy5B))UEWtQhx7r9XWOpjs;gpNo4J8XiFM!xbeR9NZw=d}Kw7*wa zDZS_2Rq1-4X0ndYGKdN6UC&1%$9bdF-j#ySS^8p_w(`fOGpB<0F`bSMSn=v3VnT96 zp#WC~vDl|e|L%a_q0Kp@qVH8_`hT^JZFmH35S;qU)-#^9jHc99>ShLrr~irF>0yY5 zj?M@JJjj{G8vY#pkcmzGymQ=Qb>X-q}nd~hRDgd z)T%_TA4+*GXGNR!X@dCZQFc7P?GPbhPNB*oHs;q8G3z?QKjorup&T#~UG}!27}$c8 zozfQGNL9gMkTt1cmeXmz=ql27sFVU&)}MSo==21@@;5aC7amaLnD3$^eCqM(?yJPq zcf=RE^mEe8m9!MBy;uGGT^6JGnkSq3nUEeNqK+__f=(rGIod%2#?ZnD!g!h6bq+|) zQyB?EuB3JnDTS7I20b1`mxEGGe4sd0?^0-mS})c@ANV&CPEPMHY2%u@>>rpX!{9H> z*_?s%&$t?qL-m^;CF2-|V=i;xKu&w{yZPp76=y`AY7$t`Mowlu#l1jyvo4tF&iYtP z)VU*3##eJ0*|m~mWsWEB%4O0Pz5j3sw{xowz2sTdRcbyj6;W+rgVQaL0?TV7pAjS= ztDeZ&Zk?#^NOKSr{wxeeH>UqU8fxgKG!)pJsE+2N4;(6b{aKbUR`=PjJoM;nL=e8? z4Qtz%(teJAt0eTu;%3`y)(q!Eo;Y2$Z@krv6Fj_)S(8Hyi~5Fve(#m|>089DMe~88Cey)pCbqz{DgnNXG`JgS*1{)!WIok5`qVuDO<*hVJ5PYyzc? z-}yVf9{E(ubR7N|zI8zHuR!l5k3O7%!bapp!;cp2VT@7_jdMdO7BHoXNo^$$t+u;y z$4y<^Ssw^WSTcI@tZs)Gr2Pt$Wp*H$`+P0o(sn9tn?P^Y#GxBMD(@s#{s4lKckG7w zS*Zgns{ar-O-07#tYl_q9f@P)I18B=;7Qdq1tD(nLn|eiq&4v z(@r&YvV8`tK5T%Qa6pd4V(xPBJ^ zK3PTiwr^ulH{E60I&lAX?`hXbT9=P3o3abO$f@iGoAQK@DkJ>H{${)XmO&>rFro$} zLSCm(6cYD1SN4t71ZM;cvMF$078eIfD>x8-R_PBnoi%fczg2|ZFH$OxRtB{9Z0xOj zh02gTTV%3r#4z@Tvg01kMrdGF2Hnqqq6|t^TX%H4kV;`0Ie!7}Uom>dK1`+-9SCiw zz~gPJuC**JgNt7N$Ao=t*~f~tN}EgprmH&7+KB}6AE}>7oAi;Jmi>{xqv(I& zzf#`FZ2CQr`Rp@)Qsr&%g~m5LtVS@d!OPOeV{Li}eEgW-(DcNWbesh+kGv~;eBy^t z)a&_aabh-kM4m_*S`tit*QwYTZ&j4NWM8Jzto-U4h{$-Q?x*<`_>4nk_fHOm?`V+l#?pc z>b-eLD!CMZlM>dZtNIU^q0?MziVmH%ruM*w#H=8*v{#y~kJ`(bX(2|mVxfITf$3-ZnuUZ0}~dA z@X!qMVrwY6YKOWuV>x_42oDZgiOZS(QwfC%BGx_MJzQpi_6Rw)Q4x#oic_xSe)@B3 zbz5___U39yVXpuH!d<`jSxo6!;cuN(>Bi>dMf31R58eaDUhETVa7Dq2w`x<6AOmCX zRd)RZnP(rSUG&n7(Re;ZLvgdmu#6PcBe|9arcvQ0D6hZrs-oM%)l(^HnS?TeoHvii z%gu<~;#N|%J{}NZ+Y_buh+Al&8x?qkF)F5e?B)+ivvPqemqv{mE^_ zBl&w(PYI!4)a1Lme3pDI{{UA|Pfr>8m2XY3fMXf8hWfzA{@0%z{2~OY6%SSB@RZNl z!K1d4T9FHggH3EK>T&KYHAvj}v(;0%!`=6sYB&}ruGg)?JFxyj)>a&=C|MMl{dH4Y zu9%9iEAhC}F?JXIft@G)idwrdrn%Y27>c*D!J*}tll7XQu;s4yvvXuFLhD{79^Sig zNs9~>)eG|+9V_FPG#unM+(kVrUkE?AXp&1nc^*7adAG{DhV>ULv}Ss!O1^7EAT#&h zTQ1w5N1?*)g>cMp=pQbmG?8UhM0c+ZZb1*<{%J;-&ct4!xBt>$d{6lha()<2&;zv( zJY~(Cktylw&tZ7v$#3gY;6^*NdZ5=AwUpQ_`3SWMFothD$Ub*bje*FEV}f58UgsfLZU_S{CTm>)bPYQOX*H_6hZj@c=9D+ zcoIrAuG{Uk)UG?D6|>tOBR*w{vM?t zd77a(z<~9Cq5E44=UzS-qy!?|YeIg{u$USO+`p7f8@1Tqrep;!jqD)W8u+gTI4Rx; zI4q#HTlTonYGx={h43nNAjn)aJS$cfhHvcDm+fk+QysFpgGc=9N#V_TexXT^qsE{) zNDcl|Ri3ol(XxBZWwK&|OxRfAu|fndVSc=xNgxWXQADe7g4s&=rxQy?-87yFwH!4G z*zE7&+t!|DNkKp_H2jucj+49!D%g7lmD$6|_2gq?%Z2b{NJnl=%r%W9UuXN!m?e)sTo)Z7G?Uuq$^0Hhb zpTWlB)}(*1!$#^dyD7|Kv5zj9<~y)90-?8M_D+19Ni7-XiWE7PV<0A99j$qb4SL)`68T{Fcv;u)Y z7H&?I-*TL$vPs3Y6RGI^>DG@okT>o*uB8+eyKLN{58pP%Ax(o}=omq#0;;0Z4X|=V z34H$?g3z;}ew?TU}XYX4BZ@tBL+P{HlTE?yic5@I9P!ykZ6 z6kxVpNG1y4&fKyrwH>8)%2PH)vyb?3Cn4lbKAB5fnIxV?cSpV-pgZoow4x$?TOz$k zcvQK&W&CeQ=J{TWXrQ%G06Q$7?2MOu%$uJ;LCr|vQu=Woj1_E%^! zZ^?uFXG?x7Sh~wyMx8*(-H8&W_Jj5i#(v6S4OvIs%jS-PQKB^h+TEyfKhWuVO^Y73 z5bV*dXIR6@X!#IpwYj%)vh529d`NZQM7&Sj?8bnAn$v>kxQc({x!=mx2}*5x2VX^J zk8DaAamiS$DK`u|M{2#QYSOdSShfk@AnL-AzufJkToq?_NnX;7I+&N3;UE9}Sy-ew zoD-jqTU#$4L2HwK-47d?0@UW(V%BPZyX2l_Rx858!0N)?cAQy5VUJI8l|rVrgo=sO zZMWn>6&2@DTdUvaO_s!Xe5y-i^WuI^dI}}30=nZYlz9hfkXbi&kkt665Oj2AgDjp+ zM|Gow)}Tk!ao!R)$UdlsExw45nSiy|6RkbV(^%G~;Ky_s7;PeHAY$f^Ve<`RBrh&( z3V&<7kU#rPOj23PftO;XlXs7->#jRLiWUR{cGNwY<{H6Mv|xQ`tz$dPC)A$m1BZhmoli^0g8%0sksQ*p3YjVN_NMi^#StUq+9&KC{n7d1@RZi=C zcQNC|+txeD6`d~+$y-J|@VXVDKgX>%Wx_Ld`q(FcR=Faa(jW=^{W&mumgc~rH6wxS zZ)&k+bPeC>TE{*dCn>3O=a$e=K~Xd%VEa!TcYY=de;!Bpa*z8l6BOnXfKfJk);d-`7z(u3tH@9(v);X_@{<#%8s2v@+rr>W0P8^(elN^|H>Nz2GZ7!s z-h&p)E!-@sj&;FJY3P7iXcHh%XdNm$^jx8YvEX)rDp1$7)BDaiJ|3Y=er7XvF0~=u zkUe3=)#mo)oUI~9`Zlkl9xaVNs?_{~65k>MSRsnRaU8*|#~kKA%TAIDI|Hgb7f)3s zr?SjNQx<&8Sc8^BhwaYe^FN2Tjbl)4rBhfhJTzHD-@U)qqupKMvPirtM}!`r$JW~| z!5KD>g)AE0l?0yr-;lwM_muw9A#$ZJ4>{OxhQ&ON!?*F(n(GM ztlYfbkks22bbpF@5#?c&+;rSI_s493~r!>n4)Zx6~P$G%VrVE9{x{mT-9k zsxr6)x9k#3>$0M~ndl9x1C&}8iwhe{w)qa_rGNa9)mj*^=9$?6j!cqW>^(mk=cYNZrf-8ps&^I2FK2!EO&KGRc4jyO67C&rhd_ zX6BEYpuWOt{=H?zgGW5@Xd>Rf_-6Gyg6?%F?xK=zL_^ORN3RSWNKxYF%11q5YAJ!= ze_1EO5VKtLI4GGk2m$9Tpgr)XAZipXbu%3;?gXkQn0vmV^7^E(H?AI|)W&-a*njP0 z(rW%)m%N7^b{9_(@f!FEoXQLp>#Jr_89g)% zw)mC>hJz1=38(6js!&|K-b|oxrNw9rN+a|9<)@vqgcUT{O;15VD^eVmqfZGon~hbS zIQh2RibXgD`Wr%jBvdLd1&{q5K&y1NuZDXknII%zfbpi2Y*O$YAreY#hfO!A-18Gz z&%5ocL#@rbP8U$zbFB30fFB*X38*o;a)#SAQkH!e@B)8yN;K)z`b@96P(%OG)Mgb* z6|T*PIwKjbd!&?&z0A75ttIB2h`i*>+CHlLtvcu40J+tm+A?83#^ZVd2)5B{O&o_Q z4A8%g8|3mj)-`cVnvI$m*eBI#*l^$a?nj}&Y>r*9+c}+9fg{kBhQt(YXy5NrIytX$ znA+K@-hOKWkq1g2gIG>xc-T3wSHeX}>$5bP=}Tj~@*2@?2xdaeEGQe@0`>Q7SfTNG z(udem0ET%z3g>l8Q;2*C;P=x0VT-Fb@6wlN&Lzdsv_?>k$=@ z#x!V}$RdMYQTr!GW@DW6x2rzPyU6mSw%x|y8#$~%{i%w?R-J~s@}90qaW#93=CSm1 zPN;(wR_3PQYm1?d(~B|`WfBkvm8js^%VUL_eJliDaNS(sl9lNPXdlI9)GSicB{%=o z&YwYh7+f4g$HUGiCi+S31-XH@;dnwN&2j-c%d)ci)#i=qH$=YtSLjx?vC&%*f7)L) z&+O$D=Xw+x``+Ap#B5_7S!DyRe?kKzEnh zNx{vr>$7D@Ab<}JG!W9kpFv2z?DWNMrfIGj=8Y#CnV(t?x-MxDnZjRKl zUi_*wZch$3P)%tBTKE^+W*$Bk`>RjBw{?)Y=9Z-ra(~esV;<@I7*L}a%XA5p+ zn~|1mdsj<{{*O!7VfX%R;u#hy@x6X+tSZ&YN1j3fwoi8eP`(Ss>-^!&THEe0YwTX8 z`FK5nRYf|Mh$505%iWe3Cz#H`8|m+9b6)J-3|VWRis$%J;3y&>o zpXJBzLD3ITAR~z;4?(vk$3$E(edQK%jQ|mMwOih}C`&0jznl zq~^kUo&8SchUVvdWyqA`A+801`=yS8+Igr#Vfi=-)9k`p=KwKKL6Gh%kN<7Tm*am6^EtTxBg|*! z;NoEWpERGDllyDt*Kd*vsBdv}BHw8Ij<3C5L)RD?^)){fgt_W6bh6yIUSnOCC+~U| z)p>Wh_Ikm8*a37YuqdIW(K7S zLz->FvABR$v#_w%ktr&M@PJ0@mY<#XN9g*tgD_yr`sS95NghiAP^_%TV30y+X3$PA zFn>XR@PXb4VH>h5Koi6J{(B-49obk3>giv8CPS#NtF8r~^-2i&$Lq%P^QUI(n{Gg) z-}a>pP$rH8$}(8U@o+K8p$=lm%j%1e$44gAv+>?%4w>E91fBx&JyQ4p#M99iPZ2)5 zlD0AzE=E;JRYSP|`2D7-xv6{kN&Xp1lt3 z1MlJM|4;JGHY>WnYyW1)qSxY|%ntnz;1T2(XftR=dc{ZMJF-;*(eT$m>UrM$+Q`O3 z78HnuEH*Z@9wnu#tE&XOhAFnh*GPf{^t9m9Jbgtv=*5FPz~LM1N<|Fwgv?y&VnXE9 zstNYl(7h=NI{Y&g>^$8M2q!=L#H@eMzR5f4ySxE>y-~JrT;-;_W*jzq} z)a9k6k$zcP86Sexvo^B6OF1#S*gHevyzjocflU;DK%&5)I6FJMtcregiOPQ#O#q_U zHJ{6=gu|=A((=2Y!uay!!pbRNe|x#g(a_}B=-^`iu@olc+ky%6gxztw$y!(YIz+`- zPW+vuvUHI6k%W&I%Ka7DLgqb;*KWi1$^r5Uumyd2~JIW}xHHT2)=Kc8$D zi6_~tlm%!7h6nk~AD_vU)@Nty=k1@iT`h?jsn7br!GsP$%KUjbzOLV_!Dr(8w#XAv z7UVQ!Hv$L`m@i>r(hp$uJuj)tCaLQJ8PBVO;EVv|V361}yDE|UY8SC*b!8b5#?IaW z^2Ouxvb#$ghF%ARl};rYIR`+1?-eYQT}@pDcl+4?5W3mS`HTa(7YvZOWiBvza3NOk z#hnK5{iJ&~_C-0{skcU8-e@AJO^F+k40E%QGzG=YDy zQY+Xy*&2iXBWC3+VdVidQ?ha~wfu+0f4QYyj6b9=Y-a%iew@iaF7?0D1p1Ke$JJx? z_vQjHuyAtyN9;q9rZ#p!XJ-H>&p#pH2Mhm!_k;Sse`o|H)e01mD$z5sK3CxpL; z$;}L4Qu^!q$6{e-0Wbmo$7K01?f;j_0bp|eKPJaV(8baT_^_Ze{5A3Cwm*9rj^;ph5o-%P5*Vh{3GWN*8ki7JKF#t&;w|Su(oV($`@jt))H3k zCtf&P0ZqZf_`3>AKuab8YAs{73m-=;Z=Vz>e^?aQ7LZ9N2N6Jh;#8EU ztLG_(b^86&btTEZ-%li{X+*jj%;WgR?qk=H3 ze+d~FhrS*(9lEpvHLcTL?{95am19JUkvlr<2w80W#kE2?D(CpcCK-ffy3sj>nBdL@ zQC1+EZ?i^nt2Ks@Ok>^^#Hz{7l@z`3gZwAyKv33=;n!j zWgrWmUJ0lhO{4BndRbJ+3I5Y4DbZF=Y>ejo6R+XdU=0lrYg8?HCl80J+~Dtf2?ca zy@2+!ye$UzKWk`C^An0$^$1`h*eK&i7SuALLnqRY8-qZlluMqC<3EH)UfG>E3ClR| zr|%YT8o^bh^W$Fj?&N_NdtIX}W%(mt1~pE!a2#=MpNs0MwG`e$OKfuF-AG`0!JB3e zl-Rz;yO#t6YG4T#>D-win~93-e{?>wpgYG!<&|mV3<#q}V?s3-J8fvGk5z)UB9gKM z%4gU2js;HmibKQCwk2NKM~ZgurqL_L7Uc=Fzn1IQcid_QAycXt@vt(&@m36q?25!6 z@Xm|~=FLY|I8%smJxym^CN7n`{h(F^+oJ>9+8FoESm4fuEa#u)ja^pvf2_BG^$bAh zfV%*`%3x1X8ff%0+%Q?ViCHN5TO7kLVKvZC34dy>qGdQhk09c5c!5;~C-_!E=cVJJ zzCxqNf1vzLczBIdCzDoEC@f^}1_F7Yv;oF0Qm2&)j{q&tVL|*cO09(ee*HGt0b;X# zYKW&v>RMmh^b*cD(QN=|e~zQHVvCwtXj}5_t_6wsyQ7bwny9Ygme))^p8;FR>RcoV z)uPsXqiQs^k7)&IK^!Z@+|9;FOaa1;4;smdc|CfQ+-nK9vPxxaigi!ov=^PF@otSm ze0;rth7h@VPe(7ve+q5ZXin`rZ3@=N zn%#jZi6VD1ju<~MQrFr8oYSW%&1_`i`E(I5n0eByA&SO;I8=Tnjp3CxYoco)p;`%v zaM@?A-WE)l>SKrr#;@dkuHwBos=pEI?iuAvZJk9dVzAPK>`zL^{eO^Dq@^nsnwvy) zuGK>vY}4e9xzQ_de`wz09zseiMJH937*H!oF;UiU*gDh~(=F4(1B{7kBEfz?P03mWhwoj|TYMwbtbAj(; zN>ItcUS_8}==|epnhZpi-ci;luMsvNz^@+gCagU>o*2G}NQGZ{Ky|+qqxiK83^$XA zQuj+QCPapCf8@bSY;|M3DFxlHt8PJBGO%XI#4)mB6!m~WJ(CJem=&kd-RnYT?vyb~ z=xQge0Xn~7B8oiu)TEU_({2)5f$4gJ+PZQbHSy*EWW-&rNcfszR5dvP*I^sf^4MCJ zGVhGv3^WyB;Y(OXzOlAsQYEBGhg5o#=;U7>T4E)uf0R^&r?;3u8yv1J*fgLmYh^`- z@2iH`s4pq}BwCAZvv05z+eZ;L+mNwT^hJhD;l;kXf0%>S=GRtW${*M3OqE3{xm8eOXvHh_vG;`y4r@w?(j+PUJrBI8Yj;eD zyF;+}(My!6)8$>p=ZWbG15cv++eyF<4QsL}G^HK64DI|^uFT)2ZC<~G_!iyav=LXA z;b5@QnJ_jpk8lrP^WWacWSxa1(^xhk%ZC$se;d}>$i75|%9)5=)3SZ1ZBHFK0$VI& z@%Wa?UFeZk;g;>P+gOmkmE4H&)bYm&yUJm8ZI(i;So}T$<&2#tBUl|{vfY#WX7_Wg zyk(!z@H813<{JOS5b2D@S;-BCH@9)TVo&tBZR7kghUXM7#COOc^}2uumJTBKGvEO(y_ zJk$!9BvSB{uf-`Ja1n7D(Kod!7;8=Oq$+vL{9e>Qp&E6J1oNpjicGY^u4bU0lyivH%*)FfCji}HC+cC1NA@i8WV3}u_g)ou zerg(510(zvKodvb<0wqabpr_ay`3)YT<2PQldUo+Hah@FbJ=S;8JP+&ai~9o7 zrGT9sNe`0p1P-hTMCwP>PH8?6e{W?fefyp@IT-p>(@o5s!;kv2pyEt>J87Yv!Z|Ps zvR&DI1q4Wj&XPi`Jn#$lRC4N;Fb zBaAnNI}2c_I{DI%IKogKJ0E>+mAj;=xaLDTEuVL>x=adc0kx}nE_m=xe>^wF1xKnK z(%^RJ_9_2^>nEoB1sM5d%UP@`$0_jmSX&s-PiCnQf+xRzBk-CRpsrDe{QSqf|^##eo`WYHf6h_z&}6g=_ikhv(s@)dCNq==*$#jl&2vc zByFCz8b(m&ecs;bt8s@>43u?WXmQ50l(N-9TJGckiYddX*dKqHe^TKHDoSH@ZIS&F zpyk2IV_~{kHamAp(VsARW+U3-pfUxufU&~cg4;3@QLxgGUqF!mNHr~`~z{L7@KJPCX1YQBxy~L({5Y6E6 zBF@1GK5o)-v+o?p1Q%7R1)nn1{vZ;|5zIlrlJtnW^Y}$-1{aNo!rFzFuy&tKm2+^& z`HNKJcn(;=x+;XKQkr}|@2|hQnI7OyA#|cB9I}8ILdfzye`b9h?TQx)zU@H`?=9GB zJP>LyT`SYVHMUSLE(2Gqk50!u-pf-xy-X0^wi$Z+tqluj;dJ|*pu;Ue3K`N*(3^EM z`dwig=Xbyktr`h(8V>}u(YUsskru=PkgC&%ON&}JQs^;L&tK3J&cPZlH-S0?>)S%M zmpMTFE2_*8f0+{FX*@tyo{K)eRa{?r?<^LMUQ@gbftg3?A~puL+M$FlT6D`1j>@CM zk7_|);2T3bZzNtthnyPk;S&3iE;UJ@Kt`Mm`DAjT-^v@;$}BUb5{NogjEVQ6yKXz5 zXNl)ZLSJcUZpU#16mb1>c9m@&3r6%Udal8owpqvFf4fS%2T48^O2&QnlIbl^S#0!1 zDR1VCs3l|e4!a(PK-+aePLi;bj_4{u-1OUf90T}|qh zIz{`B2<)wXx+LBFnlk9_JmU4yd0ZT~73#po)eB`FaDJWQ4)>b^Z_F45|Gc>>)VmS1 zb1G{4e@imCYL#p}3L8ph9LE@ZWIZdy1p2Uw7*Bptqq39iz{e=ljp;F7w*ud4ryK}@ zild9x9*WWTK76{uLifw-(i&ZZR|e4GLY$FHPr{~^NXP$~0rLs!(8(OeM zd9mnSJ<}X)qP&KPBEp;;*RjWSVdUofQ&2TXY}cn7|Frru9_m)^4UHWgu!!O#{Wt|@A&Nv)A~G3FD;w%_c9e$^q#Ro) zW#@5G6K52(*XzDpkcFF~GRe2FX_>Jj-q|#EXHucP_e=OqCyReF0);E@RGQ6+LJUdL zjwC-}REBdd&ju;vkYq5H9$Hhg9h7*De}i%A`z~qeM4&^+81tDhn;bIKbNaP4UMrlU z0F0+Z!<^%qH8$&DPng-ytxsUVO+C;~zqIxdLrtuxUTroiXW@W}-5#`J|4RZ<9t7Fi zFC)@Zt}-l9HHQ&erVSaE`qCDtQ1V)_rABQlekS9LXnth`&a+xL-iPU0skWG7f3kiZ zMUHHK303V(T%SF=b~mk)oE<-g)stbfULe0O4_ek@X*)#1)rW}U2@-m|ac0;#L5!0z z$4=82HjhPjQ)A!_P?@LJWSoJ&&i)x&S1e{h8%iiE+19$iryiW^qDDSXSEz`ePdp-$ z?=?lFW~a42(b;;fA*Ko?+yCa+e_$jQkABg65_OpsYhH5gx375;$9@Dch_N&WCWzK_nhle}GP8t0Cp5ldO2c+Snhgs3|GiAr$ zjmqh^P%PEZvHD!LCHJ7O%h|JsTcwVUe5ZZY9m))HaF_iPG*TDP1!3Cof6F@$=IV#6 z!D1>VXeFMXKx7Z|=MaFIYZR`VMmgo6Q+0T0>>}R8d3nIA3n(5AN)!mrfzA{to%$W>F zfB6C2rsnjag%;5v7&AGde;tnb#@0V?f}uUsloE!>uW{eE3`P@NksY40D8<9{AT<_7 zbh9_9JPHuME$n`(o(M7zJsZTNOseFmy1p7zWf?$bK!xK!t%pF4H2CaZO_#|*B|H{D zsqRojf<7v+Le<>U3;)KqA}BkMe%~e6?}qB>y!__=P|4`@6jpP1e^pvQ(L=dklXs)i zKBm;J!`p?nX!8AafPd+SEXv`(kTHMsymL!|z` z#EDco7OPZ+M%u^fe?@C0FdJXMIz!)q981$2FH-q)U^`VCvGi3;^j<-Ts|vTt8cj)@ zXu3{yGq$y5WjrTL--j>FDdg}`)=7!GVmO6S^w$6)#;wzYq5xrZD0%3UOTj#b?k?IZ zxyeHh0yELrL!R#`A!I_Upw%qDNUW0gmrhMpdx9(_-{Kyi?$219uAD_Y7M+)z zqizuS`R0}QO{GWdGN`1P!-psCatnJjq8O^Qt*Jvv_C#o+Mbku~tWNDSBVwiaLf}v1 z5G99i^b$-;968iU%{hUbnVstXHP>wsf|@bK`pM1{m#=bKG*m~ofy&2#AN*w!L(5uV z&}&?K>NGure*z^e^+jkkZ@-ict2ommoFZHtOapg8m5LYa`kX{IZ*@0vrbUP015B@* zcogvlFJ%7J{V>|iPqeF;;%3}$bB$~-5lpAp(+1;8Z$yQLw%HE4cx6^zN=V6q4opEv z)5d`<7`yZH7##LY;u|&X8Zc-lUE#^*X4=!pL`*YZe;|y~)Y~xTpIVm~U(2A&6pO#@ zm&*b=;iOR_EvF#d=y&N`soGjD3G7uO`;G`@3uZKb8tnZ^nxsjOUm}wlFP0-EQx#xO zk|IkmQW%(GyC8^xa zo~<<>F7)|%SE8;B8~G%q5Z9cIex#*FVKLmh6BV&)6dZvmS$Mw#A6SpP)5^BN6Igu_ zL7~_3T7l@IAB@yC}Ccm(*VyYFaR7Y|e9L;Q_>6pf?i27>rB7c)-wuu3i}#~P;{`7?9#I!P zf49nIQRRaHa*qeRsFP5Ksu^Ttt_OopC<&p|PBY0XCQBFROoIXV&qs&xP_oUPq$Qt2 zA8hT1HT6#&>|M}IX#C*)o*cUrUhu@M7c+=Gr$vH?f@sJ;Xs**4=eME{ctG*+BA$ne`Z?~s# z95RP&H>sM2X)8F@^?}%$DjY%V0hCS0A=2X55d1%<%ca+W-w<`mUec-eI}BYkt?-sQ z>MVD5G_v*+tVSWnF*t|-?9z1uB(SnGE~I*iJupmnGWdQho=ni3A?fw0;fK(df58_D zJ@(C`eGSNXv#*TSa;k{uw_Z=_Rux1&;SYw3f2OV5iai zy&!vL*^DrQMyC~kc8Fbon)@&+Z47@vdd{~s^h!=tHWhPMJUxWKWo#mSe?FUG3)T);7^a7+ zXo|C09ql$KmnP7Sr_i zjy3UtVVsBglQ-Ex-j^87#g%(hNE!(SCfiTuy8z_ZmleVEG@>6^AuA+stZ<9{rM`YS znsFgHXi$!6ayIQmeM$-ZM8cI_NvM)cN&AxfS!fRj6C)3BTy?|q`>aMhH?K|epF^g=x-F6`~OrsM{3+iGoi=TBNa`8R+tb3M_+6{V< zWxqy{-!V2KQU}n0*flnDp4)OZHKetrc#lg)6G_M}gSRvKk^sR%0j>hk z*Bb}*S#z$dT;3>+`En)77hkfg-9!>s(B|SE_xS5)0*^AvuyA} z?+v(GDaD!5jht4}iN5M~64I6o*(fR<%ClBSCRaUkRlZEae{!bF^as6u`F``A^)%A$ zj&wA#LQpEmca0jEbNQRIE+;f<0lk|7qRlt4ZwPR?$W5LB;nz(sxC`-<@e%!&^MnL1 zEMc1tMr6w3Q&g$%yxIQoa0vCEJ4rGEkZM=wzV>&HC6V)o)NBJOoVNG=%v)ZHgiH@J z0(hY+EXlhif9AQCD!@st&<(U~LramjU}27QJ9KU`$$V57NZfYoy$pdmbqQf}p{nzJ zX-FB7T}dbvv}XF-%O;E!1WlExi%}N!v>II^JbVk;&Wmpb7kUTDaMaMz+2Er+es;Nk zOt1%zOi9nU@=qW{+9gcIE4v~+KZ#Zvix`a> zR$&7>gg&JMRxRx%dgRuX5Oa<=z?<5zZ#Q~#%tffp4|8tgIL0I0-xif*7UjskI5Ev- zS6GEvf5zp=qOaeh#eG{Kh!JA7Zt8>%iO#MMO5zw5cFA!t{mM136h8_`012^Uh>(C- ztqI>ESgD<97QLVvZ7>i23#K(IV#FBV2)65dEPg!#LJh301bglnW4!IOhrxmGM^I12 zqq5VH2JW}Vt*+*(`=G6#302V$YH6X2kX^8Ze-+fd;xG%_b8 ziz^f4xMa*1Oq5${2UGB^vIb9-D*gMq$%*H6)j39tI(#%(wWBOnb~z_i)AxRBSaHK4 zIg&9njIjlLP0{kj*X^@Wu$R>9q*9k5f9iGMXryPK_!m&wS7l!_=rnnVvgI*DO^k*J zTLf-Oth8URPfjWUqip^K!JVQ)TfYY9HTDEOZfRu;VMjKpL!mI&YWqgZECcYCpab_e-gif(z~QcBXI~LXI!4rb%hRx47&n%B7fEla75+{ z+J3LCwQ5!ELM|7=t`->JD1rA$y2gG~F5g!kggsIp>tz-NyK47DPO2+|XT-Li867Hu zB<#WW$_>v}mK@=eqo!ely=H9qnxJDwCd!Kgg%h1$u@!`xF3?(;A2$Kde+6%NAmyYK ze5C0OAeh^3YCpk3C?Wtq4<$}iM9X+{N zJQ2b3ke1K!?kFxo_Dhm$(BET!{aOQPSgt*j7*@Pb!EcYX3hkE}sY{uPMLb&a2J3#y zU#!v3Dq=6@I4_I%f2?>m5cxg=L1i9T>kHY44s;|&!NC=Bj zhyuf=u5Ec^SU%23=j&`+cS9lEwm_!`sOfqFC&^4Vf8M53FROzjJW&7M_T@2+V3JF6 z)t96yE}CGq;d>et0Q)7-?HN7-Iw~IdG)%6EgI~H>@>7%xe*jyA&hhF=yf4Q!X^RsV zJ&ZQLWpEUI(`jXEL0%ui94Z!dUn7V^%(Ki`kBNg<4fWhOA97G3N?@~kCvM7)It#ZH z+O`zS0omXVFkU7WN_OyUtU{-(YQ3BrhFk>GDY19~E?7jsioTJfY2)>?T2VJGD?6vz zI-m$m7b`{+fANy4e?nYgpBjIoJw*KGmDP*IlJ$f|dLRs;S+fMtyU7m_5L|?XKb>x_ z`eb4rDf67)o4(*XdS1J-WM(1aM$`)CW}9a4R>+n{lC(CpIf@m4x3Pz{`xC`Dy=Ayj zTY=93N<5=7m5zNZ09I>R*@#t(>+#R}%#uBhR<|7}f5d>ybFqmb2KSGx8l+`Mu6IwP zP;L;+wG2*ZK(k4vP;bX0JJ|d|sV`=pF?2 zz+UKtyiH2*7saH)F?~Oi_(}p9@;GgC%J(k)s`af8rNRs z4$h5df3vz+!JkUQq;)FB=!A}zz4++DVH^7K(XM29mm;7y!2s(iId|l3-zBd=aCOAm zf)9t9bMRl!tCUV#@=p?NQ>6Z`i~TZFmeUOgOMxrxMH z=%9P~!nu2{n5BD(XLloC9stYh-D&6CH#dOnF!B-NPO z_2oJOS*?_G;l7PAU}z)=FjJ!+;>$L(jB&KeaF6}qR|ysC*o@Cte58ML$QmMhB*!r7 zf3!Q1k?n+yNLO1KHO5mSe~b2m1B88YTx&53r@pH){b{Nb-^CmDrdTe0pkbUBkgb{# znJJaOXe>wL|1`{vrdPC%8X5Kr?+p8<-}X<<<`)FknclQI!|eD;S!0>wyEwk*qSM-Y zjJ$&SdL1<30K``M^L(G%az66u%M6TBe^nZ*9enNV3LSFk|8rFz-v`0IjDurlk{V-ck>@aq=aclI;* zPW+1$ijCiII_a{#{6`sOsuCc_LzucflFEi8boe5ckU6f+x)AqI=@VF7!IILDVWw}% zLmrSDS%DCN7kuiFZYaY9I+E3Uf8BY<(>1inv0rbDRYeMu<#!Vk$Z~w%=Xu)UpEV&x zu!Oux3!yGc_je=G<`nYdC*=^N2Hupw994m2-$6g3>9$we7;vH$Sxly`r(e(ymZlu#hrjs9yf?$Rrz}mf)vPL8;P-r(>4Ye}{QfyF#8L zrtfL4uYe(@nqL>6&^d1b{mkuLqxoV&7BR!-@HSU_BN%i90R~8)KjX2dh4^Qpx|*YyWmFC2kA~C1AK(e{%20@x?WTqcEvE zeqQ8ZK#Nn*p-u(H6vQleygSi+Et2=G zH7_?1-cdhG;@~z8lQdT+lVG!=g)&{MGRo_T@y3)apw)eAf#-k9Bl}HiS~|z9YeIgi zFK#DCTisV*f8|wU!MZ+tbo3NC?-`j3>4jMw^^jGTM@AG#F0#83cY3d z(P@-VFH#4cGE&g|BH!1QqcxV8QiX}#%TH~L&?*naQ>R@!C9m5xJ5X46I*lj)aJ! ztZ^giWC}=S)AentF{Bo?QV%t`r7%6Kl$=810p`j>9pNbV@nd ze-0Ifs%xwxM5Wdv21hL+>@cxBkpUyan`dG%m=Uj$q(xqHe~>Yz)z{v=Bl!o2J*BH_ zOJ7MxpHzMKPNkj)-!A-@sPVw9H;t;ytrRw45pb!hejhT*a)fMkLpF-vRL)0wj}7l8 z%@OgPaCSlO=ezp9ilPPlAN8)xCx?_8qKWEn3sw0AS zaUlXb%OaU-xNKKe;y#K<6K`)E_n)!AmIPR!8+5Fra-;*MwG#Fw&$U*PfQviHQ9O;;w7&T9$ya{Ck>490=0}*Wz=sGJe=K!D!dPeWwksV#VD$%Y2u>pkj2ysiBW1mlQuf7O zA7KNwcc`DjB+xAv$?jS`#cL^(&Ir)Yjv*X>g9!-KeDV)P{fW}Mk;@P`Ymy4DK!n;K zhcnYdsWDspC@v`8np0|EW~dVr@=Sp3b*99W3oUOsk+5xQKPB0Ocw1c^e|DjJ9;7E2 zifDHL-7OH|G{844R-`p_cYy`bOUN2L!7CEZu8qmK$a{CLB&3nlq&sH)2%Yw%V5!N@ znY`X@j?cmnNkSc&r#eiV->AxmkKmbq7*RGVoe_yW-XI9p^;vO^Id#R#!N|W<7|3UP zk;BDD*1hCPJhyvs^VPEwe>*PwCkbrx8T4}|^z`dd#9KA?%pU?8yX*P6-FRraxEz|M zm!oLT?6nfhz9qaFo$6+SU}QGek`Vly-|XBanAoC3CYdG@>$2Da#^G5~_l@!}_1IGb z97I}O%KL`f+eVkFjC{`UCina?7-sdfCsw5f%Wv40Z71JZ?${PSe{uU6VRRAaD-!RL z`In14*niTLLS?ge7D`* zkr~=+Z4&LFVs+@K20w!VSAU{}SG)wLX8{w~PFf+cww9RsOR2Fxl^7SY=-qz%xdD{! zz!lN8KSAjH{G$z>e+WvpGsSjuMaJ0i47Zv95-9!Ntdy}DS%n9V zVqy7j`VpSH`@){bxXTvuoz0&+(hlJC$efYDw%|KQU)AZze=NL(q68Is8T97V$Ca8F z`&3_4gSEDZ{&a;LnXiearbL2N9n23p8kq^oTT@KzrL{2vA{$8{cL7c(e%FAw2mpTMS9V}0_-M+QkQR5-<3o?v- zcS9pimk-P6e@9#}?)UQqQM}(%i1s&Ts*sJAh7{oDM zU#QZ_WaaW^vxyg+^YX3YZVr-rfxR#IwVRBxj56y(UV|ra!3xED*Km0E>^x{|&rPIy z__Yr+0)r5DQD$(MK3r%&gflLG9xZ47EY6+N*hl}~e{8hrpl+OMHMQ)ON&|5eX_ljM zsXnu(yXi(o98ko5gFtgU?sb$tdkCjr1mc9*P#v@Dq|D_jL+SoajqI8goxuJHCw^9S z^bGYv^}U^lgjHoIhDTW;^G=aG2nMI6QOL^Y}%Z_V~44dn?IInl1PPTlWIc#^E zS$O?(e<*lelV-@P#f^AnV1`J4q}Pxj!o7vuLg~;a`pZx$#-d?;_XNs8+1{`l3-zJLrhB1%GSmN8jRvC<%V1eF9oFRm!r(!a<6sEaQIQ4Rk<4 z#CQ;KrE-%PrX+WU*B}ixH$(Iyw^XY>lk9F?-n^kn0@=re_?SH)U(1LC6DzIpb z`G3WZew=yzC9{UK=2#=Zi{>f4i_Yozvl3DH+9;f3idL02n)e}8XR`f^oXr%dr7bBj ze@y|tUsxbZnKU2I0i8vUN4c;U(f2%C?)$+enW=5?Bhe)FhI(-Zja>Tw>l^)B@gwN^ z&q9WyIZn(5_Ty@&h1#^o&vZeT?o+gZb*@subSEj2y5dbJl)&IdvtWZG0NNmX`$3GIUIT1Gp9wb`E*Z${qhi*d%OIv@Q$1V1frN$boi>8 zGSnk>Jm>e&!x-?>+bgDU?I9?7_VuZ9o<$Z!ea#mlVEkv~g9(J)q;LF!Ztug+e`Su% zd^TMvP`W5-aG`2tv@BA%J&49vnU0~*-HZ9*tsm5%zDsy2=Q*({)9hsACmJawdzJgL zOw|zf?Z8Zb3#d5EZV;ydxR@^dWP`OxsL5O7-R(w{@7>;7XeZr`@R6|a91DgcuU{iY zgLDNq{he4U>}&F#zi)&+1aetHe~fK=%&P6023Tq{pqW7?sy-t{_qi*2PqNFa$EV4! zZo;*-vy;Uey~~;59JOEz>il^KomD>aMz>w6bL|pNJgT8*;hcVHEx)8Ue2;UG>tk5U zAGN#USBNp8|wscS=Dv>#p@Ad%UdC!0k7gKl)gyP?L%{Gxw(9bYv)r z7|HcCk0^O^Cfo6f{CdcQvWm*64jh=uTD&OIVr#oRaD?ZPG1(CABFrdZR<|hBPXmma zgHY1fr?mztjwu`Mwwscne?J4GQfp}_1g?a}{UQ=O?Uv~iuEO4NBA{EO~Ee+5k3(TK}So~*vV z;lIV)jT#ahFmf-)Qd5kUt0b2Ch>Bah4A+5d=;A-$^{?V}c(!R{4NWOuI+Myj@77>x zAinEGdSSSW;X^v%40b-HEQ`64fNXDaf=X&bje%-gG+$2|-aHF7cJ~l^;VqmbR|yaL z`iPdeFJJO&HN6&c06Y&*kDRpz%mOpmM5Vm79^=!@h=kEv=n7S37OHf76J_SL+Qn0JQcSPoC02 z7+G>PdnXe5}}VB{-201?lz@g^T0ftIRxcPL0ft*gew z!rW37Ql9Nlbj8~(g|fLI>hM6E`NoFCI{T?IgyyiUpZ%NvUfH{Nn(iU@^C~`BmUJ8U zUfoD@9|;-|e}0zU{(>5$0s>D#OJoc?=~!x!mOUG5A8E;3KAOYAu#4SLUr@!;Y+OQI z6@NSv>_eUJzlyQwtnz`p?a%ov^aRbeA9#K?DQF;nf;bxROOs;zF!0YSF_q?u+CV|^QHJJ!(C9%Gy%?g5>Oh#{@UhYjo zk>nL8U?oQr=%eX5-1(@MUCL@K6x?GU2NOcVzrYMnYeAdcw<9xf$+qYqvDG7}a&{A` z5aNX8$Qc9gwC>GIaBZx(MUw7UQrSbRKZ^W0B?$o$d^7O^Ft|p2 zeTXzI)Ukt+qR3=fO3ObwYToKkYEUN{9~%Acz>J8JXuK7y!l3z?(nKJl^VAYFf4&jH z&Oh)A!7f?H&wh%*EQuz@ zRB=xQDlhqwNmz1OEdu0Fh&g4=0AvEvDn}3A+eR%+Ha7ClH_Nf&LF4m7!MNXilG)stg8+P!WKrtFMSRu4#`pO}%4yIzh;c39#= zwHB_#SfrM!V^K225ey1_e~(pSS>*Bs zz*!2x2$~0#`NTFJ27pb@rB?J@ZB4_%_Yf3yKG;mvCHg%`V86->wdx}ukt%uBnTN7* zK+A|&V{(sGtd`i5@s^>L(8+N~Py~6O;ib7#sFHdGjZ+GsQhc#>7I(OX&|ZJYX(D?c zTT5GOkuxbDv!aI}etjpEe_S2;^<5!lZN@%E9w0ZoOtfh$mAY|Z15x$LQJqi+Vx7yb zd2d%1k0uDD5XurPWf#lhV_)A%c5wZkeogGjs}U&4H|AJFj?Y~SQ7;ZGW;=55N(f=a z1kf^@T;pibYd56{DCE{}R`E<0*w3Dmmc?Wc6QKsG)6IISWByrqf9JOCX^`HLse5wy z$=`TG19BD|k;*{KSnf>jD_h9hUQR7N)jJnFNbIFWkJF7KwpLmJ#~)v7vw5~~8viz) z@;-~sH1brui6|a6kj^wDNHhoW(`s_xFS34%zLuJO;vtJWFo^Pv7DziXzFX%1Ek5K| zAZAZpK*Jt$d}6u>f0~A~)>k5vPwW`_vQ6BZTcuBgodhwXFE&3wc}nzJt$;EO*tU8w?gT)KaoCNU@b^2iwr~~i6)1tel4&--a zgjc@sXL6IEJ+CgTQGCV=sR|P9^5EwRz0VMwU9~2Y8AT20e|X>OI@QY%yu`JZFYngH z&e9WPDl1uThxMb41~D^Q|1ie*34ab>jAZ}#oSbGS6X`;iN}Yh3@_3lJxi~XQeC#wA#Jwze7m%9pttFNBFu4;>s;aq z+J6h0aVqdHs&NF035-Lbs+GBIvGd($doy7j2pW)Ze-MjIHvt4CwivQ&jS)03FT|^;9Y4xrX5XjA{~ZJK&E6hU+((n5?UnPV z<%OL=e)))f^Tao44g?+((|1YLx7 zFAlj=`z75(3M(tWJTuLqkx^0>Ix=9QI;R}me^aK>m@+>-&kxmt5=~klqk-5U?ao)J zxTwN`I@g>`UoY7Fs{d}^=0q$q1lIMyMJVz-Zrbfi8wqm*?Bc9~*x-+#7aRl|rCl>^ zA&u$pPbjx-?+Yii#0)q$SEdhsH`y;UZLF`AFM*)}vw{9Uya~bc@g11MUUF$V;x)~y ze;Y2yPa$T~>R0z5h?U3b=fk(c(!uZuTzYm=6wnhsJ9#9qE3eXL|Bko~5HmURI}j|x zk~E3M+4`&k4>FFrsXI!==>HM++|=YZ3Pr{(gMh_Fa>AGjWhPy$RTd*+1A?;4fQu`B zaVe=T#epoF^O8BCufBZ=!Qz*e-EpdF?_$|&G4 z`c+r$LY2;R9l*%TgwytmfC~Bt*;!MHe+CsX^D$A`{w;DkywS;2B?z5&U_-t95MrLI zPX6vU6e=_JwV7L0Sd2e-5a+lln= z)qo|1c_YqZ8|8}$ZID!yI_7M?f0t9Wr-4S(ggublH=|*wR#?7;KGW{*?~grC9W>|l ziU@K|HV@zCrYg3dRmN@W+|*IwL&wN2^~IfssA}fy3u1?UVq_WKS^fDd_8BS@dE2S| z3h^fKy!BVq8J%j$^-+%qC4RdxVFL{@?Yx%mo%T_8zNHS6mFZwB-99`!f2DI>4akkjkwa{N!I@t_XG(0bKlm? zy7Pm#395WitO7eVOvbj7iD_~2g%epTC>YjC#hgE4K|+DNwLGM1fnn7)!q5R4DY3nM z#3NU%wM;%}r9af6LdzT)f5rNw@=3g?|50)(tU6Fi`R>(6FpRw)JzSm|N8%WxH;nSiL_*Q?n_8TJI~e`v7~j=Njy!|z60 z+MHWwY;pai;+^!zl%)EBD-*3UvWvzk0g!fjYV^eBdq8_3R3fJI3Dul1lO<-Viof;5 z!)%wrFe%bmoXrOOFm7TMQn=^_x3+7;o`6iQ{R_}v{jLp zBaxDt9Yy?U7d=rzf0+7wi7i%Y$cEX%(SMvH#*Kd@rrjP@=cNlQ!x*=52m^o(NkLwrQSod|FNp%Q066^6Hc}%X= z7>Ej+)dAv@7Oij#G(*+zJtv|bXfsF!ONXY7)i4VH)>Zq(w^T6*Lyc4SuoSdSLRElT z2|s9wvj7_(fDz?H;Of5I=v&yHzE|qf#jrqeMsguagD&LWy#Hx!xn3O{69pGeeee%V zykOk;p08fT+LhMEXlv9x6ljstiYjoC0#oW-OPt8}`Z{PczF(}~vs6Ty(jDUQA<5^# zD7FZU*CG=`kIJ3S!b#8^IHe(sHy8PB`Sn(_+LS&52?IC3& zvA)um?8Ts0)Qyg3@U5)R&_StT^oNBildy8;2p&plM88@Hk^Lv=kTOyxIy&;)tx4c7 zUm}TJ!WUw*jy6}aU6v}`F57|}dbSd{0Ou6{>P_ALM8h5iX$O z%{@ggmodRi^`^HSixQidA!Es!GH#m?PJ6v`5wEN$KnzwkvCL*LkwojO1ItVs(54SG zlMgcl$MLd~RA=rS<+Cx{N)Zwg--5B?9$Q$_iP68=Lx5_aS>TDfs>UOqMGB)%)pWWy zqXd@+(C5|dmHH;iw&4EZs-Cov4^kxJ8cuN~-qXig`5Nn*mNF(#zho2GNx09_KN#_} zp=7@9m1bVpV`v9x=^}Rd5lfAWp{N1mTl3X_+;cO~btDb2MS{q6%Tk-|Umch_W>%aF zo&AkvWwLL`rF2x`j-4~2RLy3-c>Ttnpb|v3_g^yf2pNSCH#B0__qp*^ydhUjQr;n; zqB0EeW*&u}I3|o;ryyUSt%D2Bd1%qBpH!6otn6l35U0}BGwg1VPrwisG%`?3L-yMr zkHOC(U~%^oscn<#^LePjF})jaX$y97zX0A<_gc%zj?I}%3F6Wup5A{pfKZM3P%Iw^ zp-r$MnyFDm@&pa=_NfCcIsLIweR1jDnP%A%A6)EbQ#7Q3_QyQ`^_8i?AHyOAWjW*8 zLjp;JROBU(9C(PFt(1Z)RqNkUN!J}tB9ay1)e zdx!F)$RK*8c5(d&qYd|eg5a>RvBNUS{!hORD={lOE6@La zu@NV{@xel}u`#p!x7$VuhCA^MclsB*;y$@&PJS?U12##bO>7g2MWxXp-kk}iDThXW zfUtACgS8rpv}i;krZk20FLdG6gv3e>-iFKgZO=)vbWjS-= z9{RT|lmu4LcUfZZ1BxCax#7F2+CVUt?;ZPV1cWkYJAXtc)l6a`x9V-^8T5#2SEpWAlrz4@*)nc`zuQxmwHc3 zDgwd+1_CPz4r-PO?vK_t3mOW4%O5Lg#1`}^N{Et=@(~312F->=!0lxNT$o2e~NdP!S@B22tqNht>~$WW7~*9zNDO($T6i* zeSUs%ZDMJE;*B2_yes5?HIU+`h-=mMV}X7dP|cB~>!TP<7Wq{IV2}P0&}ZM`Nfq5b>e~myk z+8Y3Q)H?!ky|IwEU>@I~63CoD{aZ8befx}i57i9yA&xbsD=^7PtRAj~DByFC+KE5n z;|EOY0#h1lRSX2S4}#brdy!)ytlTHbZDO_nj@PMu6GxM7TRQ?xy>?4-A6bWg*MOu~ zAD1G@lu8AujxdvlPq=TW#k@;CqI#(vD8~Rv4E()2R&u&N{q`>hGoHa7EvibNs*`(( zW^k-cGd;y0*Zs^RptmAiH;eCeSqPeE&i)~udL~}AEUR7($7d9$u>;9-KLQiYH|ro^ zAVowX6V2~+?jk$HFx4jTaK|s$SIGFz1S!gP1!ao_J;H}vRJz(q$-tb8X_4S1p;v(z z6Zq7kdo^6@)we}(gmi(VC0I79zac}Hq7uCyt4-C#oH+qCD)&O>JKgEFp|F>acB5%3 z+=+bMb}9E1R2)=F?rgI5B7ZSIOv6-T0^SlBIlJDgnhU37^k{n~hnUiqo!)aZ{~@AL zR*b{icXHBoQ{}s2-4M81@^#D(XH|hwWl=EIxdT`*GeezO7zy`Rp&$Nfq`87S`tI+S_#iA zepQ0^6iTz*mfZOR+8#5;m7IspNFj#@8{NldK7Q1Y1Hvg(LqLTh%Ic(Jh&=%Nyzl?W zvYS+3vM6n)Bok7{7DQw#tt%ml%o#cS7#)(eeK){bUoLPIf!q8REJkglpKceKdb5)4 zzpd7C`YF2)=coe4c6DiqVBOCug_f{ikZ|*mu;dMHRX9pztq_Ch{7|+*I}C0f zB_O8t`E0Z9A{wuLFY&(D`8g%b`>QdxA(_c-QAMxubgQ_LTPtoS#S}0Kdf0mCoi~cB;YxKKEfVu3bxP)3z?K06v z-w|Z4Q1iWC=Z@OXxPbVx-N)@`jVOqlUPng0__K8fR*qzyibWlPPQzQLJkrz7{OJ$u ztM#=!f}o@j83h)H3Nj$ZmZ3}a@9=$zY#<*2p+w2PHp z=t7|8=;za7e*B))$pfal0jA2C7F^a+6!_9ylWVb$og_S?}mG$5(5AML(czQ7%?EIvTQZ={>`S7y|&Py374 z?k-i@AS~a$%eL8$|_gB_xRi0RrV*HPNbmxOjg}wv2$t9Z0Q4;Ile=Y)om`6 zkM1zigxVXb9s@j4IVQJ#dK{hg-9P(Z?;Ag8QX5j1s+6T-$ZTVgPBNAfYSUbX_Y}25 z3>u3^FYCLjzs=d=+-&RtINexO-nLm2?-0pMq$zfMClv>I-;+CaW1^y!G{D7gF7XvfXtOu{9$Xpu6Ug1^+ z;mdiMzGD%&F{bXz`~03(O9OrC+r*JSs(BAKCqoD$V_W6IQ z)e`iaA4n2==rKPpQsPTw$g&G_Z^7j#Hi%09{V?x6j+3%RMC7F5TdwzY;2b?j$ToKg z&z6vm2LeO&f|TSt%fHbpZ*=E3YS17J#d0(9D`9C%^K6S z=|EsgXb;JlhHQP~3U$mJW`C2xGc@Ck*%G8`G6OE;0}HOsNC(A{a%ixI*2%PmCEaDz z?e3zc*OB-ecr&qnqSgFBupLoLI&FP1b7WvDNcq`bU0=j7tlYd8_Ldw>czzZt`Es3j zH{{M(ABL0GpfNaB4+~AiX&RShFJIjr?$?!ky~iP{OVG<1qjDv1qfC;MV^Pb+VdTXG zwFuzdPL`qn9zqO?=jGOyv~;f0E-0@~OMPzcqu>^_vQu73NLL#_fvh;*X_4L#^|*Rw zC(u6&mtnFJ`Y5U^6n{(D-K&Z>YZV~oq&*=edCGz- zqXC9J zC}Stn(_$n~E>|>@F}HV}_vj%uD;Yg_b@`SvZV_jg-rj8Ksn#RC6a8`;QE9VWI|~F9 z5tt|PGmFWJW*i#r;879usHY9urdmdnv{Nph({N$fIpJ)wEP9budcE9PzOLSuelzO` z?5BSK&%|G4{di*C{df>_WX1cZ?xc7PuSk)wd1dP&-+z^TxR7%p;>w}mvRrv09OXUQ z*eLmBY45H}!%s$?Rc1mA7oWhMa`Xg3Qck5G;#%VAi!ej;+J ze^4qoci?$tIA{#~#4nGGT7OWW(U=xl4o&e@u(j!_blTS>2x!H;KRo7F_wZlb)>}Nl zp)zEz+AX_}lZ2K`d3p1`kkJ3;cBM ze7KN^sLkBi7^i@mQ)r68*U6TmAwfFVuOjA`)*?s&$=KC;ws=OCTj2HD>KI1rW2w5$ zC{{sz_nPHh&BO*xx@*0PS{9UQ=tL>P5D0f`l{0 z=}oIqCjWA~F*w6T!7b*uB+2PbE6dXqKQcUYe!f26KM2+*sj~WIHUcXM-g*Q{YQl1z z<4{-BV|gh(Foe~OINvq>Vj3%F{akkWjAp-e^hUV!Ko=JFY7b?f&j+W4ElxVAx{q(t z)W*6YdDCHe2eyB{b2ug*$sB$0;HV0fveVwt4?ArieNMq=msJk$%|E7p;8f7Ba!R0y zuIbv8eBoh0IDGpzO>r1IIysma*!4aW?d)63&$S$$eHu_tk6lQ_S`o|MbVk^ap+LYqsFwqxFvI ziUu`u1{(dfvTrCiDH!43o6?|RBX|UhZ}4I6!hjzcd2rbuXjE|CKoC+;=J(XgWIj6*IyQ z1w|9)Z?`H{Do7)z7WH2l5WGWudW$}4n7+N>2+(LsbT1J{WCQZheGpZ4RPcyDrZBnv zhM@r2J{bPEv1TU5^qxMMI#e8ouh9~4H2 zKG(`ym{C#Ri9s-HfrUt08}T|5;?3Swu9@>3wlo-C7Y@CT zBkbs9Acmpn;(r@b*oK1@?Xd&$z6zkBp$+g?Y~>*iD@vFWCHn$6L>=CrB=2L9)rqs) z1BtFNUScHw4%+vC>a-d-3vxpTHQk?PZu>s4Zn;ZxCd39XiGlz z9X8LaF%r1I!L<7d*K5d~cGEfOs`vryNB$2aQgx;_Z6mfLN%xnFSd@Z(x%*x=n*eC0 z<*xiN=!r{88gAo~lz)4X4eAK=vGj)BGy#kfC@^nlFuJ2;=lL~Z@BQX1|2SS2it5~h zqaryGTg!p~y!3D7DsS^XT;i1}x0XoI@HtnkhkD#xAits+8*Jr--1D|vxDNq(l16WB zroovDZ>+H2RgNul9}odLZMq6fM~NaRDbZFTjg3xwvdlc~%ehHJ#yDJe`=3Se-Tl+a z8qDJf;9d_x26T3nXCidOpv&4Kd4AJf z&FLZDP|8~WN*SV+^EnCrCfE0h@GCo}m4wzH4)u-4qwg}AM{;r+6=8rpaa1{Pv7=4j z+)tgOHtWbGc01Md^y(jy_wy}f-k77_cM?+q^U*pe1sEhmUoV^DOd~^FBMT4tA^qvJ zUvHa4F!8MQh0$l6-9LZjAG5glSKF)F6W0m5q6KNv$;{_Y<@Y$adWMZxCa@oEt>Fy8 z&&FxBla*)+BCTe%-CF?q&o(Kx>OBfA15ThzS)|g5oeUM73OP>^bUUM*4fAzCOd$`{YCzoFT>96J8II|d*)fm3~NR7Y9ac%dV3u+Xf&HA(HQlcrKs z*re`e0ytDRdqQ0zR%y-LOrBY~EX{~I1W!fslFhS>A=8#KOH2WwXewwEll^Jlx?Ec7 z6oI7O+q{xKQ;gkbgJF^i27zD-De?T^1$-?o$1Zo37*4jw&&#aB%oWwt1uM;lxl4OIm`24u$*Nd4j{Ze@)J z)b+X1$iDeDiSD#XH``!6geo)QI}@dPvld-`Icw#si&%I}lp6eE9GIs-8Ca*AB@Oa~PUBkEiCf8y_vGuCBW;lE@MvJD@Q9vc#wQ@&#H-zw9o&0HQ9#M1h1JNk5reJ{ z-A3R{yI`fRJc-SWu!O(NHNH&Uv$S#%-^S@MvnpnQcT9<~1R=+9p%m9-D*6OCu@fW+ zQq!x(PCY2EnWsD*BLe&!72 z84%$-bkOKu=>8k+02--hfRMtfn}lMY7K<`_*;fNvv%jeP^o3@u{73>d8Jo}MqJZfa z6K#Xmx~I23wCj`&w@mAM8>F|>`a?@d(Gx=fa#s2P`mHs-YEGbvwM=-~kTidH>>ZIU zoEBDr_eC3R&M)Nrn}a2og!^gCBYwKG41l0)X|2XRhPTF&Ri$o1pz&|JSlgY_w$AWk zswkNq?E=+Z!#NTtS@BM%Hf%PIY`MEMy;pLr<2wcS`!-sqbFs+~Sn}Aw!s)7AxR3A-|D-v}A7#$s#6>9T zHa~{RqN7*U4yXug+|!Mi7BR4N|TK3j_O?W5t#r*Oa^Y&L|=1UOF;th6v5#XMBt;>q{GJ z%nnY#=t~UwlR8N{4k@+2RyA6d4Oah$Fsr07d>?FNfM3sD!GL|NWz(?Y=bj0L@HYrD z2&i~}{b>2Glvek;KSC~BV90P5BL?U*8A>#$&^P3W7KGt`emfu>#vqw_Fmv+hDFA7u zIibF<8Hs$p(Tu;y5+N)E{k|;ubitSJ{tw)cSuk?nKOpf#G;9V`zVA@%#1MTB@MFw* z*kJQ)oqzW5M`1x!7KhD)-C)IKYnKnD(4ithO;F)&Ie%!{46bp4^CC>@F(x7LNa>1b66aAtZhV8s4uaad zX3B*bQ6xu*^Nn5wmHHX$AWAh(SVI$w*hY^=^h(OHHh;A#B>k+_p4z2|g=8e)@ z8=#~-P_Hs{`slDe`7E54b{J1f&+Ky+qJ8S*seRJ1FiAN5?5V`Etq)jkVq3$r6rk=& zm#e*-FVooCEufgzc@#h;ocV0FwkXq5l(>CM(>dB(*TxJP#cI|QU=uPpnewa4mXq-3 zS+4fn)xJ8QXk(JSG6ATJ_cFd-dI!qQ=(0ARE?QT2-r_EFYqrCbsLswTFC%$8yrus< zA`QKW8Ya}k*~+g|t8eeO_u%3+*Z}%2e;viv6eE1Rr&WyU0nN8Hl^%>L4A*M=94w^6 zN}r|TPYL+n!3r%G^^4{Vc3G+0fA75)HrqSX;}merbv{J<_r4G}V@T z>FJv6wJbzCXS5^DTK4^A@sS~^qB-iZMK0Un>zHsc{9JC@PQ6s~X>~I;Kb4w^fyCC^ znL*5{m%PQqLJDKwWX-t&c-j!-`ctl-zi0zUWYiow_0WPaeLU02v@K4buEka+? z+AQ%_bRCRG59Gj95OYSGx>hpY$(M0g+uAN}0O^TOMVHq5H&eV1=XOY8!;n+bwA{+d zu4ft75l<=I>>T_1(HDF242G3vQRPI9=oPdvoolw2%2kW#J-=y%>$%wP|LPx{2M5z0 zC7A4tPNUl<4e7a$m3De(+WJ_oz2bXkzQL~=To`7tsMpAu-!90eTKk$9ZI-|tg$un) z0`9riPXj}LPA8E9Y4p76o$G8{jQ<*nENux-zv!He^L3r6l^3;N;gJnAY_>j(7_lKNCzQ0mO%}E~cA7hAI5D1)nFK~{6ltnN_76~VSg_7*$? z0eoL^dE(lt);P3StXxob$WU-OkjhE`1e1`EkQ~+*du3`9)cBvAJy%s}HaD-J;HzYx z3C*|e4Y1r2Aoy|E3^Mjagq6#&G6iLRc2BqqT$I8>fMwGAg0RJMAQKlCR#FsDL*^#` zQU;d`A%pI*60i|2Qu*o5#$Wu2cgv0Qku~#;$iI`M*R&yV1wdc z_)_M&a^+^g%v>^I2>d}j)(3ZR^7?}I#Rok^6mOQl60ipY|K3cwG*t|Mx}{|JeL)!? zf%vr4x-WM@D?#z`@}zV7o@atwX(SC&eEH3f_Klp>Y((d}a)4Mr+FHPJ{{E~e>~X#_ z*lLm&C)SeiMVpyCsnH(#?n?uV%ucP1d68(;350Z|@ld1_$ zK(O84Is93{_f?5@ynZ^tetuo4o4!BA zz1!tJZwp`d1Z{l@IeaA*d^Hbz^}M~;f*jMtVM* z;a-2&V-)8kwtD(XneWlG0{QY&MYpzjt>ML?DtJl`T}khm@0%ETMp)^Y2jcx1;+VdWv!eQX)U)+ zbl*wfh;BUcvdcJH|d`>@YvmrsWgUZEX9`#as`6bhwl*uo0uLkVx@^)>~&jkE% z8FbczyY-^$)e)r0!{avzo>uu0`H;|A!*JOXeXi?bY~dQxQCC&g9`9?`7N~2?F5rG# zk!Yjs)bT0%ItUQ`is2v?m^#{DHfZEYTXf|b?kPRS66i;fYp&xV&fK1Tj&Iw4F^t<@ z%k#(}Umo(Zl&A>#Q#vKYTO29W+EH{$goBHJ-0pj^N|HMs{-f|OTi=a5KdF?x1D8{4 zHJf{ox6@92z)!s2&GX4R=thxjHs*3l%oXZI4^n2Q1r@-I@y5G~io2&tL2T(|4Hk{1 zqZaw+VB6_mv#3M?Sta0$i8Qo*g*_g1MWSitvZEA=Dm6B)ORLa=(G;=RQeC6@_SE#0 z`ObEtR^(goG_%nD#)^?dH%zSqxje@6BDSX^wICdB$%QxwU$rM9iMv>UySzc;T=&Q4 z9@qOUwk=ThvmudaXV)=N)O+2Z?GhqMK~fsC#tU(Jj_Xv&s((m?W`+mbzHiy<_qK&N zdjTD1r2Fq+I6JAkoaK6V9NH43WO|g%ID5(;GI#1_9ad85%ZCT>6?R|{c5t9>kw!?d zfsR3Jw@xKFdK5z8pyTQv2)3y?3E2dO#*YyHCUSOV7NRTUcV`6FQ;fd^BTE4lQ@|KdJCA4FJz`A{)sL?`z#|p z2aN|z=Y_-;^rGbIvVAgU6I|?0YY_iNG-Y-rv11G$MHtd6rLZtBd|1>ZyMaHst)taW zjATJyp=X@9Etm%TuUM^fFt&1=d0sdAz~w!a6L=FW|4l>DYO)=o2s-C$RvaSNWhPe6 z@Nq*i_Z5o{l2ix)=POIO{*1?spW`GxaD*45h#Fc5*}6$F>b*P}rh9il2JsfYv( z=i%PGQnmwb8we}5B+4jWT*wI|z0DOkpPF+;KX|Q~cw?Go?rxau*1KADURTZ_i*9rUjqC4>YIqTXjrL*m7Foq)JH9x;UEN7CvVHL#AB??w}tvxvi_Ili2;|g%Ng*=U(tvL)sP4R8sDufU(0|xnU@NCs=zhStv?v2(;K8YM?twkvV zjEgA0loAa#xhh9C^$0TH_Sh(*b=U;fIN+UTEzV?gDrTsl`gU{TV3^1JcMP zuQ6afo8u^j9@zS^e+m+K|4LP+m9|i7*qL@Q#U<;8qJ1>xzlOLPFYCD(q;tR93( zPt~(o3o#|*#f9qP?Ft%xAiVJY9S8_Xkxl8pwnoMSEY*X1`^CXcxB4N5kwV2KogMjo z62iMD8Jh;M)@wa4%grJSjKbCTG0nWMBzAXNdSv(`2!i5x$L3DoX_zY5C0gfqbjxD@ z=wiZjYU_+gkq2ph$4Ub@*jV+vMN|Fu4U@j?-IuS+r~W+~`*T1zTXeR(M@l;XSIB3}BS}rS zUSxN_a;00fYp;iS!f1iAd`h);&-+k@^KSXenjs!Jpg(8Bzuk4x;H+!2FA?!bJQ|Vd zdXZ>}_plZalGg;t$EYi=A(ln;z}1bwwlD{!PSV2{c;WLk_sR!BD|?hlXfMIQF? zmT({2&u6%}QV;|;*W&#OJ}(i^8c&NLnv)Ti(# z3pU}_eOb@#3Z!fn^+`CRo@>k58F{gz%9r7gznbev%vFhvrsnwX+MKQ2fnjv*59!El zcPX>Z)zVgrB%pe>UBL-#oBAt$A^gkLDDA*I0eKD_dQx|i8{!kl5&lI^oeP6Zh0wYR zH&xii5h#!d*`OK;S$v`ac`l2F-WQF-01dY1hEV$_Mg@OTX9G%=lxqb=F|@(^TrsnE z)WUupfoAai>Ogax27#o+b#(ca1*zN?<&G73MlgPB)X zPzriNZ{thDqO+Xq5-U$X9Z?N;V$ff$;f!QbdYNm!LGzXgD>iS}i<@;B456nA)l4|f zNaVw*vmREhbL2>ZxEq6*YxVEiU51prt5EwsG#BF^#<)Zb9&yXXK=-^>5K8O*Bw<*}yXQB&ID zM5jHEt!*?VwP__7j+dXAad}t zh5SPzFIgTyZTC(=-A%o+4o&9lesAre*-rz<*c51>4Q_E$CZObkm<+XCU@QknYm>XwS@G!j%@b-Yc z@?PbU`iAj&Aw@EErJ~ouE|nix%qT(P-1%0?>Vvhf^)Rtd;}MFlW^PU$YO`YKF9`Mb zsXI%afu0pH5;1IrcC25+39DD z(*uYs?3c%nYrU*dgb+WIX+Ro8dbBi}9j$S_>ZM7}n96#fSf?|GuZu^ji3=O}W|YN& z3S(BAI`mSg@$)xk?ie7q2vrlYLL;$eCqglMfZrj43tk5<>&Ii#VtAyC?6#F z!vgUsplc*Op8j<_1Oy#0l7@)+Myf<-h>a%^x4pbrTEx}(M|;IQ=YL-yK4b40@6!5* z(&TIAP(_>iNXB13i^AO04EINzKmKNbl4qJrsyqAu^-!^1cE(1NliMLG9&oUKqyy7F z+hFK*Q+kQPnzs2(!oyHk#xnV8_y==Dg3}NR`3#15_07@d9WdO^+4@*PZ#Y&Y!dfo$ zKFmH^+y(CnxyVW6ID14NGYc%Nd!o**185&f{iloAmhC7rWE@8Je?tR33OGF4?Zkqz ziNJRPTg@KXQC3_}EdpoD|I$Gl&~Gk+X@=ywS+wQ<*;>ywlD(aI;!V=o$5T|HSJhyz z{+yHIvmvnL0+cu;V>rXqjQAOes>nl)P(e{>>1bx6t|ed}Yz*=ex>iyddOJpZiM208 zI!r^5lA{YO$_}#ky(_Skc*EbKVJ4l+(8SF)!byiUBD^ajfp@yVCX)zh~34j4xZcOdYf8?Y7CXiwPR0b02YTUZLX@w|DsBAoly&Q3;vGg zohe4sEpUsZ-Z%9b5_A$yTLqF4D(zuraOvgWAqq{g%4FzGV|8xR1P!c- zLO7`_NSio*=1fBsv*+5ux+S6Bq~+#r?PpcXV!vqXgp*{v-k$}v72X!Zql9sMwV2NQ`0PK}TV z$$+R0p1-PDLhCewWAB%7my#oB)S3uCocuwIG+3(U#!AFl814g!NERkLSk6h0ieqWx=yBgO6;IElKSgq(Lw5cr!&Nc ztfoW|6^<)A=f8t=cc{mL9nxqVZ@Q(U4J*!^RB=4@S}K0-mK+CaI?6i9%K?f`r!&qo z%j?fzsPgns%R#WKRVklQr}6B!nYFtT$9G5FOC5=n;uq4CWp)^PacMs+5g0*}cNgop z0L1eIDjM5Yso`narUtv`yrh6?pGy;r^R<%pbz2WOP_iNBpq6>S3rzuuPaKWy<)>X5 z$~%#}9Tr5td)0u}G4Hjjo(`Gez3<-jiP(_1z3YmVXR#-l;SBw?3-Vv38(i$2bD1lr zjoJmf4HW`Z?s)2`>r*=31+2P+n#rRBxe*$ znY*?W6q4D;f+XlMIGTh@cehe6N%?pA#;BCt`E@Jxaf?ciUB zx_W6K!zH}1m?8(nd9HbLgn05Nz# znE1I>00o>SD?KRHp*uz&X$E`oc_EL$;-PU;kLdwdzT;j?&=Hht<$W8|&Ev*r|(FozhxSGZ(8iYa4al2Hs z=AFgH0rXGw9>q~D;Bb5wFlULIQf;RCF^$+ty>~&`)!p&^;cr1|!fowQz=A0hS`Jq_ zES+X|G#`UpO-{s}%FmBJX?T0Z{ihAhkmXwOlQg4u?-GgHNVHD!!Dh22(ImPdVg7gT zVw-i9CpUwEAf^%iKH5rE0x=|?p`1AFA20TBr+;R*$=J5x%ide)0QPH2B&uUN^Hn(g z*mCXs2s)7;jG?#R>t%G{)EAot%{Lbn#B?V_=R<035HTuO{U+J#u5h!an z7)tNUxdjT2hCFZH382#PcqjV?#?6K<`{rXVO@=ua@)+iAx6g3VNci+$a?&wpk^n1M%ic(BRnEAr6isHv+%^=YlYhaunGCXx63C3A<3e zAcxC;p2A-I1lZ)^^AH!fU*onm4Dp9MmUHu!aZW3$@#Nw}QwYn@9N8~>a3J-22OTJ) zHg&5)8juEcw!Y!mvZ{z0N>CaSy3`e@{VY6{?oehw!2LjLpYS$SV=O_2SeWx0x~gZo z;5@=lYBEC`xJ2o6iKA&!cY8%^`xG)->%p(&@Nh*x0a(Lt>aROl54HlT70ZZTu~o?A zk1E8>!QMSm&Yf@xuf&CxO2)&gpjiZ)AWT41-}6HkSp@c_(i1ma!@Y zDFU1HrF5~Gm5Mo%ynU+%5$I9my^8wVr?u?t3vHVuij`_)`W60QMn{>QYC%f)L9i2( z-_w@N08S#`IGyQ2rVw;;%VUU>kpN26q66Yd=;tZ;H5dt=^Of^zkv*?b7`Ku6o8RV} z)L$e#9v9N5jOu2cqhzLM;5nE{B7F^5>}VzBfnzb~Lrdf&<>; z9VQGT(_%wSPRI+%H2Syri~HD<-%fZW8LVnKds{H^5q!@KA1XZY%Q$iYgRc+2qNI`} zQNQkt9?xrTen8&MNc^5QMD9R;sg0~I@P>Eo&3-a{uz2Pvq!fVAI8o`R7O)jle9v*SFs5nEuG{@R_-AvB;DSFX-AXv!kBv25W!I$LKN$*J)MlNjW%*gamv zj9^7tsAl=X15TTmYamT_+hbGC9v}IE3n&vCS4#v4Sw*#|>px%oEO?RNqKd!?=5rQ( z{}l|A7D2_YQx-Azp(I!wOT14-Q!!%$MWY`7uf?b@6|Y}Mk+5F0I%syd$qfz4{Ftzq z3;h?+%vo9gBlIDk^-HWy69)bn@Tv+P67zcVq#|!Z!M*)a=lz=QzoMdxxIm4f4WQ{Z zBPnZ<*AlHtjm>&CC#moiyT-5#P!Lw)My6B4T$4{^ zAR<&}hD%%w5p_}W=sP~QdV6tUN4Xn}<)1lIF+@4lMg#VSz#z$gmwQnyY5cS!VNxz17 z3mtY6acnc)k8WnU?IM|tr7s8|08AR0?P^8XVY83XK6H`C?=%C3vPX6n=f!04(-G{$;B5(?Kc14*jmLt`0NinrCY}7Mk`!^0J_!0E+_a z!b%CN19c)V31%U3<>OF8O8fUz5{}A%)ImC--gZz5_{U;JuVYCAt>>2AoY0#`C5YHc z8`BmRx$vz`o*0l1Y^?Ykq%M~wrMbb>2gO2lq)MbbZKRX7q-%M70QAYCBYXS=Ki-13 z)C3Pg)uaaxyc2ejvq+?gy^lxcZSuQkC&Hl~lUaS-w~dE5kjN;qn?<`D*$8G~=LeSC zGa>==%8@l3_7)CA8KIJf;;fX&CBiZ@*nfbua|6GiI@b+eX9cO7LEWGBq3MKo4Y-#a z2$#dNn13r3o;B150STH72%kjl@IQS&4fwnmdqh9WgN?4^G~)0eG9rKo+S42BKP>v-Oy8^iS&13h4GZqFl1SS{E6r4%J6R(V2iz&*WjESy3M1?Hrg zwAt=z-m}6QJAQGc+e2r!xB<&!e^Pn0^x`cep2t2n!iL=nfunCKX;(uUJ!eqrPKJZI z3Rbq|cbktQ5-T|S1&9q{IAAOt@m~Y7o;QEx(pAusG8X#xnxACAy2sa40G?xXtchRI z7swCXzQnaLPQ~pXxU5-%C{6T=Nr+_l`ny6ltsFSUlrE1S@jFtPjSQ06$C#{h=hYb& z>fBfIi+k#|z~73J?^bQFP*y1^+*NcD4og#5)~qP3C7J?XgH@wD)|Yx%#I3kUl~i)U z4<;Nt+UD+$XOO4;;2@NbuC9dXzd_>yZ8cC$5uh1n>;g5n<<|;je?3Ph%?+`_qKYoj z8BWsbI-`$%-K%>4c1{XiAni+J4Y~ZJ z65-!9V=4=-3?IEaR`$|OjlbVkTwpRAZ0D&{TKiZZW6PU5YGI9QO$n;?vrMV@H)WY8 zjhOw0qBj%tvmNb_ZNSQ>^JXb0o5Q8D;Jy)d8_+U&+p^-Y+#xdSdHEKV=>Y%i~y3A~7Kui;uGSb-4m}o%E{M8+C&LpuCGo;=o5CtT^p#WpJX=3SYLQ=O=}e@ISxkGH8JIw3z!({9FO7$-kh-oNDImAuOif68|Af20+OLPv3b)vINVl8KfqHlxwKL#d^HqT@4G zwq*g+n*O*3@w}8@%94~Tac zU0SxfoA#rr{4EV@*65DIa)jQ04O_{y3dOWm zQzwdlQdRxFom>+yBJM}jGna=+YM(*5!bQdcC9$V)NXhG9C zBEq#w{_VyBv9?1d^wrKS)0iWaR;2tedqP>YV?@O?jEAl|<}QUhKOU=}(x0#X z8Qz{dVT|p?jL4BAgc_sezXp}Nvy`3{=S#38-1aS0Z}hJX&Z!Hq^N*=+76 zyW0qnjV5yK?jc%Y9CjS1o9hjR*$_AP9N8P+HeE_o3j4}g5zSs^#o7QNq(}5>`!;cZ zea4lvC9?x*(w}s-PG!8;=5wK3~PiP$0tbOWjyU z<>pSgIDgB=De>h~7h$42J*gia?*p$IoHb2VleBJE_YV;Y>*}cta1nJ=(qO^rL9H}S z5`LlM;EFne#G9|JGBqF7$aij@%ZUSj0_~5A4`Q8(BlC}^A>=!~>!0wSizyE%h9>3~ zf_#dhFZ~2YnpT{xJ|s*}O@|t2eOw?ZR@t>}s3AjtS9G-YAc~9yv!j6ioByUqn8-NV8j&m<{~qiJN#iap zkHAN+I(aa|2n~NmUngyh{Oit_M_9)1@t}R{X&i(ki4cK)?=PD>6Rrwdq41A*)NQqU zy_a~U^Bfk9wO7-pwr>0~TnSwm%8W42DsYM>)3BG&vY2|%Xi6vyjl$%A)`!qA;S(rP zNsh0SsTvg&&d>-y{;)^RoWfI7d;!Ha>*z)wKoNE#W=*kugy!udnKQ|AVJ+8@DNGiU znDE~V!yqp-lDj@9`uW1Ldj8C`7GZcNeB?Gkl=rMlx%11ewQF2F-uIx(83Xi4TruGi-koyci__4cZno@X=rrNkn$dA#5aQ%&!_qR^86Y_2TGDx=-`4E!77 zF4cg(%NMghG9zrEl<5BCCd1x(j0Q1cAFjC8aa4j$cx0~&s^~x>;16rw+cu;|NVwRa z(8QE=PZ^!WLW3{a?IYqQ;_y(~s|nKSV;eI~N>RFQ0z3+|95xJpZ=zpUw+HN72CF>~ zjl#>d;gUA=700rCUj2$HzjS)g0W+?)=Q^|ZZpf%77mCwnYPR@e=|I4{o`eOWr9 zdiJucl}-pDDxUa%98a0)uF}Fw8<4LAWzDmOrv*Coq+me-ibG zuga5Rk$u=yDR~on+{r`sVPwt;TcZUR**SJdIpj^mjS)_D(X)7PTu`xxaADQs3BKDj zSM0+k#0|-#7Fzm~j=md_pHB%b4MUYfGO)rSd!S5!ZxNeb49)=>4yoI~RuC zo#m#Nb#?}SKS}2w?MMxEZyHDOeX#Y6N1EA&G>k4?t71a9`Kk7i%0Irv{*pQXO# z8Hdd?>KSwFHd)3nPw44pNsh564IU)X^A|$hzQJh}e7UmfU53lH(S%id4x9UR`A5`lVFkS<2s0 zq@sH%+ywvi&d@@Y%OZ_QC5=APfr5_Lx~D!rI>31yb_0BP5Rn1<(VN7&#DU%7Eb4y8 z;CSzo`P>YSp63Yu9D8QhpKSjiKCTIs3QC;#luQMu|4@#+*sXxA*WI9qZypj{J!Qp#(|HUj1Fx0Lon1S52+ePT2uXd^+^~VfQG1 zD`6$P!qo?)QnC}sqtqJ^H{ZA4X0!<^9iIrLh=v=GkL{XFv|z=8Gx|2aIGM;qT!ViE zd#bGJ$4yWT_imuwf5D9oZ`|L+Xh3kgRMu^}zG-$9cvH;?G}q1|Kv3)b6W&7i~*Q`_$#=&T5B2ujDGABj%#AowvW4Oay!XEH7%aQdl3a% zPgV2a7x+85x;QAN#*W*yl3RbCQ2*Zw^_QyrEcRM*prpha74J`*8nUrdM{=muKXqKb zf3FXcTKS&ht+(Z>!%@ivvenA@Sgn9bmmz3jKJE>$i#T1OZHZD&Pin9KFs3 zdXKi{c*aX|X(AS381Wu|PL15S1?YtET-oygL|>>(0Qp5W0%Hlt`iU1MUElpJ>yBlc z&fJtR70Sus>h^0g2nNvkA-6wA+kwcR#HI0+jpkM07yDZx^cr?1@YWM8B|`u3PX9^s zPoG7Wbp7CD5{>`?o6r(=Um_xC({fyI#D4b&(n)|}ity;Utx#QmLsW2mue0bzV<2NX zP$F-E=K(i4aFnP)U8d>*(!exxcPQe?KloAl)p3g~u7c>pi8$NmTo_0So0*o&G3L|W#`pjwTgPvWH0s~KPF z2ajpq4Nfi+pJ_PrhD6jbCHoXwI{B?pijq;kw^Cyhp{QCx%l?#P=MBFP{Xqfa1DDk> zg!go7s zt)D2$?OUo)Fa2%&5EWT^GA}>RfWh07W(Z?b%N;IuOS#ym+nkT?Yrue{Mj@*lXz?Sw0^N3LWYp|~r#PgGr-IllEt_Y;6 zUd`Q5GCUJg%6TZU6cOkgRg|y%)6KceReACS{lbwYA?zzglN@A?ei@-oY9iz%&P)`nSspk?KvIT$LIBb zF}r#UAivLu!VD;chcz5RWA#-ZAm>-ic$-H+jK4l!!k|3vF1iXxg_HpC=!=}ukSnO4 zC8x~*y;+8|>ac_%TE7#1lCptp&j$K04?{gfcQaiqKl_kR8@6VI2poJJVwL3jwg-7t z_rWiTrp%4WvU!#WQo~=QG}KhfH>L`InaOx|{&9PM9=74?%`a24;Oz}9R@m2W6PaCz z%5E_kg}dMQbT&}w61w-3>T5`)@sesDuZj+|E&b*}Vd_ph%#qTH(lih1Li*53T&y76XTSvrzJuwvqo zhJ1bYlbtoa6gL05>VChDbuUlsQ5n%g+$+!~03J#Yvgtbn{)zAp0Za8~YDyd(j0w%{ z&olnib!aWuOTG;BE3=%<%g8N%y3&O#{AbccAoRPdwZRQ61qb^R)tF+gBjaDUua9tB zIq2GNgoAM~OlIRmFKCBB>@FY7z>^~(XBVZOoSIM&Vo_BttDhAeDoswaJMVh5)iTK6T!2NA{oPU z?E(2;2sVL2y|acYxbbH-`YLU!xf?%?P-0xi1061+kaG$|tSEoCk3w&h`n7*vMZjFmT$x7n^hfn{=kd^-a8WTHHDyzPqm zTHkmkR28|jx3(Xj1%p-k_0TyrN;ea+BRu70`T$)8h4M<#JSd4f*LAO}ocNkQmkem0 z@=ue|3b#4d+cf#8W_#(IoaxZS(h1W@P2l?+9(OO*ZlE0p^ zV%681R%L`x2?$$%JTgqJNE6$!8@*l@BJgR*{R|XZE*)6zVE(XjnSFuOrg`M_o#syg zpYU<;cvt}LZw|#j(Z1bRZVk!Q+YnKgx}2(7Jn&~;S#5G6B&G>dS;2|?He)RJF6jeQ zWlE(J8R-~zgPUVTr57i6WHQ}3S&uZjF@eC;I zI(fuHNPm0|t@sz$R+=*f7K#JyzK2&SqujX5y*5y_;59^s}RDZ%hzyR0I57rQq%59u*eB<9D>}M593oK=iygblw=UrP?fnMtvX@MLhySz zwkk%v)`TkQK;9aEh_C3C&POe#t64~PO}+CW61bk%*c~*J1BlmwK@HzJ_L|%8T@_PB zMnv=1r1Y%6=hY$MA4i#&l_kM(WqbiD?gax0ZJN%1pAKKjcU`-XJ4}ytaErg#_KZ3i zPf9+0HpF<2R0zL4R60>72rd_y9wWNz;@Qs2TIdr%KTG`xvw!)8JqkdA8ZR#VxD;^W zfL_eK&OE7E_B*(Zr`Osn0}v|{!58YFyPV^RkR!gNfyXFYg+fA%6(Cvu$>mPa=5(Qo?!BC5H z?Lvycf>*j;M{Gq-pB%t;LU(Pk@ZEW1PBxm}qVFOU)X@DST#SwvYB)I_lj*_B5*o?y z>&9Ls%b2-VJ-_9Z_nMO8&w!&~YLcrIJaoB6{85Xl3%kHfZ=L#|N;s?nD0butQ}TYj zu?~JfmbOGbB0jmXqyGa?*rg{5Wo~41baG{3Z3<;>WN%_>3N|<(Fd%PYY6_D{&Km?a zG&C}k@jDa+F*hni>O`nSTLHTwGjmWB?I6 zdk;sTxrH-;QdLQviiU>vKPCT|0E|5TL-Xb71T?n=kbk|nnp)f0+nCxqe?k0TJ1U!+ z0-P;O0cJpJQ-FxPf~J(51b|XPP8A?wYHR9fXbn(sF|r0417v~5rnXL|Q~)zOM}YOe z4*+93TNB_vr8&`mVSfoZ0Sp07_NK+nV^jNoRI~tlQ%4)1lhfBb0O$lTcQmwh z{_26V9RO%+Z0%z5PXb?ZGrNB!WbbJAWnuHB`vOz2b8>bvb_Cix1HPgvh>HI^PiG55 z=YL{50l(A$JF_oK6FXyudx;y_9%YVoeU;=cqw>I?niv0y< z?+E-?8ZJ&iTl4?SfEM6rYHsLgVr}Z=^ab;U{ZDuPvrfSOQoW(Qy|u@`yzTyF^*?g} zIy;$Ko6*BDF@ME0cK(WO4zz`1_-9t6Y|ZQdOpO1Qo4DBjhtAd1@m~$1{AXsUzLGFB zv9q=I0GODX!GAHx**SlO1W^9pu}uHpNAiCI#s4h?|F_Wl|3>bA<>-I8#Q(4N`M*Mo zyI5Px8QOdez`u74;A_bk+5*1z3_up}&!Vw5bo~GM7}@}>J^oK#|J7RE^xx_JAHbxX z4ZqqVWNZFK4I@3{zlA_2aiF`Yi2~5s*aBc?X#Lf*e}BnUZB0xat%0_tU)=tytpGYE zM#lf5Q?URVTiO0Y0^7e;rnV;kwSq6Y{*^z2n2NZxv=q(%X2Jf;P~mG3oK-yRzjFH@ z)%>tC`Jab>V1$M3+yP#6OzfNhI%ZC$ulx6v5EnD6&;KUmzkrzj^Zdim*%9at(Eh5M zk?CL6|9_9?KTo><1xC!)*v{mi(NT6bv^Dvfw*M*kM{Vrl==eqQzZSq()&Ft+*W8<$ zx|Cr!OS+=F3F(Vc91k%#9)Le-m(vVTtA&Ox*Pi$SjhA?;K>((7_gb`wI2 zol$LndrVPDulNlLf1;hm5$5ud%8$e~-|su=gFT|JaY}s*dIxeN2x@J?$tiil(c=R} z|H#nbK=(Cd?;b8qb_^^Tk0GXS(g{(bvxkA>U4!ul`KJ)*E~DUrQH+e+MM&_sXy(Frep8ElNi{}J@3G0vNt7kSdkbzJI!`Qw6#~J|H+<6w`rQ_?-hUqoAOsWia(= zYEyJ4N{yS$#V#4k3w8*K)ItVvp@?|+DM zMl}PCjkMYkM><;-xS79&lQX)**>@6o@G}4pm#i2&a0ndHi?_(HVSoIk|N)8$q@i|$>p+Ojz5+qwfWShpjEJZ@rE&G~yR zX<+%!6blWJ89%q@dh^6=`KustK}Y0tvyWwibZ&85_eBpvZg$FYmV&kB1_LWxa^Kin14vuG=6Tt&MuiBUv5bK30N0>XQ`DbJQ+XtZ#bNN?8#Eo zGC{3me2ez)3MDE7$5K$w0Gs$Q)QR>cHZ1XVy62?VsKx*hDcX1|kw7e_iQOVcD!(uD zbX2L0qsH=_psKXoEX?$=V;iqXsA5)S;$Y{=zgqkKF8C7j;wEvL(SL+L4oZdFbq>n0hpxOtuq-cEMWh3hnItLnP*lv z2{k`5#0ik_II1~BYuQ6`dwe)$I^P%AT(Ce_D!0{{xj^=p{WHWGjGe9LMwZI^-UzS* zc{!-Qcou$RInXRW_J2p2#jd%d5XR-&)G>GVSdCB3dXoWWXUU3o8s5N+s@kgp~IXNn#pxQ=f#)DykfV|rbT7vt$X^C5OOkF$y1e3~LC?75y z`xS1Y30-U8ae1wXL2su+Xb=7GnV5KFcg+|91 zEs9P}aTKL;K$I6{a9gjVo zOWM(a=0m_ZUbr(C@U=HR!5RHVe220nz2_DG^tXtw)fItQy(%t<%;U##n}Gm>&Xhlg z(gw}Gwq!DGpln4;*IZa$?DUaxs`5~&Ci2q;JDzxvcJ;9*!cvt*lV~}A4Y^0^@X3mK zH z`eX3xeST=y6E_DE$wj49qB0%Z_{Jm`52%_Gc%BO+)v5>iBDr%?WfzekpLFnM5fsg} zn~Nmhi#b7<>lEj-Xso@&c*+@em{mdJL&4ac*?*i2dNk(MFbOf^Ru7VSlF26@xRB*P z`7P~*d<52gqV~fyq{g`H0ESN`5rZb*(Zu6w|A}F2a6nt|r{;G2OA%|)EoK7+IqY~( zR4$7o9~9x<^3202p84Un^@;cuK{dS*Um?z`A24I8bP81111 zn<)khOUi2hK(<(BSQCL+Nl2}%vi^V_a#WeJ%oG6Jc^Aw6d91sm`u0P1DiSi2JoFoM zxzmecEadClDj$ioN8y9Ocum9%jO!-qjQ$3`AAmNGR4)%s+R{A{}k4X!rsJk!?itw zv%Fo~>TLFs;iBsz*M$@sP!1HPp?`# z<}vzJpNZLn3m*>8l3rZD6EEH^;l0K{;P_mbcni6dz4G}Ivgl5ujrg-w22|dvHo)kq z6~g#V1!f#BP}m2Cev>04R>ippz>0n4?p`p5Y5=!}O-XPJz~09FjSoZAyMJ(Q@J?ir zUTl%kMa7PxHW-H5#qOM5=#tI}OtdYXPbPENFwW05Nyo_q>B=Gblj#XGw7kB$C#%ML z+jd~9$Sx_0q!C48LY^mlgAAUOiCC}Irx6)t;!+;R&b3QVJb|?qb{z{jIzB009z6n) zN+^9$k+Y<4V7!N1^^zWiMxj@8}c zP<~XTCl?+(g2juELY2KZH9;C5AHy0`ktAS5zP(w{F_>HAJvC{lqRas1z%Gd5??mMb zt`GbbK^gD@3=%>dF%Q*g8ji?n*$`xkI|PBv#w>{)66|IFDKnpnDt{nd>3Zh9q*c-G zmP*}37v6lIqo>pGw^bqfF$7T>`Kq7CkaaxhOvjBHnH zB`lq9?2prv;^b!V%|3jtxI%Y>x0NPf-jMskwG+bB@zAxyXPKx8Pf@Km`a$Ea4ul(v zdg!X8T&(jMO_uJe*#?v!&tJ%+Y@3)1z#W}yh*RNn#adm5+D1E7f&Zkl_=|4VQ9=(Iyr0Ia z1FJPd+eS-)^oFglv$+>Ct6KpyQCT^86i9>CaI)y^NG_9f*qssm325cg(PFGSQKg_9AZmVgEav^+I-zIiPphMbKWUgq?k9D5Vu z=^m`DSMIU{E~v=6(O#pKw~dcNm+F2#J;e!Nu6UGAYJcPL$T58yjp3LHR6tQMh~jEP(Bx3EVmgww!TUp^I$0LDM&Ix>i^NT`g1A@QYy6BBu|HkGbRFVv%mml1xr z)wdC}mc7We<$U9WNh8(|=@L`M>7vXT?8J)$sIMVb5}&y#^f1_12+uDdybv9f3t(*V5Mz z+ZdfI?%h%=uU)jc^RIwWGTdrUiw#5urjzw@rdTYWh?e4_zSLDxl#VO~ z-i~;tQJya8xkrT;?OQL_4?I&$-uvmkz1=#FT{)?x`y;)@=YhvD-Ul~j(U9U7a%0Zz zHh=pDYU3%*0g;mQ3(0$sNp_i8w23cTvzgkvW7=GN2X zXzdX_v;8LJ-wP5R46;q>y`OuK_uSI$R|6aQW`_x0rb!I8xc6ls_2y&Un!xJ!5D*liYcKYES`_#=%qj^b|w& z<#?d$xXQR*rZGYq1qP)%h9v!hZlII{es6#0?y%!!4qb(Svypi0keB##rHYL+<9{~M ziw1at+XzRPSs7NcQV7vxI|hu#gUHy}6CjO9DMp}Bpd32yFIYaLOXI@V^#(|~^^T`8 z7>H%z(!23M?`&Pj-9O-C1tpsXc z0yV8U`sl)}`!p2Ol-+ZNBba^MQ-4q$f6c`f+x2$^9|QOFJVnk$2;&m!orgPI}m@n%`G0*B$ z#ceyT!PF>lZ$J0)FS0d8(Z`XIJ;&>pY0jF%--rDB^K@mIxT~6Jntvn(+tqqOp@uF4 zQ@L(^%O6$nFSDoaoOE-d6ad1f<Q@UNU4^wZ$EkqD6UQ^;^4-0Jv*JO>mqO z&t0%(oYF3Lb--~TXMZ{m2jCNw@=x~993>uvAhKVbb*Dgwo6|9P<%k>!iG#V!SnDq52nDAov?RkLnHGlZHjGGE-P z55U5WWKFH${(nZ6b3*bA-?aRNbLk_7-^fG%r;Xr1WZ#1o^!%M5Mx94FDh~Z>jLI4= z&dF;VvX#|_1?0llR)d81CWNluc=DWdtAkkRaOx%$Bjsx6qs);^Hg>Xj3ml?ha8jlW z3I%KeoAs#S0>LC1E%7ruMd4?B>PP z-AF1-umItNT`w;RCs>?QNshM5f_>sMxpWj9-GZtLS^2^j5Y0DgA<|-%A>cib(O!si zP=`~$Sbql_CpZz%$&A{omfOoFSF2a;0{;#Ja!#)yWG^MagOD&Vn5UJ zP|(GqiFEi^oSz34Prh2dV@U?Vek8;6wv>VS;>XVlS&rs>>)c1$IpnRREZ(Y3ya8FU z-wYQZtF*hid|CYbs_ELYh4yd`Q;P7HvshlItAEetPBTw7HAtOhGl$O=W(+z?eBb2F zMxJ{Meh;v^G?l>TweoSycn-T#oO92K*>anAYd59=9zM(f3rQxZrLl~v^DJmzKVa5j z91B()-&?nDtqlaqOqpLmo?^y4lPdH?PeZ(ciJ7?LE4kJxq+Zhzo~ZI*ND%{xh6R*j zTYnwL&ei#A+HA0^(eF!b)T=r{Zvg}Wxgh>PPg$uv@Ah{p!H<&0SNLdFsf# z)BYnTgko0k?F9&1Q=OmsPTy*`Ho1#8TF4~L!#X$)tS1u%DAeWo#1{(0g%0r^1>BQr z+d&yOYajJT3IE=-f|)aqJgKzPI zAco8qW){z8;W*yl=!d5B)`+a=VD!ldRA&7RXITvA7yeQ};=_r}bnPTu4TYE9T=y$8 z^&!w9!SJ5cfgyzHp}JMklTJ;R-EVJSQIEV$E0r@a6fz9{l?@G1olhyre=S~ym49E& zGZe_p_-INAg~fP4#M^OV0|`%8k@hF@@dzsiZ-rs!*=mS=AWsk4uZdha=_tFPJiYSG zT`l~kHcO>xOSs$1heyDrmGzVM2OI>3vuZy$q45e#vO@pZfr_Eu+WR%2!@(m$HjK#}EWt#7V)?uNZ0_?lke-C*S;#s?~ILJ;R71$y$ zoeOUFGwZjMA{W)YSFiDzzJH+?I6rV*3QWwX8NVr)jdxfK`+%53xz2i>Oq1z=F}idN zwAnxMg>>~>=%=RLW4RtATy?>UrnzF4)Mep%*`0s#7(dFzjjh}5F1o{qy@Zj zpHih%nl+qYO>mgL{jNxk%o8kA%rNI9P~o53Whv%(N0asR$0=#T6MwqfxY9)PW>XXD z8oejgV~lokPLmdp4!57-B(Uiu11j)(xiuy=;q0Ot^L>-QrH6UY;DtkV0kRPKFP-MCFG~84EDT5())hli2!;iwEqG znH~_{Rr8&L%srn5{eNI(cxdQ`LCqpUc5gz9czA;*v;~^Xu4&RfAfy1HR+7k`4k_XF z9&NEz4SYEF)>qL7T)WK5C5=wT;CiwwEH`GRbh4&p@w5S!ju0+|+`aTT03Awa6~l(j zPLk}*AyM~=zYL@sId^wGY~sh(&st$1=&QRO)5J|LO)wmlc7K>ElD_^zeiM#I4gH~o zBa`)GXCoGl`ysOlbey9*~IeG zgXqOy7ao0AaDRHJkGLe5J4YNh#4a@RGyi$pQp!^k*1uxS;bfB@RVs!kylgM@@f&%? zInQJ|-UNjOY_++2FJHF*vL<6Q9-6h|4R@i_&dTUx0HIU{-tYGmSxd6dpg8N50gV3s zSyO%$Z^q*=x>(9HGLHl$<>a8`+f{I86XZx-tlPftdw+$Kv%yfZ_32|WJ=UexzB^@n zg-EjaK1*v@Lk_;9hqv<6(h#er>x7MdCARgRS!tA1DZ8}vtok)`Y~ml0<(#;VC3_Zk zj6y*MHcWRHmn=`?NsBHq?3T3{ zrV0b#CrhxCTK|ZxTg}HA{~@-CAe%*G3`x8*OMiQAi-|D{Tx2K2yLsPOft=chQ_^9Y zD7|VFm3K17GtKa)6sC^HYk}Ke z-7LJf7VlcKkQcXU1!8*t+?}bj6>9w+yE$m??xwskX_biuKqe#*M9MDv9pp`}9tnM2 z27gXLIkMJ=jpFt0PIm5@?thzIm7i5anmJL_zDz1YW)rxB{^UJ#=0LX(t8$csZh=0d z-&z>#S0ib6W0&U&6KCU;PP=vQ z*Nr?hC{e5D7!CbV^h8#_3EV_H=Q2xCNq_(CS5)*piKG2x%YY-l4lSoeQJO~QSG-YH zlGQpw7)d2aI~(2#FeI(ukB?&B??klVdde6)4sAZDHEmyUXvbeoElm3xlj&G0xjwqQ zMl#iqmia9%Ix-XJbwPh0ZjE}y^Jnsm6bBoos7%V1*ofk4+SO_447*3;;Qf@V-G51W zmFBkSe-#!o!TR~(h;tcq>1o&wEgVJ}gvU`hpatCDZqW7FsQt2=sQ}(yixIiuF5jCh zLDV%SbB^nVl-hy4&OyUG>~*dq{}Or#_Zr2+S{X#^J?x}<|AUAED@Up1mNU>ZznaAx zj=OHW-3=oV_N(X;{O0emi5i?jbbpWv-djJg3_1#9SRk;2*6PseHI331+xubU*&+rF zVwYKMD7ZiIw%jHcq6|s-5VXZHf^KHIr7n0t*9;^{H9Famcfps}qkmf&ZQ5KoZi5PD_Vr zSq$ILG@%XbQ<(Ye#g_29uA;Jt*%H;l^V8znxYb(e;*(3EaX;23-GK0mknPOlmFCCJ z)xxwVCj={-%;W9l{BWj zLa}xk5`2rL2yK62sg4=Pf-q*Dnm!M>b601)^nV&rnB=P;5z0p)-+xaDx==i=k5wvM zoE_22ooc~g>zMVkb~~6=Q?eGATn?D zuRpcT^$$w(v59CSeSc;KkFlTn7Tb|TsBpd@Zr4|$_s;JwflKpZzR=Kf7GQZ>Pb(h> zAhPZ>-IhKcb`Lhm(T6_{+jbNll~KC-3KHs@5QfrDb&-B$g>i+b(TvpYx}b}Q*KM;< zp*RHHtc~*wJQohS&D{DiGTM`0ht_JJuSKixHn@$ zb>lH~2B1ZhG1zi#Ggw?9Qiokmwjla~&|ewWhGm~tyRc4aRpMF7W_)@LE2(uM7g+Zh zYYmxl-M=-*n@znBNqDL#h;JjZlJ&rC=(9F`R|=27Npzc2^L0 z1v8=M$Khs(SAW=M$2GB8QBHC<4{f>O-qoBjaR1TLVGNW!YLprbuCe~ltl-Appbng;@q&#v1 zl3lEmSD^|a7wfl+LA8J3uoZ!;D~4{9^lMb}sW4T1Pk-?B*sj4ou0h};UfIUBlIr?# z#`Gk!`(AXryj(77{tZL$t=^HXAA)Bq^t7aQ7um=$w;1{q^;T#jNSYHCTq;Q~we?y zQTMkfX_u*-RC+75Ip|5AC0+HSG9Mh9`i{))NeZHqUU%{v?H%O{)^(~w0qWYj4D~(9 zjIIE`if6681!rlP3M&63w-lEzDWTMB$}JC1K7RyYyTwiYm_Gj=_sWw}kGxRn4s*tJ zOjuG$ch+8N@%*j<6EyTU6mjG;nQjE7yQdq9ag@4&S|afQI3|tvP>1TdQz^BlA=<;=GR7CChk?-?LGb{cOIi$zXdTu%#V^@*7 z(|?DQV>eM82(Q4ZqQhhAp2 ztWgnnec;RXN1Ma|{81OyjTCXMX>a)7z>_>zFzqr4cH~0Bd?rs>y70h-AuY8t9-;jR zYOk)VmGmEaY+rx(kOh3I&uMTrVX1Fbhkp=x&|g27t1+C%V+n25D8_%%R&(i43U4o3 z+1)WW$Oo&s!gmFu+bvGME4-*PGVH*cMr^5Myw=ONXWEUTI5`K9_y2w`7~>AWDr0HR zy6x(>oRJj=pZ?8{8tWivMbRFtg_j63EmX8tZ+}n@5k|6b!s6laO309r+f{sbK0#^+s0{O3DZ*xZ z4-)R0spFkRO)h`7BFK)$^)pZ#Qicfzo5QhdCrCz}Fg;Zj`ck?B=jSciiakJ(;c2TO zuI86dg~JccJy}Fb#q*XJIMw?^>h=b10Ttp2j=vhMzJDdw>=Cs7{)PE9BWm!eDi)W2i2SjC9$VjT-u5MCOvl-q8Yh8;940Z%s=Q+vyyZvfD~t} zLg@H}CY}aCqJtN~Xsmt-_9oY27CW{_=|q-`{3g0K>cXJzXJdcT4q%e^JMLOV-8}1K zRb2Olq`g8~gA0-a*}^5co`2Wd@E=e2K|J5~0lgAplK}Ie?Bh!&XcHvQ^GdDdQi7wGBcWthDL z#XmRf5sYiDbv2jC^4!sV^+$2}(!pD7T}o|60LZkTh!!a`lRF@pDt|ffc9Eov`f>XV z(;ku7kE7X+sgi$$u(kZE`tlr#EoaE+WLdynpu;BSd{-PbFJywGMzMd9T{}apd_lD! zrS);SCi`>OG6zb{*llK`*9p@rBI^KEKn5hLNkV}^M;Y%I=z`%vlAD@f1{*QDrbR*9&`$tEkW?r*zo)kL&5HK2KcrL_ zznT}Zo?8G=qA#uh_>{7a_wFfXmrtU~f-=7x8WuBLjt57tlmr$)!<<3Tp$d}@xeNYt zKZE);kb9@Jj*fS?YkSfqxqtlI4Ay6X#)W7^JLz_#>{h$PkAD}?+Pld@#cDj+3skZn z3uhJ^2h`pQY@E-hc4TBs-`#yda(oB3B+=MW0d{aOulBB_VBBd{)6tpCVY#n^AV69L zNyaPg6MsEo!gok;hHWQ_1N8L=VV#mnyandBgADm`czkyGLR=R&F&}HG)!)a5fy_W= zBv$Nqe=PNeP=C2CZ#VhAep|ci1XrE@cC%PV7ZC+d_FNQ@I(ye@YrFeLm#0_dF52Mr z$ntEgo`lXtiY}cZnaoM~n8^xlo6KncY8`}p)KZMfKssX}KD!~%K`N(dnp-aoH^A_5 zmv(fY60-;LFJ4sQ8qYpFXQZ@fQ#nLN6j*wfmkD~a9DkkM`um_z9i*r(^!KuG?@4rZ z^(W2Fo+gFO{3yYgqJ~J;UJEP0TQ6nKwH}4z!Wd`CN#OQ=GkE1Yoe@DWi{QhQ z^V@rGI&{j5SR)meEVOfVh*}F)og&$-`YjeWB( z)}C`dQ_hqv>y1h~y`xfSyZwXR{V$jkAAGayPL+5P!6o*{LgJTBlJ;+JdWb6x<;W`7=jU~(aPE_C{8J)qFF{+aM1U@gmhr%)<>rSO z^e!;mQj(>V@&1pd$pY0@^rluX!HRhg^5nvKB z4C4-Bq*zL&?7SKY<{*Wi`CVJZt1hU}Zp-`pS;ZzP35SLbJ(4p6#PUmsosPLh6Qgte00;vdRSycDZSH^?&P6Pfk) z#lp&VpnWa);`jRbp3q;tm?J~(lW<)Vggm3A7svNsiZ5AAqnM;tQg|zsl)^yNXAjC#StZ$TpG!GF`oRCrxZ6LE& z^jmj7!)n{sK4t}5t3~2JbBluZ*U<|$xlH|%S!&0OgM-)dTp9j(kgarw_!(%WlK(fK z4STTN>_O|a=b2@u)kp>D&Yuu+tb92_H;W^*ek@Z-Fsr)fS^;3o@>F!L|? z+Kq@C%b^*w#vLOkn3NxAom8KYwSOQx=8ah(HB zwc%IwX;SnWCsV!zk4Zi#Lno7LbQk-3f8*R(Wj@n>}L2 z=Oc(riL^qQFSkxZI%Uk-HICEYouLZgtSgfR?b`rXWeM)Tp2-`X`pbo0l_Z=tveO91WASai5!wH@%TTgaH{@+5Pj@da!Ys(;c`T`1gMN6JxG=gC)Nf zQFdXG`)}KeBjJ^SenI563Vf6oW@Nm!T=AIbFewXWOMTUMdq*sqovaoMIik&A;{!e>ir7 z_9Pqi%}G>hPPgsUm=Rv029{n5RLP#l1*=eVeKudV$s+*w>olnp+nwRwgojMfsVea| z5-tKs*7MI6SE{2HFa+Ko+5=hU2sUM5p25-atu0WqpT{?qn-2wiy{)giKO?Jb=+OFa zCPNuk#P0`VwN*O-3OJ6#<}^)JX#{r`3<+s8C&sxJkfsJ>UpL@1!((^s>iFXY&VjT^M{6`XY>r#pe)b&xCRv9}W;^94j*{&}Csk ze>ma!u3SdVFK=BEX&V0Ly<-_Cs^0~lGSWz%Jx{zy*rco02eR-uO*uxqIgB9mKz0*y3Mi&?g$3D}iUWIhr31;3QYzvUgL2McHZQ?iqo0NqJOC*NV^qVsn>cA1+8 zFzgqO<%3vH5V>gAWx8-;BZx)B?;>33juHF2QVjzf715g#Ghjq$Ss<5ZR0qfij)84~0YBKwK9l-0PP4YD-JTMl?Kya2!<4&V4y!!%^tOcqpDOF)HO_=7N5G z?Cn{GWyj{eUduPP@m4uB&Q69lF&3=)_YQ~-2OToeOCN!2)e;D)_^dz8D%kTbD= zDhKVvff*7cG-epLzW3PLMywujjuOyKn7DV!YR5b1G#fhQ3pvn5=&@$ zlJ!kv(|Os1X>rN2^=HTbfpIc_yrNF1cqn6Q`D)Dil8@Q6zbu~#yRfm_OarqRc{ipm zwkLbGM8C9RiqMVl9w?9GkBidV-|r8#G4l=Gh>>IPz9e5p1u~PWXY9S!>gD4X4~?c+ ziUlH2WgMK);w7^HJpu^M>)(?CS736sG&p%0a#IWKR(xAmJYZV!S({R?rxFEpsi)4+ zYa8Zep?L+K#P3pMUAFZG&%o#Am*dE1PT%>^#YQsU$Ua|KsoZqiyboHWLnR4@dTQ}` z^;jp~;b=8&!|C=|nFzn?$WRy+ARahC=8_~l@HHL^D3~>8={>9(oIBQcKo`jy{WDwQr&5stbHpD=q`eeDC)L<)vnn-f86TOJJ4+5W#~nV^&0--aY?{I#kCswC zfAk#^cu+-#APs1K1JB6IhW|>JLp@@UTD0EB9PxFi&cxj-7l{3CdDV5lvK1T~gbm1U zhQ?u0ot0na?Xq6Z(2npqsP{^24tD=*R%CR)@;y9<#dkfO)+_@(&m8C7ERhB|p7G2y zqRg3L!w#P0z}02c4FcFPc1u58OY!gT2DjOjX&(m)x=`aHLHZqgCXO z3{idE@n!{6Id-R9s{pDQGF=ae_z zjvT5Z&nbNV0;pKJN>Xr_KKeJc5X!U#xWBog1ohsKpnd~pW(ABk#UyV2>HosDLrkUF zSnmnQ?3Y=FI3J_NRSe6LiYvP6`u^0p4eHkcqYm&g~k~;INXv$tjFN z1Y?1#o|(9(5?=i51uM8GLKj(LP^KT(JzV#MYe0yXB@*x!<(QpQKJ;u9doT&TAUfS8 znQ+cdF*Qw3W$f-A(Sm~%)#z)L;r@DntB1PxAoEQ%_3u5h4gY+zsiu)A3h7xH%V?~v z?kxJh{p%W6G(qO+0-k5W+LF@26ox8uUYxE+n5oP!jGS0{oJj8bkEBqnIL3rCeWzBz z_zG{H_RwFXkeAAjR}M|faz-ht+p4f9MZYzrilkhaM_Fd=vL$U-8gq_?U$iAy6Z*o@ zIF+%1)<4Ba3q5ci?l@(ny~<cZX6$xz&40-g;%B58a_*s0-mq;Q1=p zssF~XeY5B1JH*mnL0^;TrdY-aT+Wyg4TeN_kzvrSuI*Dic|)dg1*}zO!;_9Qqt6kM zfqYkUbhG9WiRJ>O`WE+y3^$JW1Z5Xiz2d<_Fx)zhifrgXq}(d)bMoJ^uL!)eOiV}$ z+OW3)35YnpE7kc$aVF$7B1vp@;D89|>*{V`85`P@V`c0{y{V$(?Jdu!;@JFEx+IY; z{!)+`<(&5V5Yz-4*`p)L${^?cQ{L-n->P@50<47|RZe+?k6^oY0Tfi+D_0V0W*VEl zOtD=FHGG@ZEpm`E=)sBHD~Qp^4mVc_k7=F9^&6beXCvB*lf zvoGb`g^qh$w71-0zIK)d0vK}Q1JWSYPMrpo)(}?<4ZVH#6B$=!$H>wl(mJ(=<#B=O z`6SW9UYWW&$gso>BI$3DZy#boSl9y@#VR#@z9es2`M!ts(B6nSG{MXhp2?QYpq2X) z2b!S3zhI)*RD%$=vX}jw6AU>!MLiu5^2Jbe_0>;B(><>hbmFilhT;*R>! zK4~kLfPM>DQjyNB&TN9b3xmkR*Sun}gfdHh(UglD(Gd{a%&A*<(J6#3Qnm?ui|HV= z^Ofei{q&6*k-BW9%0ZI3Ik7J&#F~jFl-vv5#L#dMo@8+{swn5=^pwUpp0+wS7v6ss zm2B64y99LnK_W_lZSehSnC>0i5sR#-iugXe>VYas*ptox>YQtyesOdoDkf~BNP%b1 znx|S5d74-mWqjq#V;Ykq#SpOvZn5>l6&{!7iQmWd?`GNF#gAt=hU3^{#lz>as#-sFO5rq)MIl#a9JU zT3U81o2+mDg1&)cZQ>S3co^&3=uJ{#6-oM#cdD=@hF%1s0-p7y`zIFdQ$VvH6tl0i zOSRDy5~6&a?tJ2~?f6G7Ck^;sRcpFyON)<)ljAmP{>5VhBhEeVuW-ZMGxn z8_hk`iP9ACz8IoY@=E#T0rA3hP<(Z;@pl$v%2U6rkqQaCOxqj6 z><2tPbU&u9(Ojn=OiV)b$);U^gki42m+}{NFk41o;$HeAkvea6;E$DyOd4AbEG1X? z_-JZDp3Q=5Ki0P+lh(RyZEQYbCdSrZ07<>4YR^1?0CrPtos{x6NH^feLSOf;aVE|B zF|C3dG2#zmyCF+WG-`G!NT(4Rdymn0ADu954wrd})FX~WQsE)CWUN-hsAra7K&Ef5 z;jF)Vm}{VWWmQSvx;c_@b^FsmLxU}xq19M8m>9+(N0Oif*1_Z8Wy%Jc0=2pW;=eohX+(e#W*=#b0XK{hebLe34wcW~fc* z&y~KdyHH*Ly@WDJl9xPru5F+FG|CSRk8cAA?Aq754=2NmM#0dSbWdyZoQwa{kGMIP z*(gUUQj|5pO(eS9TW6j~O35eOsPEwJ#_-rgsLQaDP?i&RVxsTTf3bKrQn%_GB`Os0 zICXizpr3)+`LhGGCLJV3RC7gEhmTkXLDOoSq5iebtH=!|Rb!fm$ofxG<$`@iRS;UJx7qt0YlL{oa#ViZ4kPClb5d5 za?CdMbZjAZrzf|qLfJz7`JT@vz$#UzeF;9-aLlL0?R<9A!1;18*M&{daPAd-W?-yY zsdmegXg7Is0|sVN;m!R`9INfO*v$YGodr1f&h+HV1)-sP)-#QD6?V=jEe`BrbaNhO z2dN2;`{wrA84dz)qW5F@em^$oL%FoUqFc#CK%T=5;#-pDxJ-Y}mf|c?WxpQ2nGOCt zx9MV)y%Ip*U2ME#Qhx@oJ~i8W+X{AOVR@I7f#!SU0kJQCj@rvDRa^B@IEMxNZiN;v zOeae9yLM2dK+!Kt&+~#GIzuDP^vWmXxCa*dAdx!SLKC-f)(m5?JTTdx(U0kbL_Nu2u zcgfY&^s=`q;R;^a`(2kz=dhCn7GeV^%xyc5OMm7vB(tigX z!C7aB!ERj7{pOz-&9tE(5vEtVtFRxN&^l^Woy0!$#H6cq@k_Fy@Z&&n+MAz*D(|P8 zjh|ug-$nmZee%T8x-bv2kdUjcN!h&r-o{B_K>_hV)E9z|UPS5H#8*qH)Yy*`Iq!!~ zMQyu`&#$%AEleqUG*(%^AW%aMHthQ1T=_zFtlvMuCP^Si_WI<%Q6jnLX0J=J!ch*& zhs5|)W`fA%*3iH$MMwb{bwSM(miF+M_qZ?@2jgFAKh0?z@;CSG5H$!;csjX_@mE<9 zg_Xh-#y8BCZD8HO#C>CU3|khp-BYqz9{fcQmUe0NYj=)XKGUiub1cnw%53{I5>Ac^ zrGAwmn0tp4n~0`bw+#u2j)bmIvu3}+T=B4aQmh{Cr#Oc#t~mi1`QMB|V1A#0LP!C0 zZ+~L-I?8(`YFO^kF5}6GaTa z<1z4yKDRfDq>G-b!Wt7yBb#dXh$a~S8P~=FgNe^OgO$5Fdh81oD1U1{55`o#vyc%4 z?+MC=Xa2qP!7>0TFSi&ert#KAM1LgA{#gNLE&h)+bG=B)qH(y8k7D!Wfj7kk|(@Ns<&i9y-0y!r%1r7QpnoL0anh>(XU>LMW~OewJhdUjF90jQfr@I#>iPwouRx;;d%vIt{q^i?uOBYsYHd zM0tvqbHM=O!qDuI0!wXENE&p+5%qo-sl{ww5zAY6`1%`TqR9g~(4re=-{^Dpy19+@ z%Aj<=LTdK(8Pi=$gqz53c#t7l6@E|$+YF!aRa0ozlz?UOD=nuhIh-%y?ff$4o)31d z?~D<@i3eNkYjVQA?bo;VFwQC|07IwNV=P# zxXfT+{!!7!Pn}$1TclC55f3^LLlXCYQbahJ{=XvS)IdZ~JaBGi*2G(0bVzPab`IkI zrz6?jOcQUjo&lZaS7ZlUtB#Wgz0xK>1PlU%RITw)errdEY<{avzS3rtXyCp&wfos~ zcGt7lQ`gB%+q>kQ=@jq%^rW}N6q>iS8@)RXT`7eW;W>!K$?+~KRB7N9y`Eu)k`H@n zJX{Cm=&(4fJt!!jkuUbc1Isk=4=(I;VjBPy8W#LPNF78A8TsEEdw`CV6wGfzVsN(y zN2ra}eo#4{4DZRxO55-H4<}Gf?+hhkKoCbA z zdEfZ4B!H@e{h=lZKRaKM@JVqMEu9A)DhxEcFV?YFMcqy7wdW#uL%a9;Ff=gN5M=Rf zYyl3=^>tz1U=?i&4Xy=*w->}Qo)`E~WROMfg@bnq*7W2%@+Wn1h5A+t{Q-YzcwYmz z3NlTM_rrn?1_sLKuh;&U3-9;&e@)5lEsn0io*x(ppA#3k>;ZdB$b%W+zuzBK6o@}) zS`b!2f8Wn^QgdsHf^O;p8&$ga-+^sGS>Nr%#e%E@AF9D27>l6$ptWFHCXPV4@SY+K zsN6SiGWVAY={Gd_R~*a-(VypU#Z6%4w1zIXolea{=U|%K}6(YPcWt zU!x5OZGhkel<^+?OM_!??>F6IKOy|>OK#BjmJZT`$I|!E>&?F%nnHZr9CYK8_HCrYyw$XF!A+{6{+#+`X;jaCf)y9(OLq#hIfa?c5-rbastok{swMeSH=!^ED!Mm zlqv*W3L#q@YrS#10Nk%$AuNj%s-f?7D8=mWgO3$5kibo0q394TY9;bn1`2)*ebFrb ze`?F6B~f@*#G`dDiSEMNVYHSd4l<`1N^P%tZpf0KY5znUMkc!tK2umGo|Ldqg6mje zU6W+@<>!``#=)qnuEjogJsY`Vu1{os?^#&Ozu62a8#r#B4*`Gvo{s^fL)gcgkl z29rdVdiMgzvwGa!51^DQ;%Lo#i)6b?hd1A*;X9vhL#xkbj(I)z=tVwJS?qMU+4_S) zt5i<8JfPP`*S@!~F9CNOYQ2yP2oq?6kJ};3Gl7(lv?}lZcfj!@bn){3eE_q`ndxc? zs_YNK%Q1M)5`5?p(-4AJp1%V`Waqew6ZZV$(;T! z4qEL_kT-G$)$C8F{9^0sw&-$HBwrb=w&X}UDE5f=IIt9LP?}T}iM8c~d^5oop_2lT zQhq(yF&O^h#g;FM?vE5_PiGtEkOQ9>@hyc^sq=cnnMxuc)#^hQ_RMGeqf7=%azh&$ zctU+7|4@0^)ym{e=!GCnH9K-wl(0S{q|9GnMkOX2^eFd}nS3%%ON}C*O>*p>KJF?j zSNq*C|34d4`XnL~+-&z;!>`U~I=h5wyk%i(5k)e{$1s%l9(i znsyph@%_iOML&42ccVR%BlO*>>&5?f~Ws``6D~f-xHs|l&@x^fWgJKGG5JOYprA#{f;G!*;()zB4LXSH{c$&3l!-u%1Sz2 zQr%Ty0%_F7669Jb7lpnq^%dP!mcFj9(y9^}WcWAf!whNpc3#-sLSZ6pT|;G$q`a)p zf<@r=5)!P|9A@`&}7%%cfrQJzgq-Cy%zzMeHt&VbHupf*S zDNV+I)m5mGLe{(Ve@?cE{Zr#HPuHZ_@$d7SU|XO@a--jii&jWd4nb1vHl9Mdp2)I? zBWg{XzUHG%-5uSgvFj*So>SrK8i3K$1a2fFL>%{T8QBsH6F4XOS%g<|IQBziCvKm>@=qFLG_B}WGjwR_5TAa8Hn&;YW%~!d8RR{<~0LKOY z+-Tw#F5i#Fy_SMB{Q}a?8SH8i3L~=%4?c|tM~|1N79)y}|M9`4#r(uWXiXmDfV`3{ zrS|mi3*#>f33#8tihMsB$(=m5-BllbEL(tGi zj~1zuIH_29@t{>#Klc~p=>M5^sj#BEc}LhWwTIewpGCodM*OF%ZaMb=Rq#-9JI_mU z53;GWWo*m54Sl(`Pb*BuIBk2bZ&8|{EWVG#2S~BTJCr;c>)tM9u-(H(Kzb%4D3zvc zOP;4e#OaRpv2crT3(TJqcXsE>DVbrqUqY}tU1zw_xP2JAH-svkqN+*p#5N0nKCLF-&!`c`9Zn_O$%u&|XCw4s~J6uB4G|VAS17HYxR6 z*zh|ptAj}sdP82XRjOLr{=QUc%Q$L>q*lOtbS!kWHhhkxo& zLZ7VrT2QkV949R+;Ilg9*HbeUCz-rfCKfwQdjt>vcK%T_<2saC1eQ!HSkrPgVs`G@ zL>&F)p*Z&+nj%gkk^ZPm4E0$&OX*!{`SDI_jNh4oRjVN32Q|FoYaNZ=iIqdw^ssx z+T?*Su~+V~4PAMVoOBNliJHA!fZ^}Y?X&7o;bBY~GC{+i0F<-(oNBemQ0UtId~|Wa z%!N5iv#n-t-rc-3Y&227z|ugjz({t%+YeC6xhK~!0D_#!H*+(goB z!7{87cDLdugH_>J+F57EXUE%&uK}y*Nt|*ASeW`*3N9V=$}-DyF^?R-ETA! zH&T}k!8GXT`n}i143Ta{V33E=L#9Ar(Rw+#VgX}1)>cg(-g=}`GfMOgNz@!A#7IXH zfcR4TW9rOg>KVg7fsqlK;v!jAEIVH_ufi<~8E{O+Y$+=b>s3!21L8*i5CA%lThQFT=`QDfnOF-lR}d%JAyx zcK-#yL|v#UD7T}#`>1afv4<>B=CirMA|4eGR^zx~fEIwOXK ztDB0}m(Ul;^1Cl`6u}RljvE2U9yvUL-p)BOeIAR~Y^{|dAZpZ+2SZN$?9bq#1r}If zbCMow_uvb?g8?R9d;~f>=R9bvL&!xmOlc>|n6n1$Rsd6~a|BWPoPVM@Rs6V`qEJ#8HzT@z+uH@7vjzA52?;NyzdK6XB!c z{u33b=Qz$~JHAujRlKpm`4YJ%>wV_Z1lL2wF{@}JBeS&<*ig6)2qe+3}{7E5%$DRK7#`X2V zCTmwV4wCsWlDiyF_c5BOB8!Ap*A`udKC@M@3BsdB?jLbuTF0hcr26(*_9jN(PK%$7 zR`zl((Q{h`7f~O#ghiK){`+K-=O$)_RNt#@Dgk9mv%re?9-!D`a4f+}2r`)0h}o`7 zsJm?--1D*1K)h{4YW^q;>FiZtO|nGpzsge6Tk^0ct@YmHf7@qPDnqqsOSXRpNtJ0y z6%dVVFWu-^I=xd7rExiEu7u5uXyCtGpbiA-KT0DEQG_am_@3H@vO*mP}GJ+64Q zBj)f;a?ER7tV9{8XZ~E>Dn7QvEpKVL6p55dHAaM?f9bw{U6b(S=GzOx#w9e4lWx3d zXsCRBy2#2^GeQvX*b0vs)sQ@IZw9f=1(h6w;7zSpr9+yEEim+&v;HwBvahqt8{rMY znvwBi0-PB>RaI?Ax|@k`A@Uf=_IJxFzaB1uq3hV*g=coy9*BY!#6e$9b<~m%pMYqg z2Q=O)aGoHn_^l`&1^@N~-Vz&0Rv2-%NM?Z%X@zgxUr)KLxT0Vknm zcE*}t+YuB72s zfsZM&T4gy=$KgJNg3(n;rkuBn!40l_*HOMW#Uq{l5?V?+5^!9MJ?#pgWvm-Ci_(D1 zXu2wWCE|z)hOdE|O^Itb6UhAIXR)GF*ZvSRDtNJ*=n~J_Py2*fPTK-BAN?>B5zNgzND!h}oqVes!V8u2RqN%+ z!%p?_p$XenHFG{mPC3yA4ScjA;vBsFmR~;FEIb;$Tp{<uW2ZBjw>v~^~rS$kj zQ`MXtHWS6pKi#nBkxgpPzB*qW@=bbE z%~tCi%A%J>9`c%QZq-RQ3FO-c2i z(KUmuKGM6r&r;3R8NF9oYk^^h2?Sg;)nEN6=_l4Cn8^5_%8TWU<>r^l=_u4qgV*Z1 z5Ocn!IwUesQBd>Yny#8s%20$&Dz|tc=WzL7x?=J!cN~%j`ue#6VC4j>!05n>208c+ z5#X>e24Enluuumj^vhq=$rCmob!(n851n=uZ2q9dQM#U95w)dg7qOviefpUp!(d&R zmee52xL0&kcIC5Nb3kU8oTfu?%+DpxP!Gj+ugF{@tu5v(8JuN5Epc>^;r8P4-dU1E>-plkVu^z?)17fs;1Vg7Q%gh&EDNVW9paA%j|2#q<^!c?3-bH zIf%kMr~FeW<}b*^$hG2zRAwH&+2Eyxe1z>LhrPtHkj>2c)T8_NsLB}(+uYwk&gOE5 z$YO#5G0J|!(*$k_Z?7wMRJ%;JXnAvJEY+#ZVBKju%uI;8EYoj%>hR%XVdW z+4b*^>K@z6hI_mJdb041vRQr6498l4P-=PoPt#{TTn0Zkyxs}^c#M+J{Z;|K6LjNLt!&FCru*XB!kLU#6hi5Ko1miIp%W7_au5 z-z5xy+&)WpcgEkJ{t~;rQh*WnCWVYaODV2B^C(vl6E*HTV#(Mw?%gzaKK$ z1YnHn3~E*DfF((5PnSca?KgOKe$8vTz+}fu!nOMOLxWf%2i7Rn=ptt)03Sj-1wNE81(j#JT)eYZ+B6;5@3QM=o@^#pf`9E;Y{Ex=6DBcN9UdJ=IGsRBxpO=_Wd*+2P2DlRI1g9W7!Azn--NXIVJi>9m+%NV}{(IolzR>!OfSF z^nN9-0$ZQ&Q0`Y10U>0LdtfP4urlXZ9EUGi*8`$5Yh4}KVPaFfngl1uF_oFP&S zARq8)DZa9_Jqhn5)&V3dsc4m-3$)O|`$k{-;t%xm_+&84qg_1D2yysxtjG)AZ8g-& z#7Snq>djnmGo$HF);AioCt8AazX+UP;+aN@18&Voois<1#!xh~+-0fvB z^*uso;tCs|pM0*~g}U~OJO*$2B1sp4>7p&iV0P{nuucS26YRcP<``y!{}S-dN+a7! z3;qNVnghoS!O>&s@v`0LRv5JzrJ5szb=3lkR+>{np%>@d^Dy2JtKKlxJ z4I{#WJM_uCSgm5YTQg`z^|pvPD-jJ46SYkQN#`J8NYGwUn8i|^6?7}*6o3ED`h`DNm_Km5eEu>Y{=3}t)oEyK(iI! zh3&w4pcqc2A)r(IUS<3j>x}Umuws~EU$wZt)-hIbDC)eUFd35$c8ws!9kcc3%&Xz>{kg7E;lG3HcrbBzW!YI8#;T z=Gcf)PV<~9XE&Lo4<+;C{it#v?mRhtVmr*L%|wd0=GG+!-yj zyR(>QP|_MxjOr|GW8*&qp#Bw&XY?~n_*5R&pUjt@GsP5T1*;SdD4|v^P%lM(A5f&` zxE$uucnpaz*4nnjG=RIS4g8LzFW{{Dk9hgSB(KjHM^BkL#Si$U0V!$HS^dsH%2c`D zt2;8ofKEzOwk*F_2%~uw+gmX7QVJO zp`go=qW#J4q5*t454wj>|H62|(3a%3EqqSPfH*g&k<2qvYgUG;;C!!+o>96@J6zEZ?v6}Oy zThoIyhgM@5k#P&~XFA^~I&9=X7F0$PZsp7Q3G=`vf?RYek)(pX;)Jw+v>T{a)7`wF z;PkJb96A@(-7tb@S7k3xd;J*H0dxv5I2(aV^Rt4E*4gAoy0WP~NmVl3qLwaqBEdgW zv(Y>Eti+^r<<*2EVc{LJbqfqiP5%T(wHobO*GSMHk=+3>ADwydIX{>w!G!5@6u3&7 z3M?Ew7^;AM_;uKG%_g7e{_%G7_#a`H%uQ6ndV(!f7w^1S@lq;gdI{csG*S9U@ruv5 zz3%xj#3nlAuXjOsjg|6Q=97;BFlU6c@XMmrw-?xNmSjRlMU+)FHw`g^@;<>)jDnYV zX=d24riFm`i6EPzgLznK_1lDmhuYaDO(^bG1?N0ix2DLrGlOJQkJ-2l`zbv`>gl|G z2URbh1SMe@SwuTH63nLcAYb|E_1X3c_~A(PiFv+ZIlMs%THE4oA{$VDCm-Xg%;W^>U%`u<=m$;ky&FJcN~tSnZL zfGm63F<$)msecrD$24LTLFQoW4@0#Fw@S{?(cwjMLnCx#X2D3-8;NSARf}&E+)-AS zJ9BSaK3Wt>f(uT@D+rYLFy@H)ROMay?_euZHt{Txth!T*_A-pKefk5#mMhjdch5Qs zRa_v-Zd1)hvhQ5PUe8l+{So26=<9w3Ou@yHX*&zsTPD;KXH=ezD8tL=G(*+T_j&x+ zxlD6?=fKFmMkOrsj=tY&k%4+dkoVSt$w#$$@7nvzXz+dafi$2N>3Tb1C#P5_hd)`CtPg z+HKY%E{9G;1V8+mB3CVb;pD79p1c>-)EC{`y`QvhACTz5P`bc2;-3jO{M*`2(GjPd zHIqJfn+I<~z;YH}zFTaaCx+^KZV&{@-IAv#JJdIp#Z0EVE#t{Ns2Z>?Djv4xJ>tN$ zFFc)ZQS4lkvXw7I%F)QReZ=m6gV%~6hVg_wtS zbx9yGN}d%zrN@#J0$U-stUSgZkc;h4es;}DC$ssP3)@_cMZ4oqsZ#h@wQ`E)Ahoxf zEhG5LymbD#fat(;Ml$oTf_n^zK2ejYlO+D>>b#+(+9?Wi2AySDk>^AXOJL+8r z-fN~_((*5h#>$NUFq>~#VT+eu*{wS3`W5x2jeh4XJuTo_*z>GjqYN?%3BA~v z!BUyhD`Ru9Vv;jr3Iq$l<@iH5u{@29TU@6?eT|#bLPbCdcAQo!#G>@FlPR< zO5uQ2k!X*z!C;mVbP_y3yTWQs6eS~81(~G6MhCsS67^U1#+ID?pN6Zt@KwX@5%6j| z{#bgCw2A3%`>{A3c^x4efp!gHao3>PLChDgwr~%6w4y1=iBL-H6QlA*=h-3>h&=3{ z6e+&G_-6cAmlIagB4b*h!fkRI?=-*pc$G5h{w<06rz$?kqbwHac9Pja5~_B&+fw5> zYF|W2X-Jt&9K%$(6O&k@fM*|Cb=cu)2rVviGeKa1{#eKK_n_!$65F+p92euTeGkBD zQOx|iMcelh>F1w;tMfqqk65On%?(S%fCN1B4S7;dA$?$~!gRKt{cj8S)n=khl*4yh z;&SBR>Feag3Wt&f}fb{*2%7B4$uE+2PlmDAxy4#Dc=;q9mluK)IFLD%5)A z6aTAX67xy-FKtPKk8dA;#8_2rrqt<&Wbfvh2s?Ht$sB@+d%Elv+EK6cjMHuuSH2{% zOFutY;_ONq2#5>UVI!%T2v7D5R(YqBPb=<-Ue0d)R-**!xE8dVZEmQhc0K)Or1Nq>Ow%;l67OEpmrR+?1e@YQe z(mCSt98%h9b9_ucwdQCMk{yybsr~*f*|p}e{Ztt8pI1FZB9+NiPw6fu@;t0jM|#_l z4(R~0ke!^H5pM1ob9A`p%0N>~B$b<$K5}8huc&{4OdB$0mc0_I?3sq(H76!(L$3bZ zD?ch2$LtcDxC7$Nw z{J;3pSpQ#N8UY+19~`5SvxBLdiJ3DowWF!|f7x1kW(GDU24=3*duC8_78WKZ4rV4M zZgx&4RyrmYDkdf>8aPII2U9U4S2JR2F&-AC|KE{RX%A$>Tn_ zyE{qrLz4G9Y3l=KK0R?Q7ql*2my^9i^_EMqba3Jg8`9}rj_lL$Pd?N)A81+D9_9&m zqJ=P!Z{s1BVYV=Gwnn-oS&YO1#t4pEcAR=IGzO?YM}qk_Lf@PoL(pluzHRcNJ{S)e zf|M_3JhW^D^F~C2!D^MxRi{4TI%P@97!X#BzI>W`>f_z?@7@7rQ=Kf=)>HZ9?gC}k z3M@?0)2%kVFF?Sf*%355?lR+)TH2-aChxpL=-H_wK+l?&u01==iMPSrLebiXZ3XzxcTxFu~sYNpdV621C?3( zSwL#1!4s_IvMwz0G%wcVpjp1MG&Crp_FgOi9km8ixDmd(_i3~+(fHHYPlJu=v>1YX zH|i|gAF-^_h4xNC-Ny^Oy)m)d+un+<{G%D)KbFPyXwqe2tm-{7LG2q|3riM74S>z}zS2 zq3&(ucL@dDf}|VIN&e{2gZ8O)!C%h7nljfZykgggc8}=%%jNk)-npc_wvU|BAgthv z?Z7c@x4O;3@Tx)a-EOV}=8>BD_u4AH0{Dn0l;r{guMJn-6k!zJw z+Qhg!pJ#xw^=9ktIn`$f5uUSKhhHaA_2ok?zy9`_Dw~!6eC^@)ii+B3Clykc#p}2a z=n{R<@qWv91FuGdFCqpXXX?#c9vXy?;$37TdJD6h^KV7vPm_rTZlHbr@=^Dyk=R>G z4hD0hI8=qvKrbIt&E7C>4Qxx-BuAdl{%$m4l}3T7LNTmt#u4T+h{j1suFpG~IQt!X zS7tw)*Mi+|V?rx9G_s}<_Mv14pSbgkR4equk#*l-h)HxQT!Eo9qd5Y$OcLn}qJNNC z9Jq2`8Ew9^2aI0`aH`#bme?vf(=?={D160Raqyat8}$f6Qg#z9Dlq|t&|lR>=>6pn*2Lh} z4)Vt9$DSH)G04B7OZCpsOGJXyh~2LSwjlgBPiIPw?DkQAo=ErhLuN!DS95zLb)EV% zEP$0KIX zbx)u7T*VX}L+bgT5gTXe4tq_QE4XSl?xB%Is+=4Lm)uvTq$O=IM;!L3SVnLu2M@~3 zml1h_ak(z~^ltug3^IQM<(@a=03xga=69$&?+VZ2PgJUsybI2E59FIec(3(=oxX*N z*@@2qDjIjG>L8!iAc?Y@gE-`>9!nXe&XZs8B!C9Jla>+Fg0JT?MgT~t-_48H6^a-7f)^1f2XXD z~gG{mC%BsG9$yn-&6ur;YvaH%=v@_4z1X*cR7%COHa5#FH z)ed*24NUCo1yT;XZCYKuM~W!u^Nn~4?%hMj_*+^Rd*DJ@mtVuuV@#(uh@9Am&C#*F zhL0aFx%0X8F|{A>oi6#%tOAtO9i}Nj?1T&RU%AK&5Qq#bep( z*gt6VCe61yJw4m>=Y@bw^q_LFk~C%SEg`sOXmaDGOGbUSs_>#!!=mh@6!M1WB$^6) zVk2UC-xtT!In;A+RJI8hCK_&6U+I|BY{eG$(k00@U;*UPd}yd29FdhBCh7V;av?LY zm9R_V8i3fQRv2B%yLR+(NcA*tYO8{^EiH(V{ch-)F1Lmr?XH8a?5`OZC{n{o|ZqsS5Z zLMsuF3hgUl9`iO;z`P8Epjv`!l;~3AxL>GyI`r04|e`4_g%q2B=Ys`IZP_^xfuZK&4wEN+H?r_4%>#v>YRoiv-Deo*M z4kh)0Uo82h=V!Q`%1Xah93gJyehKfqOUG4@Z;aPpt}vFY73V!KXA&d*S_zP4)s_CR zSOR3_emf80nepgPkbS(WMRm_y@$&-lQ0v~qrOHm|83h*%-~JOc4^M(H=l!9QhIcy5 z_79t@lE_zWZZfM_@uY0D=)mF9XMSoZj(e}wESvWH^GRn>o+sK-j*hmY)z*GLOoE%My9$ZYH+kET3y#vT}wmTMB5mxhSorv znyQ;<7@-ZI|9|9U3(vn83)g`D7h})8(6cpm5XzwU*qfSiknsE+^`}zFqg;^5;Z<(8 z1xEyjqD0n3-*u>xWJ=jWIfC1~_Lt7f(&MeIq!Z(^dQhj`Tsk``dbCTX+PRR1gC?iGx xC>!}`yQUub<8$;Z_{!pL!Pa*95$ow3@iV2#daRPXaCNx4rVjAjIWs#n@IU{Q*jQ$VawL zD5kWEZ?p`6kO~xOZZp7aK1w;vZTRUP$f93s(xq(6G}7& zV=5(`BTbz!{VOZW5IC}imfAhTr1E!MfVW?MxK&8c3cIF3k@KhZZQ^PwuN#w2wNx$L ztOe-NTP_wkAqN*gg|&9Y^1=S|*m_mL*bu1nSNhwzW8ey4kygOg z8%&mtAwt6BtAP?Iqm`k?iDsAz)o_>!#pWQ3a|-%gR$t(w{NzPuSmx%_xJ{96D+ZML zMXeF*Da=I@8SNnmbm)?6FTP_p9@3k@+n5h|Lp$KPYm#2f* zFGPdrIQ;|>y4}r!ewd}^n*L!W<>ItwDWzt@C`zYDD^x)rjQi$@=)jVb$q9u;6nzd; zZ_1?MtAsvhfyzr?P4?$!U^tvh#sC_OAiV}5e{jt^_x1-xsDy&v6a`z5_a}Dy;^sfw zAE8_KLf=Q=8Zs`?esb%<$xx?9;mdJ&VI_;a-ad{@loDfzXGcaTiJ}Fcbx?yG|NF6< zl98>IDTnHDVT*T>kyX$V!%8cda46dc z;>)T=1qs6JE06z8asdWltQE&*93ve+(;6{OM`76JaP*da&ZH8t;lfP;nBX71eSX6WPKA9+*yZ_q~%Lb z4P!QUgMDOaDEM*;=UdyK4JT&44gM=p0h53oJ(i;$(Cq5Kg2g!Zy`_!`6am7yN42@14^+k z-?!b04qW}2aXQ&sDW{>mi>d@XP8Ia;K)g*4LT=889Mo`U$Iol^MOx&UHeU?(C|34<^9j`j$+$vEtDX*`ov}DMm0n(AhoByz2q$xcMG zsGum1+)bJaiQ#v`N9hYM+w$e4YY$n#$M|`2%&%07EluO@n&#~Scq=AZcNek_up$tG zB+r(LU&F}IBwF%X5|wTW`>DV?tQP)Oowf|Pj(`sH_bGnCO;ig{oVX&B1h`#bDU{X0+5b1D$aSM;|rd@^b~Bq6)ZY{%O7PovYvE z)kePog@HiGXL*chd09TpZ}eHCd&WEA2GIV|1-4jSw82Ix1pThX4rJeytPPd?CC~Ts ztL>|K1e{}5XxMdS=H+RB8<|vVz_jU0q*S)A!Bs)RYCBWkmIs;rx%{qdn|EmZQih4K#n@6jV66eNbtFtOgbZFFe_KsVhrA?7bXde%W*9+oSXIP^CYwIN)bcBcu z((nlsG^l|4%9p9ckcZtednX+Q9AI%E+2Q`gl|&-hO%WVD{H9fJ&(=7}}T%yYl4C3r_ z)rq_e0_4GNTr&*Y@4iT@njP^QEQK}<)wmM}`rNP($P&zsThYm~WI(AF{OO&{FPfEg zkCcnQY2PDr(0-I4y1^%5R3A;^>Ofqy1OmEDj%d5V^^1RJ@2wpETCH&?@B_Y@RsFMX zY8yl8?%ARsXE{~qY9dVca3Zbh0saZmp_>rS%%&^jUa6;ONeRbhi7EIspHK1(B zaOMtXu5K>o#`gcGax}4lV`c|10sa&Jn`vTWX8#}4G=-z@c))Sb-_sw*QhOX>Sg4hc z+%aU&ID~m+?Ai;uB{15&50gS(L&oV2^tI$#EXj}$ynaIRWa7q0I{6TNa~sfP{=CCX zOUxkCCztM@U%LMDurPCHgDkmIWnxjO&CfGU!rARi|y3!OBCt^@f`)b~H`kTbnUZrs2(1m)d^El8}Bu}I6)-h92 zeHz)R|Ks!W-;f&z0sV$jI@wAcmNL6{vLs@X(1=%cF)0w*KtyyToZ#(cB3TKg}#QL>dI7iX?<*Rn~`*h zTv@>Wh}H;bGg(yCsdFjFnZ?F?e@wh1l{qbx6~I)!eTLQB`kJ-UIK^>s#D+o2lxGRiI}s z@^AcYIQQ3I5tl5FI8TF+%On=lL3k2n0jvlw3jksL!ej;HfsexzC5uBg6ZOUtof^j#xaysZ1ZUcH(jgZ8&#A!R%e4?re7iGct08A2mxa2sVVbwdS^YVPJ~=^CiQP%fa!Kb{dttQ>RO15MyX5wvBb0gcC9JJ> zIXJ;&I2errw0nq^kP5m_Mo${XtCTTmNMyYYk%^>&&pryEDFIC;QctaRIKtjy9CU{E zft0Gmmz8T-Y6NV7+0bkGk$eIuR3b{%@+c&cEZGEZr}S}45=kX37IsI(qmS}txz{GZ z_Vgw;aqV(n%mi@xZPZN^%^rm{_eL7rA!KN2<%ij2=t@wK1p^y<7k>~aImG4O`c=(9 zEH*uIj(F|AEY4bCgmQC$5F+iqvS&m5Uu;g^Nxv__;R_(dU9|5B*Q*G zTIyRm!$6D;>PyonMKdQ$4qXNz4VkJ@7hT?7WEw|VD5~wK+yVo1OQ*u9eJ$Yng{`5j zYOov;ix0}aePNC$Cgx~Ee3BRhf(qm6KyzZ_)Y&zAvpD>qyFKjmP)GH3w~X!)OVddg zKCc23Zs4W?s1R1j$dgLOr_FH}q1-Pctt12OCvZJkXnf-2q?`uS^Q&ikIq!PLb{ z@3Uk52$4@s_@5Kd-|^h0%ES$Nlr04rf$vY8L11inmd8oqCCBKZQ}PwZ;+XS4XFgWb zlISRo z37iZYb82=U_(H6#kez6IHV_MK8F{w)RptV+hzLcV+XXd&9|)vOw6Zsc$l$c0TA-`U zGwZGgB1;3bMC{@#Xoq}Fkhw}*AxY24H<5A9bS^;4yu5pxo%!KASglhpP^c3|S3-gd z-&mbvsgf=Bq2+`SbOcZc%SM8w%ZdDYn)WKb*ai%POkKEGFWD)n#%g9}{GA*G+Fw5;*`I#69hnOD>#Wk zbM3UU-`)5)IJxNC<2N zy^#O~szgJ|B(H*(e6epEg69`VX#Hb|-YcPxrR0R~n`;}-gbz^s<6gz?_Gfl$?6jHm zkHJ;1h$@;Uw&}|5Ibnj{ z=v=yPfN(%4+F_)Wq_%n>>y4g2VQIdQ;CZjW*tj`vs;{50S(>5Vc+2elqNL(}z_2JR z@C=esBZTqx6&Eqlq*#%wZ*a~KqfFeeo3KVmiu>)GnN@;kgmqp)z=At*0SdVpzl7uh z8UkXn5E)br%W6xLPOoElk%1<)W7iN@N`WRhfLV+2n{nS#rj%Gdc93U1U;g&xu3(iP zVv~wpPWP*AR9=hc8*6NdncWmiToa54=(Min+pPW&cm)!00ds5a;N`B8moxfn(~~*H zw;EUO@djGsMH=K{u%sccSnnA;*jOv$_ia#fTAqc;M5_{`f_vXR7=4r3db)WEYWH|2 zsiTj14ys8fR~Z|~Z)WmRV~hz3&DUkM#{kGE3P$5~LTCjb--nb?t$-6ufQ0or@R6Jp zI~SXW3%=;0=V@S^{RXD`>yf2O$exP70^-p@@Mg^A-f(<3jWhNq1utB$U+h&VI1p(q z>-;gZGT@!dZw@|%1~J8Wl4TaQH8e&r zH(^5c!DPxp?b90Z?fOQfY-J)!^Z#Slxc-0a8Y?^N|Jb!F9bLzbVKl#&nq6IL!20#q ze9Ln_^*l+)M(fGnD{%Tb4n=Ym;Z5?PyXNt8WJw~V(?-@=UztBzmlI1mLD8Ql^%WXqJKMiHmUO7)?|-Uch&|^t zhK{N)HEdaR6>41MyHBTF6e|SMIGjRAWP|%f8&nGj;Q_uhVq%pRRq*?~=t6szC_+gXps5&o% z*7Wv5pM#HWoJ(+3`8J2iQZDO&zzPjElSO6>f@pPWIz+o*i1#mo3M^O1fJS8nqXaV^n7kB| ztPkp!)$5eALJvw;F*xQl|0$rm`03ak4*nK(stFMZ%;H|$Bu_z46wv9Cb&LqsUYVTrT#XU+XP{j&K8Ucn43el3*SENNrC|2#~6aOGndiaQe}s+rN} z8JfZ{$YUE)#1ulXFu503(ZilaE-y=Zb5%A>BTCqvnJHM7ksB14ld^ic$2qhji&cd- z0TlL83&Yio4cHQsNta-SNWOJ`Cg#!g1Qt6wa(2MEROUXJ8oTPc`-1XkY$QSG$yxvz z1zAYvjp;Ddu*wZ7qA?|8kV4>aci!J!3o_wSSf$F9oQoU3gF|GDtP~!5>XkxjA3%2W z{vyCW#4DA^Ec3)q#yVNGm)B&jyH+PgcrC3vGtDKMk|hhM?;D}9WUg&*q1>ZsBT`58 zu`wnt^(JLG4c?5m+f__?c98Hmerp09vgIr3h1}_nIe0TZWkd^dX8sCBrwD^&h@;_A zz*!i8z`=x=yU(H$gaw${iHXcsXnR1(v$=9tD5T`b@s1$5+rmrNXJ>A!8riNtER53U3>vpodgJsT&lK{e#7Y`! z3rXy6hUW)N)+s6Whs)2_Ilcpl&C%jZN-tcCKM_nzjHBUs4+QqYKzkXa|Bf&p<4+bu zB;B5g8C0@OUv&u%G7xir*g#qkH)MIVIJ@ie26;Twb}Bo5y<23Pg5|`d2thd9+0uT5 ziuX@5`u|iq{sc?ATu2M5eZ}m2T$`9%bt^Pg-E{j!`AebJxSQr#Z>s}82CCcJUwGXY zury{gi>gS$Q9{`EkWE=g`al4xnZI+b_sH#ct?c*GjDjl|Hu^{M^|28!r1k<1Q2Om} zczk8uORqQQ8Jw=O;!o5_A@5k=AKI;70LP5BWGj<5Q5W-q3Klm8Z^fOe@}UT-<8=sqf$w9Nt&%AAzl4ys%b}W z4-zdp4m=MeUT9_Ws=d@Mw?DN;N}#v%dm-&*?X@kA%}3M2;Q!u+Vz7$t?XAZy#z%TH zMd+|PhT-FhCp*InUld9I)Q(a`jb<5c4=jQat}rzJ@|63+dM(d}kI znuF>*yW<+B8UA?OCfxWqWi{rn0;JKBHpIXh60n8sW}#D-{gV&X1sC#VN8@q#&brS9 zh(!YXvT>%XmbbJnQd;Rr!g#^y(&3 zGQ)e3GV25X#l2|2MyL4mkrr59?+=aN-t8AR56B$-7#I;NX-D&=xX*Us^_C3f7#S-n z%5Uoh0uo!47Kl6TcSP6^|1`WPhLpIR7yHMN^byARpfm-BmAcn&z$sara+JpMZkHyC zipGpl6T?ySi2QLjA2@`A^E%0R4r;DpNM0$BGo$mEOoha?;{0=^SXSeRK< zWXVO$Y;fwvEP+wPA$H^e_KA}wD;Do9s?JN;e27T!!veSH5*KPPluE;{+6Yf3#AQDh zY%v824)VDqMf_<=-t3kZ^Fu`8L&Y86ULz20BsT`>wrjm6Y>+&h5gL(GV|6fYvo$#X z>(jB0a1sZt@6Xe1+SO`oaMqd`q@Lx|42it@N6hkf>`fhIWMf;T-_9}-lj@hG5qGRw ze5o3P0`7j=agXpDsGxjz5TrxPsPzwQIv}kD_j()VpTMtJ>r448G8X3|_BmL8lP=-T zIi1ys)WYxu`;*FGUs79jf;ezkowc6R2KH4j{6BakG1kumv`J?Lg;$Yd_4t;`iCrAA4^b+w8~`H z>!SNx3BPIXJg)cmdSQ=WF*&dE`4icAaqj4d#&U z7R%aY(vCIIsiMh1v?#8TIg5`adW_xM4Rv$Rjg_`T7{<~ zAdVfvU)F|sCcE^{=dZ}I)1Pzb86luO$1v^nI2L|Rwx?a)l~+XYJ3BD7O76RH}1(tpnS9Pj;n(9V>k(B($_KTdYFc4rR#7dC( ze6G(I%CnMo$gd7u7+A0lM5JP`q4|*9paz#_-lpoT*+Az<&~m+Vg*mpX?UiPt*fBaX z%Ar}^)l??C6ni2pE_45ZbbM-F1}C_{k~ItzjL@Q>(Qb)E#%h}Utt$Q2QS3xZuV7E@ zR!Q`tCG6YF4^bfmj9$ctG-x2-jg=W9LU5WfM?tzZ$F1$GUdRyvMvU)nsDZ% zP2b5f-gXiM=6@p5MhTFZ2TJJ!8r|ieE|K;m%{QV9>fd0 z4dDXwlZHAC?i&*Z?&AspENG7~7oY`#ag5*;*e(jr!bA!j$9t^-AeeGVbq z1EahRFoXe#xD9|P`bK{}i9~^c;1cPR@&_Npfg}C&aBIZbe_X-U2SO|o8IcD&2m*vo zR~~8@@!Z0=`;D(bfByY2)a94I`MR?EZVM*IQ=;7;PdLAh&!5a6&E%h^pC50@bAjvY9_Q*Fm>*=Md;fOmPvd;Nb?68} zBmyokF{2-O_MlJpIUW?r(zp>|k&YA!&`T=WX!`nxN2;`iXOU>X6j?k_|NFeC=fWT9 z1}Q}Nac_Ip&;!Yzh>Gmd5Zmjr*WuKA2v5Ii2L*y({YS103VeV77?W3<&IJ-IYGl>RIV=1cezS0;AB&3=1+Z)Wa*{nK@56{d#SoINGjv z%rJL-C`v`q7Z8-bV`;r`Ar$~9q_9YQjHPlewklxkFdG&;uV>zwY!KnO=|SkP^Rr}c zp9A!=3vv8Z+e;SN2Bms?9V=Ub1a3!|X1Ld(TcK;Nd0n#;l8I_P>GzY4N&`LCrT1SK z>2LHwS3GynVreO?pVAZ&%X>!+m*PmCu8ox~@t@JJd>E47EtZN3J1Q8RZN}X{;b}~N z1f`1+%-blkeFU&tRqW|5w`4uyrV~?9KZ5t4*q~+JT#vta;Y%aymlCyssb-Wjc!-b{ zss~QRS&9rL*fE540wAyM{WAF)o@(5thByq#0>by}7_q=&VswN1r5dBS?_wSCkvmXA z@ZShwO(D#YQ!SZ;rWmuHvhs3;`lN@VsLYPR;Y&)|kE#)32?cz()<{HKBzQ;ifgdO? zh4W*!J5hcN|8=oiXfMpbMyaJI2Bix;$k#X}yS)88!}%sdmYs4EIbN#UQ%IEKp}wf)TA6+L z2mJ^~Lx+A3WSM5z+;Sbn&2MIeP+nWXKiM~(Dojx)J$rOGhhF&-vAnuWd_c7mQc zLyj9!fpz6`bTS)%yazG#GuoIXaksYn;;a4Z2RGNg8^>zXZ#-#85^EA_@8?AjOasn3 z!VURK5dpVk@OZQKdOk#hUqhy)(&@?dZ{nZ3)S_Fz2%|m|^|F4~1BK1%iNvDa>@(i2W>73^3 z>+FwM;DAju@_#)-PMTfLdeLL4%v5#PCh#5K*T4rMp+t~>#Xd?wf0V1J z)NlB6paQJbii}CXa58J2`tjVj^zuEpAL@K35B(gd7jgzI@a<6--xoIag{ zE4D$AjaIPe4x@+P@#cbfIBP6NF&7zTd&;^vaK77Hpevw96)3OjRPyq+74gJBZ7{^e zv&;0PqJ)GFmT!)1<8z2w? zMg12zI!fK0q80L0iB5@7NXwOBs&lMLip*&DhSSHp+-LAI6|0tER<9ozl|^+-vYz)I z@S5}}Tk{PXR6#29f_cW<1TiCV)rDjM1n(At?_N7gaXXN@RPtT)?42jom^tc_y&&WL zM-jYJaMoheMtQTTC%{$USrI)9GFq7h7^){Hl`ek09zZ{<RR0*tr6f;bJ4^Wu49U1& z9u^mMwYV9vs+sHl8p}-;4$Fks8XHy_$?q^rp{Ue{(4jX(_8IH27YECFi48rh*|@E6 zfHm`*nua9hzGP7ky*_e0v|cM^ut3&ScllK!#-I7=QeKW~>t;Kr-q!{ zdO20n@Q%_+s!L?q3Sgi7!#n5Xi%Z6O|AD!^boNy9@(PDTy0IJ!81u}saj)Z@ zBfmjDpgUbf*CtLQF*_3lzUEX?hI+z#cikv3@08H*FDH>yl(HW}YO4gwAfJbDEpT$s z6sDjadBLsdgC(djVyJ7d)P{CO!?`Y&s!RY2(HWeZ9)X~T5?-*6X1HZKl%HI%qg~tD zSSHiVXchn#r<@jpn5z5)tlbdaVJa_@i+T0A7)%QjfQ$C$yN0x{Riz(Oobln?zD zdrRiN7}mL$3eK8$>Qt}Oa2 z+8ktn@4yv7TSb)6=W^JK=+R8DbZ=W!HWslmu#`^cT3^P1VakKezi55A*6r+*iKKh~ ziA;DSUg+GV_FyrrGbHs$N@o8?)tHS%|o`YO)wV zVZF)2WlFbu800TYAT`(NpTdVW)u*m)7EBomK(q08Hv|KLH&DWF!p%6+Y3Ru8BM^uf zgq;QL@?t*V?6?ulVW}Ivu(H zs#$>Y%pw~ce{m>Frd1@YTK9-*mPYYnr^M(o!?QZJcz0Nf(HgihF;#E1uIiPX|2EqJ0wdX3+YieK$ zjJ}UZbTCj`K#=*LwWIC4J#nw5Y=vAdDa(^jVms&A-4*W-Mc?}$V+lL7uVaFy)#J56 z+_FXPOepYz7&D4UBY{4XU+oEe?7|H~m%R zY=JL{Cf=(`Bdh5hV1Icp3nzCzzadvaGq7a(Y;cbSQpuniq=bE36iZee!6ce=y<2KiwD?qNp8g# zo^g!eRq%stXs+hlxw8V8fEcxEb32&Nse1M(ks1`!wO; zUEuuA6Y(2iD-guUtBm_D^zVd4qZ=-2ttlpE{|z7_qi1F zQ+LSL(b=pc1e*sdndwpW5U&qPMESb1!^=n;A~C6eIs|U}Y1@9T_`b=abHNGgPK4-#!>KVSAzTsv=9-_P$+ng-wm-2O|B|Dpn zMd)vW(}`|uqN5Q~pf7^w-2s((k_rOU;gj~Ikh{nkyYX9V+uTD)P`OkIIrQj0;*!9L z2%DbIprnQvA-i`tw2jkI+XR~8<-_n1eaMX?tRA=sXRvK|We2j&d#VxKmcjElSg;Py zu+-bgY^tAnkWaHC#&S(zP;CCDT(te|v8&P&pFIosc`MixYBVqkhcFR~jGF^msSPPA*ZcJ!9~$N#*ds@__ndsE8H$B z%nqxCFYM7KZkv$g^}lotFpyQpZg>^9&~jk;SG8${a~df8`sarPhjrV2jZnLM6d;JSB2E%Scts7ORserq*LSo$2FpeCByaCZK?#d)WPW z5))}^iIj|rZW4VYJ^adTaHZbXY3+6=IQj$U-)id&DBISY4vUPysD~Vg_B?nW=7z?m zVz2pwkxS;G6^UTTZ(f1=-tc^$HQ4@ZnyxVl&LfP@g6;HU^HN^1*5y*fWNo_1b)2uL zXOts?t}z?ak&?*Wt3whm9qSagj*6~2eKN+Ni(aYZ^Ilmi4R91=XDJ0oWm_ZxEaxz@ zUgS6mo=)ZY1ky-9>&Z5tl${A7!j236tj3kX-uG(ES+8$}AW^`GpT(8<4HQvLZuGV> z7WJB|Q0N(fV&}sTsVlu*xj#p8<>N9ykj6#w_!?VYH`s7D!ku7=0L~icwVk&OHG00} zzOt$_yg>?q_Jt-$9;+!1gm7wrr{kM~7lU>0m$J)Cnf)ub9dUegvbi3LvvuMtg6;KM z0o6-<)OHjb0UwZHqz|^f`KodD!gHTL|5Umm|7~ahYdhadhj>{O|8IHMd1?YW%>I~{ zZKgL%bN%(ztB6>D+4iGM*H8(Hn7>+}Y=3+|!>T#8VA7E#25Wl!IM|7*NuvRY_R2@z zu1aLmkx|XYmPsq5cE)m*AZyz?__3CiN_Fms8i>S-QwN2^gqhA9r4>Zxth1V#O9p7QtEy7JH&o2O-ScYFIvuev)2 zW9vWJ53N9ME|cb0@KH zwVpftOnPs@2}MVZC0u~1uYXu$tU87ei5`c z*+Qki7i&ivLgrJEp7F!XBFtqH=F)QY&)K+}6e}U<`PoX<>buk0p9;*=hYvxUiJ0g4gYuY^<|V`^(vlnNt_Xj+ z!I=pwFXsvej6z+{H5^WV?7DTustq7(70if);Wy$lG{!e6YZ@Jgo6N8z=!sPO*|p%h zD|UBqiK;m+>)PP)7HLk613yKx@U?$sSPolGaKKD66Txk(ye;(G+0RhEpNS$7W(B%> z;CAI;%niO%FdR_Sxgc4ebhGj^tEK6__E1Yenu5i7cuWSEfS z>)#q0KTT?`rFTPf%uGpKoxouwDVDj&XKEwDs1UQmOo5!~(UW}ygg_!sJDndV3A`j| zMrzfQF^vNiml+gajhaD7)EU#tVt}`_zjU@BUf6ss)W$0n4P#gHw3aEL!#qj@%s9>? z%u%Bxnz@Px*#P<|cBwf+6o%wdHV(QAI=VwINy{f@E$IVNpg-4Ne_9c*_*L|^0>(QfQA#*Y zDD53;AQYnMFRK+RcKQzACOn1^cv791uVjN?D<6XRO(GUTq96ZRg_U_lDX(egz<1EfX6mW#+Pff;| zD2^+v5*~?AIZTLXgy*<8oeWcIW}4=Oi={qA^BmLPH#5GK%zwqR|H{p*wtoI;`38OK z(=|MV-t7K7Z~ik@E(L_6_|Y)O8q-E^P+Hm7x-1X2DtT_2POD_+0mShsww6moX{A$S zydjL#zD!6q`qli2ovDwUe;?sAKlR}3YO_gPeN0Jf2W4>LC-eUNN{$5$1l7s2j#iyl z2R)lOxXEz7AtjY|-~!<3Zp&@E+x#8SCCOjG;Zv-B@^JN8@C1%;+T9K*Fsm^Rwj^Pc zf3=7&E8VOa$}N@oR#*jOZa@CoZbj;;Dz&9mTw#nbn}2HY@{)NpKj*&mrfU1{=LL{v z;cO>6YR4uX+Qj`yFx@>!^IV4>k%|$8X8xMs6BG#Otj6FtiPcq~i&#-TpO@_lTa_%- zoEJzQ|0jqci~#h~#pyQ>P&B6V6?@Jlm>%}ar;0I;xOl|mMhna7)xTLQo3EaigC8m{ zUN*8T_>;W&_rBn@tFCg*MLYHNFlafZ3AN2Fqe)7q2*qi;ICuUy^6kI)j@Y$*5OHaw zntlJ9+XaEs@U0But(+M*y%Zl&S1Dvdee}&H^i*>|_czeRomIC6)+$NMX~h}-yebB} zd+_}FdouU@62-}?-e({{6C+$#D(+G`64}#i!-u(ZR!Kws?-6;O>M@LG%iH{Cl2nfK zltwyJp_`27{9cnr+ZuCHVF6ZxZaB}$miwkpMBD=P7J^$q?ZUS5vFecG(^;vSL2dtH z#wDc0(*m&KxJ+bffwZHO&D8y)IHq7xIJ5IMQ}I7skUdoYuuxM&0efR2>s=5@Xgd$1 z1uvkEVGO<(_p~LI=fu{u){sp-D#gslu4aATRM$)nuIrsF<3`bcPtj+Sd=T^ZO5sH! zf#5hfK0ck2`q5X_R--GMu_nlIti6t(<x-umLKze-9bo^3LUIKq{_r=nrl%K5N$xl$+k1m$=ZEOs zJSYBtgMR-P^JDw}EF3ZenAuqVAK=FVVCUlE`d|3(|0RJ?RsaqzcIN*_IYnq(7$luDk(@R#idkTFg|tJ z-ZyPOJ?kRJ^TFa1rQGQT}HBH^!)!(QGvxid`rUlaZBPO(Ua1gpPf;I0iA~;^O=y~z&QPL zVX{eQA!0*J`F5Fh6~~3Z!)ZT}*-=3lXD3kuzOIq;r09qT31EXv z{e#biRPFimiE(2;5tly@TR}fvxrJ(BUJcK_#eU?1g}&iJg$k%N*&xnhgm^%%P#K)^ z3qo^Yrr|xnVTAkrfMCQ7S{THH`=G+DLYFZ9hLT|*?8z|!C}0DEpS4N|U@-%cMyL#e z+>zgMqOBJ0WOA5C=Wvqywf=c0s-i}_O8s5lQQy|ptY}9Ok8j?VaYFr3K8V+rDbQGOng8|!BV}d5_8f#-u@;pdEkRiwfoz{?=${L6ySpbr5(NRz z5V%f)!Ti~`;J1Aue7i#U!vxnS4|%b`YY-zQlu-YD|KCo~5NNkImk_L*-!HkdK!kpH zD@c-2WCVz>&re%(c_nOw5VyN;&QHxKarG(pMuf%SZ>8@vRdL88$Vb#)Sm1C`(t-X) z@xg4j6vlfmz!|=u_JE$XpL$$j6rjQj5l&OWGu7@4nxHmH^^GG1A+Wgb$I=19|A)@l zp9BUM>F}rJ`zC-)Sg9ZD^@k6#N8}s0|C4b9T>1g#Neyfb9i`>{aPI!xiRz&;Yy(js zggXvk1`6UxqG9fP3Q})((5sNch&T0rHY#F*P(sCkIA=mA?MzxC5M*~7vAs5c&Rr%_ z2&D5@T{)mfkkSBTKrmiGZFn9sp$G=dqoF|mrEm@`G8SEdWsg1zoiU1Y&-#ZeGG+9- z;7mbmaG{Z)rHY&i988}PU>hWm42D-aA32?=lc{xuaSB{qJe~@l7(#0I61q{+7(@_{ zo*EH|A&%Z26!_H${+)n#9@~c!`GW>oaJ%ziIDj1H-B;j028*G_v06sa`cx~Ev8DRQ zTq@R%_UX1c{Z^^ZS4OYpJ$%Zf(^}&=`I{pL7P`M|(9i zvreIV;wOxmB(vr6<|g%|wn%iNu}1Nxle8|U_lOh1TUf8HAEk7oRyIvGv)E=41BzsqI* z8ERmeOk=FxHXx5*>^YBRuALy`G+;CU6BXR;*j1@A+b}oLoU#n`vWLMFbd3F^8^2W< z#rJZ2i8=?hw-t1=;C7OA{|~m#sXY^5U9fS|v2EM7?R0G0<`>(xZQHhObjP+cz0b^? zb1`#Qzo4FaYt>q1ipm^Hgx#mebCjib`^N)@_PrB6Qw^^s^2J4W`=#blt9kXpRSfMt z~Fr*{s$*QF(n3qwN9G)@QL+l4dnTMDuw zLx%K71`{W+KUCm|SPFmua>2{J%vdnhj7o5Wtk~_gvoZ>qz&Y7N(^7^7bs^PB5eh0J zKZHY>36%Baw-xrBrkjFoJH-$|yr!{#LP>*5vB3KZ#wvRwSl~5bzJ}3?1K{pdcGquZ zqmVIb&G0|}HL{NIAuIum*OcWkbGVP-t#7z7|7CF0Y}s(g*~%%hp$DiO)KjJlTzhf~ zF4Wsj%shppcytia9Ib$uc;mUMgIZ%!AZBaycY&j9**!wMHrYgc4Yk1}h>2ORks4GuSdF zGEHYc!r}$B1&0F4P9+%T{aUN*kS-*Om{;VPWk@79yHVe-_N-U%wH-CHDsK8*q&d!_ z9x>3k3-t8Nc7aOE7H2vo8IJ7dhKsD-oS7S&Yc+AF!3MEw*}%pJN$>Axpe-rLOzmj# zycu=F&iT=^Gvd((`+8&@c{&q;6^>xL|78KVZ#HUx94`P3Nm{^T76cp!XNz|sl!JRQ z1j7?y_UjxR#&wUn_;`m5DM2X)2kNi_5D-G0#4jH2I7ZQ=%b z?g7y@vg6y~5=R@@D*SF{3=rB^6CwhB6Lc>T^EexSU~W!<9`|NDTbA{k9ei$E{PcvF z;vKCzW@!O0A_V7E5$5lwg|LK|RuJ8uFod0QXbX*_6L*Or8y|mUmdN_{w;8w3m#@0> z(XX?Bx9r;Y!9R@q;6qmqL<1@nEtOT07Ph2z)iM7tH@F(fONG8@V+3iPdhpQmv(H)m z(!5o|j6#~BtMaKlkId8uhPz9B;}cTQ5AeNrG)V<0hMR;Jx8MA8-sOJTb;EQmi!}lZ z^ z-faO49y<_79Ej@u{qr}>A+idLRu#ca9QBP(bo`)6p% zr$y$9s7fKlqDr_wA&CXIW~uKE_{{0`(RcwzCwBJZzRR5`Dk~!Ae+O;@7Z?mQMbasP zc!pxnu>WljnltOe@D$ox-j+KR`4u!%8D1OyuKI;O$vTIWw(h-d$JjO zu5f681&WP;erjWE=UM~R=ABI(vW+2m)k5uCSAIB}Z%V=4xcH*=BH|IER7_Z4~1GItl66^DzNMa5b2@i=Bq{ zkLl~C;VYXeq4j|cSHIyGc8=-@dTEe zX!>?fg}FBbn{ehcSu;{<(QNDSwM+nvhGkA`_hhU+d^TJ8zKoH~GA;)s%}Q8g_%3nk z72axZ{hb5@3i#czdb$4X z)M00fuxI!(<}H$xw_Q0Jb@Z`__+#AC+a zz6ZujSz4c{dcZWZAc4{y8)MlOL}Z*!a`?XyXs2t*?X06A-?-Ii@4lZ=Tu9sONYkWO z{JM=m`DY29Uci(E_IxG{y@F(sJ~f!a6TQrZJ*&NUw?cjn5_dz6+u8vq9Xh1i#|^Oh z0(DBR^{JiIF;L8T!iZNU zW!%%`E}z=!HCCJFbEAL}TLnI+xp_(1_%|_Mm??9t58^z`8>pkzMdh`sN$cTT&7-}e zK$wU@Ag5AgPKO?uwdyP9uE!P0!fbTnE4gDsd7OaiE=wL`b_eb!nNrS7VdwHcCmfYg z(n<(QJBcnmdR|ucn<*+JIQZFaIH-=jECpcaV!jj2H+NcSDn|eXKhE&!nvBfxZ1L$~ zUT>aHR&1Fit_^II$2$!$770x;Cs&D`^9n|(4a=jG9vN#PvVd2N37R-2G?Qi=7!uwP z>bdf#a4`~NfeF?M#v5RY1|MKzHYBQxV$QWrtzCSEdS(Na@~7p!_sDL_0uuBu96kzX%0+r6nv|!k z1neeYUwfnt%IbcL<=14{V(sMXM2|v7aXmYz=Jj7z0Q&vGYa;uj&xPOQUvf3onL-)h zUl2D=mH4hRACn-iRK3y*u9R~G(NCM3^le-d;mRobM4bTb56=D1fAWO-tw!Y6ZdeXP z%F0M^1!u>13|f%|K5K-Er=Y}Kr#S_^D3lU&SUKgqCwuD7t1;~BV0XRuK91X!yiBS} zxIX^=E=_joImC$C&%z3;lKLRf##fz?rV*Opu40qCuFNhs3t!ecpa#QNXk59D9d`WZBc6f{FK zS=EHhIv#@Edb4Zts!Jvyb~S)TEM&jylgm1e>c=yg4Vp|~xwqPnl2`(EuxuKZOr+n7 zZbgn^((51U@I9<^Vu!+1mK>U}2*OJ@;=ZnxI*R}U<}6EJ3FjclMzmowW?k3l7KQ35 zhF6C6S!T>=kFy2{_yn)rr%> zodQ7Xf}yFmtgNKacr!1ehd_g$*Dn3{zY5iJP8;u--Gpy$n0IEY8^$w{dI`)Tj_2!1>&JCg6pLDC$y&^nE!|alqGMXF zce4cB6<5vz$_QoYG432JrE@HMt#o9vf$3(o_l9Z9FtxDWGG%A;+KONXX6jscG&F)+ z-2l}?8Aq_=z662jhN$<^W{>NJsQQ+}>k6tuKA@>YtK0 zL4=mx-Al{mA9|KdmuOz!5l}X`b(6I2XIlO)@MP3CM`@}*T24X#hS!x-SIdnkgj}1o zoErlvF6V3e-xECLep69ZFxjfST3bGGW$`f$4e}NvuPEO)mSn%h!w>xw-LC=FQWg9? z6=%2QTu-NLU9eXPk)L$Ae33UjS+u-ZficRC-ebP8n43M;LceuxnKxPjWPnLhcZkUt ze?Vtg;=Rrf5z&+evXMPH3K&OWl+Y~irmu{)4OC1mjktEe-jhTE2EY~UFWw@&Ggvg3 zIM(XSBR7Z%pj~ldUrc?UpQiztWcZ6AZhyMHbZp|=*u>iecaOU}=E1dZy(+HC>GyDc zigEmK``LL6t&AOw6v=~T8_e#%xKIM{6123Q2(@`z zVrXYQZR9ygtVIHo+S=O#WQ+b-(8N3)9$cnjx5AK4hH`zP6|Ap4uXKO1P@EFASkl=s z@i+c9bRliIP6en2?=057vU$2c;T=5SrKQs^ZDGG<ai9>(N6pU&^vi0jW{w|)T3$NCTUuVYv_3;Aa%j)JD(C;j5#YCcs z8Z$WIE|gHg$f8=|}P{LZvx z;^z5PL%(#qk(a_ZT@7!VFF$@pdy%}hs~tzVde-vw%zfADAF;No^XWw^m4=b>r+z%y zc*1oOosDiaCR+-iNWj#*`(w(|B!4hcGGAKLFO0>Ze4NWKVZXD{$pWX@!E?fOBkcF; z{%)7XKC2S5z;c}#VYI0b)lS`(+;z#W<^6CWpQ=0Qp?lkv?-DNXtP+@+P#F+>-4nWT zr7HGxu_qT#0x7kP6E(YL?(BAyBI_LI>sk&z>)vvm(3k{ZdE1f1y<=4WorD5~DY@H7 zKh8<_n)&#t?Xxk~;X32q^T>cQ9*(^<ddJa>*p#N?yRjKdrROGE(RvWc5~* z^Mf($fcV?VZ?Zt^Rgrh5aO!t(X4jz(!dju>Ep%DxP(q z8sORHPUC_t#aU@GgnQ`YS(iDOYS&m!m5Ct6UbS<7^2?=6m@0)Nv`tMoGJ z7m%Unb)Q%wvb+Rip8n4kx7u{$uMf@0>wJ1qyQ6p*DecDfd6(N|dUO8`gIsYLo0=JE z6kMLn$8d2B3a5&yYIb1x4Jh&Y?UYN2?G2iZ zF1%}sK}*i>A(eAZqXWKDL;|;4!$MLr_ZInbQ&dJV%WJ;IV+Pa1rKV9!<F(i@>1Z_hY?X;#tv6I8!`Q9%O3cSSE%SKL9*;jrS;XW_KWWl8ImF_kcOgX#>h zYajTD<0%CFr(!p-4Jl{3=ORL2jG3hlx5&@~u4%UHhT@PVf29@R_zlOgc z&|gFv^bTzT-^NEdTz-oq_L1ctb_c>65=kTL@K|g@&)6$=ssaBl&n+inC4I z}hS?OXWseR}JLVr{qKAJkk+o;0Jb zc-7MXYni@xocVNXA4s?~ZM#v`B8ye5t+nNAEEuceq^wM%jj^ebeJo5ly&}f82aF$U ziYGz0#?rB$EX*AI$%`@MG@Q{$Hxd@R1m*6|TVD>&q&V*n%gQoji5!O@|#QsKgS>q7lC zg1yVo;y2^u49tk?UG3LVAkpP1bACG-(Yhg%Tc6%UbQ3*MU-t{6IdK6He!SugQ*PYK z76r5S_=yrTtC?}E?h*=q!MpZBOjTDgk&Gy|fD&>Gji|yXq>;+}*n=$p;niXLs2q#N zr8j^H7H2w0E~ss^%F**G&?fnBLXR%i2Imr$(o!& zg<+$n>K6+xQ=AhgsLKIVG^*7vCXx%B{c<=f+d9YUJ(;s2cF7nkLP@DsOK1O!$gSXc zjOWpu&;@Y--S;Xr0~Dc&vW>l6*MFkMi4P%%uLXXO=K2ugnq3$B<$zKVelGCGCeK$L z)2+n1+@WcWY++EwXO8w_W5idFkB1khBZtbbSstDYg~#q4ZKW}f6Oy-w{#rOl~IS(YILRx-?#Qu|WwG_FsVZH)Q_PLZFT z)Gc?gtC*L>RVYf!6uD{4a6!FcfUPlIR0@U;!=m7gG4h1^O6!4BfjT?h#@iwMW7rHw zAQnY`8K(Yry~GYMosi^Yd{)M>UF$m0Zt!LG_DmCU=CoKr+UKtjRiQ>WEKTSQf(~1A zcy^#=)+LxTK2qt_d^l)CdU@SCl*0Ma^76&3X+Q%+FT#4i`CP1bz4#!YuX<-}TbEEu z-fQxJjDHF{$64l(t8}xM^=*D4h#bnL{tru||IhM2u{9R<|1V5q`EQYqnUI}{J*~kQ z7!8briJ9}i;F${~Yxd42J5r%2DYp`Sp*UWT7>Cyl878dwC@f16il}b{lyITA9HtPI zQc}56;fp*Xsa5!HuaxH;*Uj5cORxQm*4(A5 z75KMHjNqVueSLX;eLWNvMcFS{(6H|SDXy7(N>lX=lTs95F5fKULpQ9rZ zC`SnxVt^9;efOt70_+hqrqF_7GRN|-S1HW-pmq@e3kvC9Fj*bL)4g`4MXV!GAt7K~ zpfE0BBnzEjjKN=#AP!-mqnX_Py^yGPTbd_rpaQpL>_C!;k9979LI8Onksr7SE?&Yl zK4LHd>;VYp(7vJ|K{ZME-N-E{V(^lJ1Qc$}FknQan~0Hf82IG&;usOA+5}3_0qkd9 zgs0E|AG4Vd8{$Vw>C_xsCuIduo?6n~of0I7{L5276%+bAoTe*p{$_SpgwPie7{ETu z7@YK=fGn?vFI)6YduF$ZoqQQFjGW%r6YGhu- zfI>t>fdCU74gsE5NRT>27y6NXr~~sdt>U`>q)Lb-vto*>*9a%t^sCmd&NI{7$DvQ2Yu7LeV0FR zScmXIA776BQX4QqI54`TcASVmS61*}e3PAu6zORn0BtrV#BC2sBAxvoY7$sDKsDmi? z7cMW7<1e5!C-o9cus9(hKm^x7YMHpb5Bud2sJk-D-!TGs* z?VU&a`cU%x!uaiJAi!bV#@{i4fbaaik2jR>F+SWLMNX3AG-ZdhPw$@#Hh*E?g4kk| zB1wr2hqlPu(4jSH4qvd|$6c($PowW>bwUG>r`e0w%@mW}#%M_Aa^I3av&R=pQC7U( zkxA9&z}77(>V@Ztuons-3RlR{5WUMuu`f%0ms9#GUQ460gQNz9?YJJt04xi1uef~l zpCEMe*0Qu^wjiBKkvuimJr3LTitF(OhR`WfESl2HeagHm*+6bycgYiE3(@Jh?=nobTEyXC|+*tyF5=*;y^o-eS`W!bMp0~OZvGo_Rm>!zw3Z%!XtCK5^Z5;$#$3bA)f^m4;Iu(?^}Wu zRYiAs<|h0|t%8c0J%&sO6-E!Fsh;mmHSbcr{pz2~=VVJ|uiF`LMp?VFPIToZR0riV zuBDA9rG3JC%N;{=*EJ)R_&1plc5reGf_Ymu^^5c~stlLovS1Baz+8#Ab2<5w>$lX6 zNrj5AWUx+u(9Psnbbg4Bp&<>`Ao{0WsodRV|4m$=bY<()?i|7%X3&S?E?gH>(tMZ0 z>#d77Pu_s)?-_oQL<$PsnzOp>4G%k!4QPuM2TU~!@7`cF#g_3nRSHKTpHFWdiGcJ{ zuc@?##aYZONIyFXz@lehmKj;;Q{2b{>_+OUF}Rmnl`v285V2OtOO6`Gb5vA{tz|Fq zOl+%+PhkoVfiHUk?A+T$kJ9*qc(Y$+r}AY924oZo9VvVpyKHjL#&*>a)wJ9-F2gfx zFXz+2m{p~d6Nc<*t0f>M3Oc);r&eoz@RnON;kmBo95Eph;Qk)Q>!Hq4JI8xCt&vOI zZu(N&w0Zf#Rdg?BoHVqp{r%uUXB@;AWs?Vi&IPhh#?COJWeucx7ghmw3r64CFcROq z)4{`wU_6^+Y-J|rn@mlSF}V~bAbhgQ)5$=y*Lg4hJ6)^ST^Dqm;czy6g=)X37gKK1 zN&9y0H?LU?psqtDvb7?;WH%{_ve$UYB4UoItP;`oJ*F7&_M7 z6qAr8)zu&@rn}Z}OwWI5a7S^+zZX-)1u{i1oDk~NL(`)$F%EHg)0Z-30{jaD9Jx$y zdjz?0o8fY>Dk@2D2FvXw)W-hz2leI%Xv4IYP>Dz04-KvjW>3BCDJWRAtxcQZa{ z$#T+xW~8FtMqA2oJY$w)=bo>b_ThCQw?Q>CW;&)Je!z8nh^JdavU8F;Sl4;f14?>) znisu^+X|GXILF7cv@V8qjf==T!HU(qjGny;DE(QT*cw(S+bzKZico7%R-5yZm>j(1 z7;&Z(&*Etm6V>+^zqG6fE(L~!{QPrqSA`uw+Ua>A{@!9}pl-!#CCNULk3aTE}X_<8CWeJDAGS#7~8&t zI9RF2>f~B~Q44UkSFL6zh@dT)V{puK+egjy5cl|4=eNC*ww7PiNsNEclOg{E;FSer zO2)!QWgyozG{(+1;-c#0=298taq1)6S%Ha&KfH9>a)(5e zMW<;fRu;okY5@DmrCrd(&=yT;X>9?syApJ?`K$g0mKj`q z?@R|D>W;7bGjMmdb8V3J9YXix8e!;?*$E{mitncWl0?}815h~jMrw=+pk8M?YbT$G zdj2@N4SV*v1rk35Ek77IHRcgB=l-Q69>WD1{^BnXWQh>7b8*7AOi&XkMBCONbLE(9 zde`Z51&>dZ&;+N%O{BB+IS&4eL&@vp!ll zZUpVrV7Tj5d1LIlLRP}X>S}PJBPD%A&mlmvkL>ra%t(4?@KuQi;IjQ!)P~@Ddyh*_ zKJDrzNeVQFJm}D&Q4LGgAEoY~@Vc9(_~;9EWIKiqvjRPVWwjJ$L|z}x$A}O?H*SKi z`0ZWQmnc3k?yTgaEHHp~VY9axf(0u%Q3aOexgt`bFt0^B=b2T7ggDnn1Mu)xI2jzc%AP|x+& z^TQenA!B2K8*o+8cts>*KQ)w+hZ796H&Im4}NQaxE#S)c2GZgIH9q9KsD8M z)IQvBYjarwV3WKCz$Js+YhXY*1_Qb3a<4+N{Vhft}tXY#@CdR zjwP7A6rfjm=0&`(6e=~*BC>~S&DNQ-=0qJL!rv6p2fij!xkAOJ+sdhZ%!v7GFJyRh z{`eZM0q(LZtH!$jvZvo)N6*7}3tWl}IVGOXQm}^tCT2JW+8UM^Q8sTJt6IJKdy{l? zYkf8RikZqLaC*3HCtjJ2_=}boT&;f#y<3L;)x%i{Eumm7FYw7evl6--Xg5tBxIcksO<@# zuKEiL(5LGND-SR$zZ<-0Wf3f7abe+7vMph8Imvg?g-U5*?qUynDbvZ7*NOc}b^z+Yk1XC&4 zPN8RCm{^`6aCb*ka|UZuxwt{ab18UfO*mTyz()fA@+&eKwxOo3ZUAK2r`$)1p#IMFzp#S)8Tf)C!kkZRqU^*g;?EHs7u!3L%+0<^PD=_ z-nza~KgAn;->4Pd=xe4q_xyu^1b%Y>VN@uy=Z5nPOXO*z3`_EMT}-8-^hnPS zK(SGmj6fjk^OvGU`-;BV{lUNcRJNKx!mZ$ae^N#MWi4IGk#)OZc5md$EJeDP9 z<&1c73OO4F(Q8D6jkLiUuveR&r#2~H(G;z$-&Smdq54h4-{9Tp^Qt)%>RY~^d5W04 znALeeS?f+2^AwMfuw1Fmzf~g)gJd%b=ypALQ~D!gJPv>(vDfV+TuCa9wX6D-V#szF z-%BGjgXVjAtv(4;WfXpQ{dvCHZLfz}wPaOnGi6f@8vxLF@HI~3Gs~b-A*%goyu9DO zKSq60n?|dYcp^hp0 z1*m1)Jitwl8U2h1g>F@PA?FfWA@sqApz@H=tRlz_+Yia*kfhmQ+g8XNKS$nXON0n{6(5a50&{B~V z!KX|`G7UWIFU5z%)TGn)U7gyv?y}3U z3hU~=bV3)QjpTMW?34Julv0RUAOYhBZDxwG*p?d+nY4|cA6yhOU@z>oya{*X-ly%C z3O?uKS#I3-ljb;=qzgTn@6}S&vzXgcVKNRG&Gu~PX#mYoHTrR>xlq}M>Iz$GjjCg- z3DJ;owjJM<4fai&(GweeIFC1e!zNx&Op0zy<>}5Zd5!tXyV(vkBro@ObgHpoG};l= zw#X{sa*s-#cBU^Zfb-XA*_zxQT9WiBi_{`v9kmEpxk^ePo-uLXV8ZchN+&PRohW7Z zd0JcP<=8t?DzKf(b78=(%r`Rc4v3e zhu34nqjxryZ{*LHbemn%^ypFfXYa4@RjOR&e=zh^-K>7&!+Fk+SnEw)uj-)&LMg_kGnH!vhsZa+rCLo(PNHa zf2sVtTRxeU$o^8N+G;S;%X7RgP+ zm)_J3{NRPQ$lJ8s_+V#X?Hj*{?D|F1biUgw>$6>qGKE$I5{N}8^~?F_JQL`dNr3G} z7!NFKPxGX6p2C*zbMYc@-6KR#izk8TQ@kp|4QV*gcw(%C<*ddp{b`VFZ#^sb%Fxp< zjm=XTK##p$8+Fk=Y{ky41`giY$m&G;T1Bsz@ysUhT+tSN^e+TFDP8JrUDCqPM+f?7 zSO$&H3vAoH5o>?rTJ90SbbDXrs+PHMcDgdz9M_tJ%)t@T_z59@Nwme4%)mWvTs`Gw zT)TzPd!sfrY5ifsP=e@i?a@2?%{vkGhP;e^Dbvtx`ki_! zeU2fD`o6$oIDBOdyf(QHttR%})i9x(+;GoEql{CH55f(qgXc*BroH)m@9%3$WZvW} zeSJI~CeNx?F#GYZGN_%k)MrPr7@dpd=1afq>=3)3W#u7&lN(|}5s~F#DZRKaP=9d` zm??p5d^~MXC*$-cRILq}JY2Ugh4`raS-iUnmBFL`z%YVFCw9*wh(fa}e)>}ycU8Q> z{^Wfwn1F^gC(Ge>qt8bvDSMfgtbg*A-j`Jw;F0ZGQClx6mH1`tZ&jR-9S?OZ+g9^6 zhV(ua6`$n2n29ccobwRL3;~5s|2``Zcr7Q_(L%bs3#6@PnEvshrQTb_G3u??|`49>DDB3m&u*{yNwpDaeH+oXJsf_UpMHjBRIW)b)k)aj!)VWCRbGeov&2CSC*0I& z*Zp}6GOc^Ka71%b8HhBpnS6rHVs&Q?_4a#gVy8|Yx1o#;YCBbXq#v&ZU~03@K&4If z9M-t!a1f9|`%)b1z^K)@#pEI50*syhVefPYL4Puk0~D801$5gI^&;`5y1<{JOaJLa z+SzbKt-pJ`-Fd*5|>!hXl{3ve6gv89u8Jo@s5{6+MQRzXb%yi&KhRB6IW_Nwi~Q+%@=5MZjFJ_ z5Uhzh`D#oFzq15&nf(%aNayPX&KH@VUttVdj^f~>JrI-EDp`~Pma=FngeZs6c#ifS z8`Y$pXab$KvgC_iVMK<@?=dP*9*Y%fp)-#-TB*pTcv@pmQt$CgB$0xJ3h6I)`2lff z(lq4{n3;>C0gKL|c62vpezvQEK8ZP#;k_nJ8)I=Sl6g6$IHBrV3UiYg?3&|@x_*pY zCHv!Tb6ooJjRore;I$1cJ)S4#zrKV3eAdV=^S}7msOicd>!Iny8j%D~9Hs?Sg%Ml$ z{Q`uAsv%Xq%=9p+D5Tb9FPrj2beSKJjzCFz?qwBCG77nrtY_hc0-<6MJD}d+z8Q*F zc(E5v+0a(ZqpMs+Tj0w2}#)iYy2C&yRNj+Hj?(HAyEqMVB< zEl#S;aSjOD{x$N}JLO-9UwNJ{t=piHxNN&G%@Q&_*?stKp_iY}B>zD^?Y931h3ewc(zVY40kypXJ3BgWWe& zMVll*fGbyYny^+|(bgY2g0}?XJSB~*4cN%er|WL2x;^`0j_8SPM}+91upHKn3TVy5 zV5i6^(hf;iJyZ7G&8%!4nBCFy@Xz@>LRtZl&9LVx`=lbFUQyrox7=Tm`z?}gY%44PWM7XhRj)I1k_KJ`Dlf(?TQ~R_h_1G| z;%r<7`SgIW+K>?7hlwm)hnrZ3_IAd*@mcYL(MMb04azEvJNt(NJ(*P9Tbozm;1Z>P zRA8JslVqFkkPhE+Irqj?FZ8wjmVq78mNHogkftfjRrt~7lM~~>p3Sn*F3p!;FLY~S zGO86j^XK|Mkf9#?l>Y-2|C=fPzdr)}m!QY?f0exdFh$1y!xaBDJO7I*di-x84`i{J zqzAls4G3h>J83s7IUWou7)R=j8iG zYp<r{god($zNaqF!fOzzG10hjSNd@d30FiN&L&Cxe z1GxxUn3v;}5@UivVv-CnQf|HwPIGopVSLz!jYkYhfP`iR#bPZ)iXX67uU#R4^YONY>TA zAr)S54=?f+ruqRx5a>U3PGVu=AL$p0cXeXSLw80fSn^~t-(EuTx2b(N7Z~)+l`keyd zJZ%LP4!t-77b#d2?)NXwc?=A0JiDX*s^F}PBxxV~vqvL=33B)v1u?v&yN(L%efn!f z`73B3J^b6&Ij|7;P>|}^FGnPxMi=th@iY!K?5dJm~x41pt2&2#mu)ynF@qpKhSU zWWec?nh7KRz_EpWv(0xZLQOAS_4R03AesThlM&@Hb6_I3(Li>;rr<>?hJ5l7K{2r} zKhsjb?I21aa6|pE36<*gU*O51p*|T1%pUt|)4RY!EH~^iP+2s8s;feQNQnBx6@Tl1 z0NvjLy&)T-`fEmjeu^fMgj*5QNo&IPND&p zAW!sX_uL2t*Wp5MMZefTi-^~khCo@8`$_^fX7?`kIDk;kLBUaGYSAR`{2r&aVW2E_GG)vYMm`%u=+D2QB<(cw&eMmRRTJP@v zJtu`<4oz8x?}t`*yZXT4BD}74$mH!fx>neF?+0k7)LPFlvVv}?;Na`Xt z!88lProffVRYjyx7KHV&Vs!gyr-O|Sq^CPJsIVhtB6XHg0{`q|jO(Y^o_>|a)am>| zp(#aN$ZqL$>;09NM=L$<3=ZNzXbW&o7_xNF_;d&1#O2=gI@+9+^BS=KjF} zPK$@tq#CuvY-}B6dUzaKmeNetg}t8n5sI#afGR{bF-f`OI)$k(yDk~v@gqxLEk%E& z2gPV%c)1^1d9Vg{zqz6vs=H^uNzUzo3l)XDZgt|W!L^lk>bNJdCl}0iO{!-{tt}sn zFDcJ(OrxI#v89v(!8h*ib5HWUH7Yga*Bhd&+lroobVXWV^ z)v?6x!-_*M?}$*23&92`{@5Ui+((P~bx22@_g-!+Tk|2vZA&2shOc{rhojJo5~Yzh zv8@Z^+O}gezvcd;^sT6gCMY$^_aP~5(<03gEHg=v#<@wWk@9DYPa1h%LnQr_RTye& zqancpt~Q@fL8aYz=B}M8weVVa=xe_@>kLIzhA!#$%TM4IOI`_({@z2N2Vq1Y0Hb{> z)BT_-?6!Iher2_j5nHyLlFcuOLn0pU=lZow$?@N*TJRau1FsE<@yxKalF@RuI{$UlcPz z26)gmB<2ZewCA1x_^=VxqJU2&2jmoI96`qgVGINzu%xsjROakG$7Fg5ck{Fs`dirA zez0ThXtTYlMmYA$Pa~CU^bYZFU^V0d-C6-gq`6X8n(LK6RsTA;d(o7&SMy27%o#a1 z2rTb>Xr9-}MQ^)ligLTmzNtq9_3u|%hJ=zfx;?0|Nvnlv zE3wj8+g%&S%S_P{(_6Q8tj6oJKy{hjHItCq&fjVo%h_5T1#$NvNWN8MXm|+gG`$?9 zrVFt+SG$kQ%2HW$gELIOUC9e6a(*|Xj9-*tO%hqVmlS&*?nCV3!kI>gmJ?2go zQioc=S-f`u?)~S62YvlW8;9Y8{n+qX+2$*qAJ_1yaKxE-iFa{YtLpr@#=eU^|C z^@>@VonRn{%llQ~8c|0uye1A?A&o4V$S+)9aJ7j6z_7icBT5G|@7+jGq$z?E6AUQX z#c@z1tl|1Pq&RPUW!(I3+xKzUO(lx1-yXzWYNvS_9fjHK&3t$sccu392xRBuHBOgZ z?aIb$KTh{0g>dPA^`z+nh3<*mIlt0yHW$*|b)WuPxYyC3mdOE6ln@+%Esn-!=!gtd*P9hKIKe zM$pi-c5B*@U+@tTCK_M zTslE5q-rL7Wr6cibl1d8jbqqtIIu7Hb9&bc03P|AaQPmS)nr`6Q8zW159cv5Fl_O= ze@F&!Md)c_uJ*D}oO{2m3gH7)d75e7fXl6KdX;Q^Zb||?D9UN4j!jeyrTsCzU&euT zffObj$kQa>D+sPuOw|L;o1c2+sTVK}qKxaO%ufBpU)dAxsy9RqtFLNgm2y0zp^+dw<{ChcDhV80 zX14G3!$}3iBtdeq40Ty0fL6dho<*E`7fY8W*g@^3-i-;WjUA~UMI_nuI?O(AG(vRd zg-LYQm!!-k`(yd$d167CV%X#EX;u=TgJQqnC{*ds71!nDx((h;Ap+edfkG_Kg9l6R zfxz@po+gm?d+8H=8~R`KJ;K7qC0_z}Q-*SlFoa^(p)R98{1aF;csz6>IBD?Rgh7-( zl`Z+BC5OM-U;)d{$Cc*025)BSzG`kNT=n$6Q!RD{IDiR@G;=?zWi^-7B;0U7jf>~g z3SA)@ja{$}4E{cPY_`u!%O!o!fftOcs%U^cy{e$}U^fQMUw(k%VU$m5?(Y@|htDu| zXU>UEUmli0)v{?;p3@Bp&a}+=>Txd6ly^FYo*pw=*)CZSE*RmDy z>!puhfNJaPhphRt)<`IeSf!qUMR)c1%MWHn+qE91)Pc#@!ZVEu09R!qVdwP@^OsH1 zqL$UemK$q#k(=m4Wk2>5=`ti+q4xOaIALhrHx}x@>;6lP?SQ{m+yr8PF{fIpK^iH= zOdw+b^J)*lD6mOx4}4ACDZ7fltFrRwE1v!K#Rc3cZDQD`%N^T<7xLzg!SU+P-!tZ~ zp~M$?>YzudF{zIxd#y%0$+sOFU5*GfO<446A;=ceCo|DqS|R3#EB=(oiwDe{MK2wH zmkRcs75>V$^;B4*!WeVnv3ZtK@b~3Y_}N21oNC5)7X;E21c&!e;Ddhv^vY zR@!ZTpuSk}oYc`j8|3J9dH9AmL=>-AaJ1}Wt2}wiS?8!6<(;b`M(lx4qSZid*CpbM zu>6I@#l7949oo}{p+J3WYyNBr0}DS9TN-Pq~T%Bd@S)V?wbUF!||CN%*g zifDfdGy)k@qRy_%ysHX%Y>S0^`);MR>^%^}Gn2SHpjh5fp3uoR!NBq}1DvZFpc37z zcPlrlxW};Xxs`|fbDRP-N!s?ZSMI#Yjy?5+hj-6TYdQf`Nv*#lucwE>a}vlFKX^VQ zv|B6d7ilgIK`oPQuE)q1=v#-jqDqx8fHySG+;4lMvcxVqW3xu>1X!Wqc)PNp;yWuidWWBs?>#*)(eKFp=GMeTGte$mpzEmz!x}SKk=tf<8kqW#?|pGOCGdO^BqE{gqP+Axvu- zpjW5!M|S+uYOD144#W0(V=gZ&D3a6>N98{E0@a)*BlEcJS)g@JfqXORk$-yjo(!aT z&jB;J`56}d`O>8D@hr-_V7H)VBvUuJ(YClm!H`&!5GsMBwj`24z?g!59l*qYnrWZ-yA3O8Z?`T7pw59?Ci zLG0{({KvkLmq;ot_eHSCt@a?^BDZ6><+atsaHVNM;{vY@#V7U=8Oa&1uG8_e3p-Z?}iz9fOji*Tv5WkoE4FA;nH#uhvL;gsl=c1_?4KGaB@*J z3MmmcoV1Z{|5w&|JkxKH^uM_L4qG#S_oZDP?bq&PcH6G;a~7?Aro6tLCGJp~IYd+N zjEFF;M@wG^okZILdz{DiZ@bs#y4k&bx1YJIJaO6giRh$0k)!O|9U$Q zIE)YBPK(x6xg@?(8L{&V{=0BZLFW#h}n1O9#*I_#d$~s5$31O zT6N%TSkTfS&gpD;IaPQn-d4L@Xf{y6dfAkEW-!)A;n<&^H6yVvh{y3=-0xXe67Z>N zX=Bb0STEFxEP7>PdA?E30(ooN5;jxtcLeu8kJOXV(**prE50TlHUhfTe8^Z5dJ63N z>%nNGi+@z^Nb`~h2xDP4xSpA1>E0G^soZH=!%z(MT^jhWC)VW_Y`qk)N#s%Mec!Ft z7gIC@Ny!YzRG9Ywi5{Lk@l}VO82n{FW?2y)=MYab%3UPQ;b5;MftT)m#Y_iWI_L87 zrck%XXKKma?5S)FOUr2-u4RbRMIFvvYxp%g$*{jjcxf{)^a@-k_DEw2C8a}ppD9;W z3o1tXa!%)kjvEUmVa)toN9S4?0z*$3_#(CI7NP^Xg1SX26M8wwn8S`y?hUZOkrn-8 zt^rX&J$n2yn4q8;!(+fN?%6KIVr+HG$3W%;K!Nqm!VKKPhQ%o5qGHp*rm5JkDWdY$ z(|SBg&|+x@rqIw+9-Z4Or#(#kYAGSM$pjU|KU4+=tp1_Zgz0|pONuPab5#dq1cy#( z2Ie&?;vCvEJm2NmC!+n@KlQF+yltH+knPt<{XrI17!p3PX`6|hsV{o*eB}D)!6Ff> zU{fk&FK1W-9|=dxV ziE8Kn1hRQD!!2yf1wpS!-H_Fs8W`Sm^BJiL&#e7-wSQ?Y#qygfPvU=B|7lC32#ao) zU1~g7jNaA0-(~W{o3x9E%um_VNUY?a(HS5e2_D?Mzi#4= zbg`L2k1gm~^pMI~=0R1|12?)U0Bj@hBP`PW0q@DP7}rvs)iKlYU+2st$-gv&=3<^& zvErnw@YL!odfa4`V<%&9PqSH9q6FiWo7v@N7-f;)w?<2SWh)srP-i0tZoQ=|{XOh3y3JFtNi|*zWxNY)SO6BxltbhH!jK~PZr8_XlUUsxKj>1Ra z0bpvHwOeQ}n#IkAr^DvoUz|pJ3ewxhY$_#PtP4-CF?CZ3rac2zjrq_>e^<+0{R6sU4~R z&|M)IGM0Ti*QavHCv6KF%JY|@o@f2R2OOlO^@e$)&{AEC_1hKN2C$=R(m#I4=FM4< z?SQMr+^y2jO(d!St_U^Sd)aA9In}JeKjrj3gEwft$ zITzayc0De+oD1DJpJK(j_}!8RH9=q7chq6A8`5Py6=+VZAaz{6y?B&{Evxiu1CmVw z1lS(#ZRf(0H_=MX6_C~*GG>;PuIwpF-|xGz{D(xs5kAhLz`ROX3V4-F`%^M(Y^{fU z^}5|hWLN=+UGx=4b)dm%Ue80!;N+B^aje7WCaRF&94z&wI;2H+tY0cZu5ICYVUO}j7&2G zH!TM!sLR2KzreO}9l0vXeL2~M!R+)?#$R)5w60xoxdV?n`?*F>X7H?cz;%6h%IXRJ z+*WXV_JA5e_pj7p;Ca%EYIyvdhEL9xWaL+bGpFC=AunRV@&RK)Ij1jr&%>83hh8_) z%V(-cONpG|ir}ZvlE$iVJ>1mLVd9LlqiP-9*?>RJZ=#|f9{HOtcJCnS%S=z0PtiN9 z_S0Q`Kdd=kA?gTw-zXb50lR6tQvH&-TLm-Nx1J?M%j((OZX|L}n#*#^d#{!@(Ow+8 z6r8d`^y>k=nl!U3Wi%7alU^H zRLhwb##Y!jSAAHGx2vfH3P&?~Tk=L8gUtQ46Pqog`;wTl1M*#aSY9rQja&=Z$q$drwW?~p)<6p`bV+OM!=Ww~`n zr~7@j?m4F?;MYS)4~XoPm|!|uhmbEH&JC}wDwhY>tUL22B$cJOrazV*Un4X_Bn=`5 zY0I9~S@mg#IDO6YS@O(+_=V}x;NY>E>~80c4F68RqD*hGa_=yi4$u-g5wj4ZGp6IT-PLZX zQ5{;lt#_y_HwY+sFcg9iZ zOANnlb#sZ*`@y$Rzh}9^*b-@Su6f>T{?qL_sy75(Uls57$EPK|wmYv#gmUn>ix7_z zO!uat;JFt;V%v=6Q?e%DM~4ma5ZrZT)QuJaJ7e`kjn;H)fctf|QOAXI?6*?-UC1O^>H?3SS66-H;2s`57k=hP6FeSQxoyXiHIH4zii@gh71UBm zi&$b4LKH&Maa}*bev+~>3eAp94K8Y-o0dZF#ak%-$j|~2IKaC>Lo-$oGQp&c>uRn0 z8Hbq%!3Gu%CJ$0s`2)ZpARzFB4Zs@dn;#wPpMwyp$}blem6ZHe95tZ$fja%Y;Oohw zqqPD?B`B~F&`boyo7Xii8UEc=i1S}ht_~b@qRRI74`y;Rd~9**A5BRGkV3GQh^{Qn z5L6u*E86Lx2UT*vpQeOx0=P$D4B!7i^`e?kxZ#vJ&N22G(wr1CG zjv(HxAIan3&`iL8C)Kh)eT;k}PxOtRIbc;!sXt+SiwPk*f@)*&rmuo#XAAcG4t`be zepjO2Y?pJoJJvpatm8hkECNQg&Q6eP8La&cwf+ZeZm%PDMrMf956hJ!E15w*=qA47 zGTV4QN~hpY9z25nerI53AR-N!6Zz;U24K(N9^aGcRj!NfS-Ne z7~bFCBcB?vU+XB}-&glNp((CSO=@h-?^prA23GHIJaaRY?*?`N-%gF_zV$QEhPAG> z>iyM|^|h$|^98Z7fJmnSSR8G|0vg2zxAuZC%q5Nh=&CI8D!u^oF?EKLlpii8>wo+| z>6dFc0Wh9b?Nu;A&(DtHACMU4N5E{Ej&}Om%D4EBVZmQQJ`F&~xA5ZjPWl0xtDE@X z$yeC^TTA}kFjDJZA0FTTE>s0g$o%{9g*N&x)d<+mWN-f{yrH3q#p_BJq7Yx!MEAGo zSPxj;$9pd_z_PsC*e>WsUrq{8T=swiW%7F2 zSpv{sKCgo1U(?Uqtcc*=Kje2)F@;KeiI=RfPZ`)(xP$ih47@wEh@eFA{TC`QkDz}2 zZvU9?{@SJH^e#g%vrRkjdq3p{4sO~>WjlB`V$5V0lR^2$NpHvtPeN^SQG*5Qo- zmY3gY{*~yLegc#|AjRXOm2Dl|)dki{A9oRs^)Zt$PaioH0Tc9sKY~7{Kt`w8nivoo z@QXp!9yjy46L@m$GxfIU?DPxB7@H@^VTN#n zO61N27q_JPpp|%|sv*CdDE#pv83QS{JqiQxIr+nOItz^WN|kuFyHXfH!{X%ufhshs z)Y}1llwm2hM*8+WIi=UIQnUN9HvzYqU$;DA>?P50H=Ne}=k4b&`&OZ3Wm~?W%j6 z(x%LY+%|E$^!E+HKa8-UmH!z5(J8~m$zV4jxEPn2zYBHmORaK-2rjzaDs6A%X~zQd z7aBL_7aBzixQ7Vj%6PO>Eg;;-chghEUt%(9nVD&hmm9b+C{wC}P7jT2PSJqMQU^?#rfVEb-JAwN&#hLld0;-KOWN{bG`ePs={VsHkLjs2OS;oh=r6tSeJ3j*w@^a($mrwjAUndKX-==bm~3N!fn_-$YPJ7wuzqhbT@s>KoU~<#npAuc%)Vv%@^GYX451=r4#sNbDZ2 z|FYmiTM=N}fummMHjHZW$Tkoj-Cb~vo<+0ZHasG^!yhJG9MV!~`Vyvef?9mEvx-k- zyZeX8%v%0yp|T0!XqPZTYnE>#OgWL=LX38~Nps&or<>@gWuB)0&6u-vdcmia{+2`& z+Xl)8j|I}xSjEtBeRJQfhtb=nv`!#aoV z99ynO94ZcoP%l0vw`UTEor>u{84FRu6M{6Zq8CCh=t?{kEPRvNak8b0xWpG?QGG3_ zWl!`Q9m}VClT$xs$=b&JgFBJ;wAUceWCsTMNgz)Ac*)8?K zEr{>UOW@g+`QTWzm2VQ}5!#BKM?=m3^BmXUB_glZD6X3GH<`+>yZ_oYvER z5|eJ0Rt6wqgA8qk28s=7i&8sWoXfM*4eZ#JLNx8zMdCw?5$Cn@6ZFVSZknfR??yRn z@OvzC_I(*cYFxw{z9UKP;kWk4KK!JGr1wiIUPNaV?4Z+Voj(;WgWgugAZXN99foHN z`6UHlX7jVwE4hfp!CafG-guU7RS7S-`hlwzb!BoU6h@~y;tbE^YbW(wA!?0*Xt;t; zH;J>!YSAJFDfsv48pqToR2ME@-!v;>oRlB^obn=A=L>zahz+ga!PoeKSk|ITX!ni( zhv3rBQ%I3@`0p`&amFSS;s)>Aa#GvHe~Cx{SAF5s@NGE4rh)i|X8taYKr?>)PKYID zG+vg+Uny%XEd{Bv%tE>jZuZ4cJ=Re~6Jm}=PjSVPpf7!+U?n!9l$M+#;p&;_lujjP|dqCgG|9gd2 zESD=fMXa;*KNLH)g{ykhYSxZo5F8Y`O3 z*sm+!Fx3XWyp`W!e4JOx-k8D)35+3;GWx{=1N^<*7Q>j)dgt{x#$htcXz^iyZ$Q1_ zQ$|ED8-GPWkXC}oAamiPkQ8VQG2}^EMqzQ(`i#T@1}zQbl?I^?oQ3Auv*LP;)%v9j zttmW(jkEZ^H@A$hj^PyntGL$NmgfKusc}pTpElXNC~+#Yvk_`wTTcvSe@i_soRQds zzeSFac3i#tS(32Pa(Eg$_Y)6bF_@jE;g1Y=aEHpT@0i++ue#x>m@(v;L*tz{vOe0b zJ0EvNuRg!@VOuEmj7nBvKm5X@Mr8MGSKvUt3Ma1k$vRg3688vhWCQEh;7myx`nkfR zp3|IQ=-<}sQO&gNfD2j#!EU2YF{crDc{UH~*B48%Q63Zd>ewcFj@12`* zH2W|f^jrY}=GQ)5oe%S#!+<1CD*#Yxs^7gQD zosAi)_zXzwi%k*QjcLI_tA@OK+H9o}?tWD-!of$qPd)(pDY2e zFEVmBRR~~K419gkG`+R|THD*daBc8WyEF~Vyz7m}+(Uu#w1m-_YGZvr%4CCpPIzg_ zL1j8`8RbG;?Xnqn{m?c<-w_wM`pRkF!;iMM8Dr;?Y&aQT$SX4i^-x$u)cAulolZO{ ze{CHHz6bggWbz7XHI`X?b(dz!zGraKPjFhD4`c&D=v!>N8IG~1LUUBF55oME+3h+Z)|Q)csOBf=euGZ%br)*MQL{H#VLl9~hlW^I8;saAgI~Gx^bu~{BE>4i7&IeSl_SK32 zIkK3*qUtV|BYBc9@9d+vpVDT3;KGXB5xl~G;K>b3veo|rIzv+-&+Bm~|B=gApf%!L zs-TctqMvcBm%23Pk4Js;!iX?*?lo(oR4E`Y6FpWhuhTMxz5N;ZFkl#FF72pLI5nE> z71{Bo@76h(Q~(4|Yc)%TzKYjWaWvW6gx-R4AMYI(9jHjyv!`;3Ykm@Bu5 zRTZa!aA_!iDb6Z&-|0}R=1bP7j83*L!u%%$OUGY?aApT!ge`~b^E9gRFFXBot`+74 zRu_+`ki$3qFM}_{!)_iyW6Y`BBzU50r2zw{aeb8_vWAz#_ky6g953kuzcPsGs{;dZ z4p7_hBo7i0IJ!SCX8nHS&=YM~Ec465@wr-^bM*Y$`TU}5jBK)i_-)QI2|$RTg~7YA zE8L9MV6%CS-AtpP@ihq-J2w+3s6(15?>&Cifz1n_IwdBH4ArL??0J^{A{n-a0@y?3 zpgoEi+70#}KS+3J74S2*#($kmZ0pDx6`W#QJDcAIuLDDa9^S5uvjUvtO0Hj9wY+_Y zxMROf61YWOEr|yZ12-rjTzNTjJhGV|Dz=v3?A!(mPGbb$9z08~IED?PN*Pp4Z2Ekj zUjbGqu}dQ+o!Z7ep&m)d<@eboVE16EM1GKPn%v>E51PmrpFx*%w>3&eORWImCcA%j z`q9$}6IN%)C}sXGa+yHK&F7C@>fe0Qyo}u9YAcn5xBlqWWUm>2V`V`vA*0GHW0?* z!u>byn5DVuu!(B9sbi)6!`#o&QRR4d1EpXKFV*B41z)NqveFGvtJwuBHkkL(J(@ab z-!DVtY6YDty!1V@Hx~j~k|zC)VxfO*L3UA=9G~2~3`g3sqjK-ia+`!PhNh&$$jJKQ*D!=9a`;6gyx2DSoy} zbP+5s#o3+{R0<~2{2Pp5qTQ6F!iv2iGpY(A`nJgjWcv&2{_js9Jzf0BD}Bc9{VR??qM_S6iRtK`;dAEm0H{rDA+vuv|K|ABrTAfyh@5@IVdhgdf-0&d^uuh zY5!T}%HE?k4PO4E36rFvBTe@;!)=s9o~4y!1fstx(8A#BIoSSPwT_>c<*4HZ-aB zbwg=`&6cDWqfWybQXp1%3pY^3 zYnyOo83&Bmn>#|dMuV(5KK!*=*Ahwy!mO^$q3E0F=$|k5heIF#s$TJp;+4i-SqAkC z%#)phaeDs&%6ku~J9KIPShhB;2Gfu}I&ijM2JNm|akcwCo~9&GBEYGcm%M8ALA=nEVqkU#X>`h-Q_d^+c{M1w?$-iy zLa`)wDE>W%Q*+JKTv^Y1hHm{)K22fL-!n9WDV0G$VW9|#0=}{@UD92!a9q)o)W~H| z^TLP=cjoZPD2#oN*%WeD0b;Y4eYsvevfs9noy)F@w|$tbV#}{3RXOq2nRA!HUY_B) z-*9?}OHGQfy7ScB41HYC++*Ghmn#UCuv~%>7TQ67jWV!<1XJTS^0=u`W>)atoz4S} zYkubf%geg0RQ5R}=}JaX(4sMdZn{Lfp%g@8O&UT;CtQS zpZELPDS>7$NnL^_wO6-Yg;@jHwV&YJ6+$6RCI4#TQV2HVh zISG7{6R`!(XQi^syk}mtsGj*BS_RLb@^Xd%WQ>d|9Wrd{wYeWr@PcT&x5l7LzhSYp zUOL03ui6|q8ky9#4-l=YrVHHEwLm1BNByZ$`=WizXY;u@u$cyJ=kklH9kw+K|H zuosD^V|{Y|XUniP%9kXBLG}(2`7cY&Rr4Y*Y{+wiVleWYW=8A}3kAUrLBcEhDTc=h z+-zy9Z0bj+ISx*Mz}s5(sW#TM)5Lcq%M-=orm(j`8P9O5jXb@<#D;pgFZ4!oP#|=u zC)fK9?+p)4A8iJ)B%DvvKOPE@7Nn`XviG4pOLNk`9@>=zX6GJ0@3+$(DIJ4e zFHLTNI$W~Af=pMXny&JEw;4%WXW}^l4l;}Vj2On~%mujV1kKNOSCB)2+;fdLvDNdJqW$qb z65+BxnA~GeF#^yrAJw|IH(7(-_ZJCV&y8WmepTVgjYZs&2+Ls(cZqZf7+u9cOzkka z-izJtokROLlHzUpsQR8LIG^U|^5%@fP)?)PiBbOi=DC86_6JgOW~rNrZ~>c&yk_Wn zp>&}rHh*c9$yk`VMZ}tISU?gQY>eG{B#XqZ>DDA^dC_US0cKPl&zN&aZ>qrgFB?^+uV3y)n79( zC8K1Fw;UqhnUxGK4}iK!iw>Mqb2Ep6sHPu%}@Y`%J#P=&Y02whYgwd|vqW7=D_5 zH75a;9h7PtS@=zu?CMFZB}9SHZe^^NcR79}xB>$vt6^EXg|Vn$I#y0(xGeqjhptO@ z?&RBAA%h~=s{^WKVy9$zf@7A^Qs^MC|7s8aoQyQ8(MQ$c0g;j07qcMf!oxsuYw}KT zI^Ck!yQ4wn17&!wIlr%G1?3wVOjJ&)U0)2rD~UBF(>ju7>@k@6WmYTHbNQ2PZWq{} zAjS-#hCldwF=NS}gqKo&r7@fpQ>NAO{6ZH6?5bG%4Em5{by+bEXq_{oFdz`ZxeSvm@bMvq@>|h?vz%9 zxZ?LZYaG*Q($OL%1Ce?A1&gi4l{}JGNXD2v99hwcv)V`{on6^*qlh(n+G%xori0o% zRLt#`-JbV};<=(cBmYxOc|a54Op-#$e%Z6|6hpn50LaGXdEG-1tDgObWM#E{!bH0P z$3wct=)SRS_}ZxxD{vG6F&a4D`5l(Amc9-lrla>KOK#hXn(G&^UIS>4Y5{~1M)HqI z`zj#c-~BTi$>)NG+ex9IgIl?njO);{bv3}S7rFr-^G(SYt0X=3gW7fb_?ZG zMr9$pKtX-#`?~Io#u2=xO|0ip<-afz5P9F4LlVpus zc~z68kvkn9!UmV>HWnVVL@HgQ2u>}u5`T;X*pqoMa7KS1mJM#^#HR9B>VOO6TzxSEOdhQkKc4K&JQ{{ zS{&tP`oO+r;XoCG?lMjDu3%(}WDv=pX2jhP6JgpG{%^2q?_|d;BmR<^nmaD88qm-t zAP&rGC5dL>)pDNuH?ccrjr$RCk;KZrCi<2{`+n9Wi{r@IzK8NvLr+W58jh6q(uXAb z#`1712R)N{>Bl=FO?*{g=4%cE=4y(cq+6>NlCXqW=RG){I0fplD*1it zo~`3hQ4C~i*DeH)TG?cA!KXhJZ|MJ*Bn`gtXG;!m;ADqQ@$kbNLYn9MsBkm`cK$su zro)37E*{J)gI*uSrG(sg+5YpFXo#3GDeZPhjnwWh8iW%V%byD%%=$@B%pV4$6=BQn z8JSkZSWsEfFsHoY5NJCUQ{YDI3W45AAekn6UPTxvA%g zR-U)_OeeR5n8N_H-xH#vOi_IsV42u`d-vMST6z;>OJ$KIuAUF~b5Vv^mppjnmY8^( zieMIdAmkpNHgZ5jnhIkiB*OZYviC6hQn&t9N6siCgH){nZBe#r6&>=yq_MAB2NL$BBWtc`QBb#p@FO%7`O&1@ViVt$CGalw0aL$ij&;ySNqJBY3{KeQ!i*$p zgf-{A+k{?ah|rm3v%2Giq{`Re+)0pGCgg`%JSl`^EnmKBa|OYf!{X@tu&cd@N6BQS zGw3a0cmfS_$X&26$C6L;N3@V-i|%GC-9=->QVw71_;p-<2bCMK5>{Cho7qnRC42XE z!1S2~jmix%IuzRHjT6HUaO7uED{WFiI2Vu$i9baZQwgat@(asdUBHw`Iug-3LGy}G z%WQ6B5JaNM!wTuDwNoS<_y`INd!Wgku;P2vib92RqLi?z`k_l?BI*3Wdr5gd6R%3f z;TlhgT>95qb`rFduWHLriLsnLJEfrunp$#tDD9z>(w71{lrVt}7&gOEr~SN0^*=)l zKx6GAn?+7cyJVF=^o4bTQ%f~z}@u%4KBcbRSP*7+;p=>&q; zl*f)fIA60`a*L;#s2uC45dld#kS+IEE6pE~5Z!;`Q1%q>e}m~Ee`HTj@A;{kpF zi`zjSXNMgn4X*Zg%Z^N>TAiymY< zUVsnDD}OFis5v1a)WaiWs5W3-uwXXUZ=C*1(npH|k8RJNyCT*sIQ~)Q&SHA5Tuh{A zopd`$+f(rC*}j7#SY~Fr;DaEL>9*r8(z}c&{*D$;-Sk}g?*5r8Yzy%{n{&#! z6G_-lsqZiTM-GP{#B8kMb^F){O4?zH*0r5)WQ}4bK(ImZ`p5FqDl@OF59yESzTt17 z=A}KNZIS7WvYnAeTjM2{hjQ&PQ;TPZHB(_1|6rvZLH(nnZ7&4MS2WUQJT&kssvaUv z56dWN%2SL#F1xQeWXi%cusx2@;6YXi8nUd+GO1RPr_E{-=34Cb7G5#G@jb_>k`Y&H zB)nL^0FsrK_#m)?S-N@+4fgWk$+iYzEx|hI1Lp+h z=i%}R%9FZc=&iLxe{v`wM2?Y)AS7V&g@t*hk4)fWoG~}&)fB(wEI>zMFY?)%k7q2H zDsyobJk-SWZ&<+KgM~Q4YLWyA+n{U5_WcJI0EsdvG|DAUQ-1uAeu(oJK_rIOg(T-M zkiT*p$fBr#q~5%n3*kD-)Z$BLe>~kOf5CmRz15yiHj5DZ7zv-EH3T2WSz{c4(LSwg z)=wjgc5fNf;x=Ivzh~>&^-}glMa~k29i{+MsvEBED9r2w9`c6Meb}_nxx?nN>c4FO z$mE}Ws#D7d7#zwlH~tL{%XZmz_iM*&MK6cMWcz&@0Ly3VwEGVqui3q1xO!@WNL<8M zIqQuiWhHR74s%J_PJn%-p2ZIs z(-BwWccj+mNHR_$y&3ZnO*VBEk+xnm(9CozY3NpAiOHTgU2qxbvI0-yz>L&zLE$BL zUx8UDT{)i(;Y>_&4MY-a%-<=Orjt#{#D?Sb3m~^UH8%+!H+wsCh zR`P8X{9Il~25WuFDkoSRcQSvRFU#$~(E0ENzsj6o#ATVm-CD!1buZG3U_cw^J>tV2Jl_jVPVp_Tgo z$on6hu6Mc9PTSZ#Too;zY>xk{j0st9e4K>G`%ywTAG)85tw2Mt_&DlAr!V@nUgc!; zLL0fitam0}7I}O+10D7kxT(P2b1tL)|m@jk^ujVXCg)vx?KJ=v<7lW``*YUDb!h1kWdFX|a?UMXf&z zOg$TH;cS?=FJh{QiTxSFW}hMT~w5s}FAPw-pTma!+!4YtTOCW=rRv z^}v+%=N4`;!};4AW13xaF^UY(1_k)GTCm#%?&=dV!-^5psr7EXyq{2$@WAW6y=cVD zXB^d_cdUvflSdd8?G|8lia%v&`xHs?Uiu=IZDP8RCMH4h8ysCp$=N8ZzV4?qk>tAG zpN?aSi#?*6aC@QwS4aJ*EEOAtA3u%n%r#BSo;`$c6>}HkHRwAyb z-Lx}IJ^qvo@Kw#Tcke1#9_LvZBtP-37>W^<4+#4F54YjB~6(AxgClUKzb!}YP#f8CZn=B?Zie`&>Q3Jl+2l+E;HK!6D{ zhojkTSO53tM^z#>y4Fcp8w*<*c2^W~y@FyvZ-bEwNu6>3F;!{F6_*=nFL+}{{^4vH zY1324whBrJq>X|4b-f<7bXA&L$ZCcPd10#6DejfCHx5PgTAE%-&IZ)J8@|MeYZQZ4 zVl9Hg(zz)z&nbV6m8K26l?$UTTkY2+WXhUF58hWy(VwgSDI`eQrz{*0dKB(P?JcWQ zmFvAG6A~uTG9?x!ha`>}c`|fyx7?2aAST zd=0Le?WfT##q9kHzVc+Ao$t?SxIJ|@2j7yHP!R8gk$$hb z;qNF}W;zQ!S`KePYOaDzim~m+%WrKwa2=R=_|x6`7B<(}gqx0a+&AmrmD|jDMaJiawz0fKH0 zxX0MlO#oG6MAwSOlL;X_uJ)8(PkdUCgNl2yuOUxC|}~8kfMwXWe`SK2=yu{>;9Sno>w;IUZ%kyRn~d?k#Qb^vnkQ=7cPV7KuS-k&$+H&1cssvwWqU&hW+h^0kbl06kSNECr`Zh;Sim`# z8-ry|;w%uw82<~}A#rAs1=UZuDYT-*iqD0J57#Vv4pvBVR2MNFo;+=sOLyln;!&z4 zX~^|rT;g9}oGxuln25E{XHb2MEfcR=Ib0qCwJEdEF!I;OQc>C#JT2>|>{SU>weY8@ zs`x4&-Wi7bZSLW@_`iMn$MW7LfQwsL1C7^3j{I$_-J6|&WML40KMhW6^eBckq()(((#EBm6P?_k5{aE`0=c7d}bIkG(l29#W zA_9CKq_K$Dh@;7tRTDP*JGiduPSPahDvHh z&T2W0Jt@Us2nR$T>SCsnuD(XgyL$4CujAT4Wey(dKd6@5I$@nUIwG>$ccU?X0Pl*# zx6FUg>o;zb(`_a<@Bm2@P*sLHS7OjWJtDi^KxLz`0K60fwBa5js&KK=Q)l}2E;&06Wo9KUVLpNr*p?VM7@ zw;|?Wky|rtzY2udi+Pooy3wdrC9F=bWt}I!xKFw%?{UaMJb|X5c(t=IB|DQk!?^jgHRELjy&|ukCy=p6%QPPIi09lOUI;L2HVR2?`i64bwcQgwx~a zVH30DO1|KY@)XUnfOsti#9na>=xgb7k*4zpal)-viK)M}p0YYsmWbC?J!fXe25LOd3k?C3NntbSfBA2!c3RU>-CZhuyG@kM%E;#FS z((Xc6Er-mXl3I{awga4h7dv!+g58kQ>a~p0P zAyszpQnGOxG#45#9C9PGPDwXHJ$|e2uqYa=kUWzfVQOy$ zY?ng;xLlEonrqG~n|j~CQNezvA6yZH^Jl%**(<2QAnZ*B?`p1?i~ks{YsM3k1dCQg{)MDocXlfRj-Yd= z)1VV8>o0&2R=FLCwEywyy++^R$12j|F{gn;n^+OQsJCqjY}Fd^|Nd={d;{kSj2$#a zEduGn=0y(y1w|Pi++w~{q#%jN)!DG#jvtpt#vt>5D}^~bmRLX&6^BaVS!h{wdMDN| zJ8LAZ*;q+%Jl4ayl}w_iY4B}ZE{I^C-GTh#VN(xK<^L2g)PYuhOpCs#udJlzei^1J z2){m8mzH8_aoS(iABIOeE5-K#OvdNnH<$6nf7ba8cf>9GvIje%zvqr6S+H7DH4DxE z{Tfi%FK~RpbsU}Mi^=2$laRy|eUfyQpNx3?vs99sEo~<~|B;w@(!J~^JQ=eJ5m-Xa zqc<7GsRKngZ#C}hb`E*5$xCnjk(iy%Z>8W&CZ(A?{Gi$bMN#$#k6jo7usmY2CWmfM zaH5dYxS*F>*)iR@&ahPxCkfz^=u72}q2#(=QJ^~ts5ygG=aZTT^kMR;OoVVtAE=oB zfUAwjDZ!QtbSB}pKx1@l+jht9 z*tTsOf7G#U+qP}nw(Z=0le^yF*0d&7qgr*ov-iH?ac9GYE&1VDw!=gnNb79kZ6LBB z5~toP#V9!us=amPIeZd@eQV>qrQrr`?I9a)eM6&}&&nFxkf@y!LgmX{3T~~oXj3n* z0dpC)t?axg{bl=WuA2`w^93P95IE{9NR5`Yb4CTDq3sBOp@R{(nW6jZE6X-o<9L@k z&|@wo5JfH2L0R)Q0qhd`^aLd0q}X|V_xIBh7_o!jW?JMYcclnxjj>-px@>NUF%L?8 z>>|8Y4G`8enowU%<|wSI)1g1|K`OI$n8gb3OfTp#*-n!(MFkVNg;bwj7&W_FLCp1} zha%>z>jppI$#H`hti^oa=%1;$G?VfqPXcDIJPvLKW|Mm2w*zsi^QP{TJf%??ozo&6 zf!(;_T$87|^$+XnD5Vi{4;(O7wPHI(Ax2ch3!P9Aa`eN1$<|&gYC(_GHDP$65fY`h zF2c#D(0%r6x3Eog!0MTkef28qEar*2awINl%Dg`S*XG{oqn&qu_BgDaonXz+-zX?j z8ZYB={p|-RhD?q8e_%+g{}V%EVf=rf5gRM}f4L(T!vEg+$0M;YGZOya^@~B&!rIv+ z1rHAx7tpHYTx8Qio>^#^kz_p7d=+k^R%^J?Y@=+=UAEe6Q(^e?aUZo)-mq$RwIpoK%hMeZqT>zCQql-E!YU)7XJmjauGJiCZ>t2P56 zB}%>z#A?sn(uBlj58?>A=sygkkc;G(hSfVb1Q-IBfd zE;%N^@XPxEsDF!crDv=IjsEzy0##XGRr>$?a1edhfF}J@8zx{O>KodEgN2ULm`jd_ zfl>|~DgV>-;p7JTqY3n_&5mzE5gOToH9CMP0!v%t0jd6=1Bo{O9zOnQJQn}KkQznO z2LRbOf?}urz=5`70bhMH&4FC{!7m?2M+16*kE4N(5J_ba`eK4fZo;3x#{uVFT3j=eOLJ7AL@a%xy|86ewtix z4j>sg+{h}we-C5uZTQ2I^>c}G+v9AfZ)SG%U1Poh@c5d+p3K7aS0#U}m7WARVRL>> z*;v|wPTbB^i?64yf}~>pRI$4@e;{PQ%9!yXxCz_WZrA5G#D&%*^<_~CUVM5WPTChhs>ad?*149s1^D~uSAME+v*<$aiDi^#Tv9@O_R|jjvIiIKn?4{Rykl!;{acK^zIpgZ=@n8`eRUab zS7Kyv8amhL*!cb9`x||5X!884N8*ivu=pp@1TGVIatml3@L_8FuJ!`>Ie5v5zXtdt zH89n)eVe%?X2DuV{@8B(D1RFLc67CWmAdbN@7<~X5&mA;2KBcUAX!}^(;~?xjA)#6 zF43&q%!5|A>c%g&6Yg^*gQNcY=DXCq)oo$Gt&PUNV-;|QQ_{-6v57Hr$p>FpiXi66 zSVh^cr`Je#!J;u#p4iAd?D2X^fvsA!SgJIm<*R+bY1n)+Hn)DdHLv&Zd zrH-3hlT-RBu6_SCD?xCD=o6`UVZ`K1!XA*jjGmd5K#|SEs|Xtjj{xVoBlL*BJ9jwP zAA5(X|3;dFM8?_n>BPyZn^3?048aH3@(M9Uf-QVr1Ff)^7n%35jW(4oHh}lM( zEvh)${1lciN=3<38(W5kY)6|nJQ|i+U0Q}d#y-`j8A2mKJ{*HdrGCM#ncYaEj#{;{ zcPIliwF0hK6u%76OYx}|U>`L5j-pRL8)e(y&Q4K~mtP#HL-gH(60T_HhK2JcN^;!k{hdcR5hY&>`ha+v1B%iI6%r+^pH8 zhK>J{4HyE%5T0a{<IK}eqx0Gg&2+0>wxL< zF#P?gg6N)G;MmSt!raH@=3W(&FO~;*9(Pm|YD7O=Fa3jf!s0pqSm?}g#x!we{qE6f zEf)ny6K7}jZqYwhla{M#A^iYh7vWd8EP|OKXZXU2KFRT{Uuuk0puzgLw%E}hI^JzS zQ)(6<akHTqe`mERKe^}`*65p-3Wl{9`0@r&oKl1-jfSZ+Hj&RH}Q)Gv0^)%pGBq%eoS)3B&;c2rux09|Yqs1qn;Sn0^pn;mpR*w$5R z-uKP{HQ725Ki8nQmz$EDRr`%+DIc7^T&I9;2&GxXz;g{BsigCg6ET?IX z@t&omv$0@P({v{H04lIY3v?pKi^;;TmeZj3m_LZL)a-fQt5BKj=JS26a06(tRedE( zQN$2kT{}XMmWK%6^)vvZJ9U#BIfW zqEz}xImgr1pF=>CzvDcvykKs(*JXp%e3EMQ_9W&#&Sk2N{k4{NQ}Ht=u~T z?;gwzA?6)ZPvWwhcFUtXxN;sKP^pVXAbm{lwf?N+CulaDBWw|IEU!iU_qTX)evuUs z4}IU*T$8T)Mm&UjTwuREJDKkL&o9?GUBdxA4 zMi8aa49nVzp-o+Tj(l2C^&8r2m&R|3<~gyMiw3QG6e=4f1eM2<9b1IAJnd=iD+$u% zr1{WsXKQ5agsd$htLa^j>R9Cp{G*6NdWobgk$^6iZnlVAbKB20$>%mr#Gq~&7s;4D zK5@z1OrsE83|21m$PGZo%v7P6kuCxT28*Q&g$8Mw?{hGm&eeq78Rg*s_}AGDqU!hx zzd<9}>V$E;>jZ^}!OG~~{M7o~OLc7L`cp@29kzZM42PBd2GG(8zT%%$OvZ;tEc4;r znkFH8=t;Wti1|?NXumQbZ1STe58p1MtB3)Kh}s~sovbogOIbieC+9lB3XFMaoSx-(gsoEqU)9@$Oy z?ZwK6^>@9g3yrc7NUg*53#j^uQ5ovb{&Je%bCUhEva=gDuP(KxivxAp^Xxip@{zFM zx7Ft|1JCQLJtRPr4QU_Q_17dv)(eTsz|3xaKWi;tUqJLMUq7%h4!W1p1Sbtq?T8qX zpcZ&h<2wBL)^b$mXe~)Z97#%S)N*;g(bHztf}X@{$I}#ZP0ZrKpGw=1f41CRMED#7#?q2-L-KjGbuu zMusBzD{=UYptdl9F1+c9;T`svJmTq!Q2y@|_$;m$Q6i}_XYwQw0!<%JvW3A{)p-_W z7g+7-Kr=guxoZ<3kUVZ^_?VnU=OohCn_6L4?*VnJjX@oupmPMY_b^-5?yN$=l|a=f z3Iriz8DT(RUezcGE}_E~TPi1QC~enA-l3v8Inr@kPWly+r3$jRgdyVuDi~RT`rZ@ac{V z#rZu}prf}WC-3NwkdtAgv?+@!)!t9*c*_JiBMcj+${CDl1oQPRmp&QkoG2Lr@CPD_ z&t9JDd-imhcd!vr*5X!^mSiQUT`y@96?OnDd2ODuj9p|%D8w@)a=9QOy$XvQ?evzx zr6)thQ%-F&S#=E-cjFB&-4nSju-~_&NX%UIuBCclE5l;J|Kg#2s=E&fN10(ew!&Si zU-7CeN~vCmF^>odKvJ4UAQY-B2TYBHrJHD0SYevkJ=f{9B<}^(9U=T@idZF;f6)M$ zxbz5O9K}0Ry&p&4jxQxN8U@hsixRALQgq!>$gf!%-iB^I79wNR;}2SVDirutK_G99C$P%)kboraQ)ra{F)Q>tV?qF+Zq~Py$?>~Vc3%7}6025+^w)-}8bLJ#55d{zpTBr|;Hr3)vnowNQR)lQ!e8M3b7R$G9K{ma-c zaNy8FeB3{7iW0~-Rf_ZU!2|41QN1~=(z?JWmy`K}XFbt2X46(G8Nqtq=&o0VIX{>^ z_EE^zSLra&HrbA-eev87nR*<#g){{_QKyEy9*&Z|0Lcm1!Xn3hrxieKZH6Hx2jKgUUz|1;w*Y?r`JX_7Skh{HGJ%E5}_-Z zEw)C(29@Fb*QnHPo?H&H56Vgv?J#apTd~w>^ki3>Ue74*Jhg|;kQT_5b| zIG&wxG_>7Sua#^!fl>!8|Hc_B8_#bj+_t`*!uL4B6|L*-c$ACi4W`0^rHu>W%AB;~ zc-}Jn7QVVeDG><1>^PW5NCDahA-7Rxu5&C~)n_&PiG`h%#somYc9?e{LA3`I)+-11 zTBym_^J2fq5!h3P1oyc7fdTYvb)=)BT*mL{r(kU{%@h6H7(Lkj zIgrkJU_8`%kA5a`6>IRxdG2JI;VLmp2!0e(aeK~i*a?pi?u~>3@ld`(&Tf7u{qoR+ zNZ|P7C&0!m^{{OHtE*;!zQ4%hwD$1(^Eu##I*Bwn9t*HyBE{_g2hrSzo4^}gBfk@P`Wn9^)NvlfFbjk>0jOtm#bt+IS#qQtaHtTvacXfXs z6fjqK>;;I+nJv68#S|xoMUxTT<0US<2?G$RmeDG3pHQqV47& zEe{Omn0UU?HR!6R-6q4-OAqSWQWz=8-l6@g!}{Jzh#{ont?4o?HgcuJqTz1;P)pga z%#DBWZ;Z>ZgPgNVq-;wWC1UrDit|Xt8mfe5DhSYB3lzvFk7K96ACy&8M1CCAqnuEi zAz1K2t+hJ2&pcOM>J1nGj*#L#q9z!&Zs`s&JaP6kuDy$^VtIxLB(N3U5ZR9k+*}$0 zH0-Itk7=ngN;NMJ-x+OW1Esu6O2|n`MoS^1nn*9CQ<$gQ!Ps=Ox76KMzwYO z#Sd`yG?b7>%O~`G!Gb(UKCMWQ6a^@-4ikN`^v_f#X>!4;{1Edo2Abt0aD$$x4cq~RVU!2*hAunx0zte=W1D~e3rUJQ_bR;&IkW85g< zBlUeYwIx$@%-P-a5)Hdv2tbIgllo`cm`16D!nKONyGGGkIQX_87aT*zBBU)REXvUS zB<-Nztl6Dv7CEra{WkLjQ)KNR?WZ9ed`~^0G>(w#j!flhH#WZI!m?{x6khZbTL+jt zQ^$}bAxnmqm-qRFg(O%k7I7@V=HqtV(7SU~V4+0It?zn5XEHvYQcCtIJz1*PyLyas z#_)KLM;cCm&N|#J5!}hnJL^9+eP(@!Ai`w%M%q}M6}1@zX04dkEtZAEW3?N7tOkBH zdA>H74wkXraZ;QK1|H7PxZgC*QUdNmb-VJV_N>!pr-Zb4yOWt;cIJ+l`Zm+QZh8)G znLtrc=Tl?hMkL;!oqvrpU!|({OTdv$*#3Q5ayvYRB$gY&N5+SSgyL=H+KsUzA&6T*RV@d|R9Y>8=2wiE9svl4Vz<|Nwi%E6Tp9bu z()0W9h3yxRy|%}HPz(IvugVgGjcIdyLKaZU6933>G>Rda;)x5WqN~XKbK2z=l8V|W zx#dw9jhSkvI9$SG1i8bUBmp+EiFpReSstAr8~t%3Vi4{Tf^YdC&>dlmOr%eW(Qa5& z5wqGuVSSlOU>zzJIMlTBzgU$f_h?hY#rN%$O^V^K*pQvMdI-HreA`c6n@bfMSZy9f zG|(+@Psx%3V!bny9LfiEI=AzTvo|-CZqdgU#M#mKTRF{twh^HXkpLFar)LD$tVcIl zZS(wu%oHIEYbsrVWZNaAtd&CyzsjIFpw9S^|74ikl3Jc9Qv<7*f&9gUy{sho*zZA3 zuvCe{0=Bj3*pnKfd#?qibNRYAQ2irO2FzWLxe11uA9=`Rxv?3W?5RY1HGTT>-UcyO zJ%vu`70FdySry{dQ}eH𝔏~ekChFp}5tED0&`dFxty^vU<&mPyV+j9eIj(%i0m= zf^D3>Vc&IWG)arTcd#YY$TL&7LyPE5Cj`-Tj6|f6qXw#60#)G%pzlL~`Ry zw2gL@s@}z~&9FMU?2*M}jxw(8mt)^SWHCnod|`mo?j;TDS1q7w$yMzv5PT|i@EwG1 zoL=Aixl{^22n=RDcI-61I;|@U98rH7L{77Hrv>%J@a*~$#g_rOLb0(%x`V6iNHqu) z5(#wusLxJK%)4qAoRNR1+|i--`)k@VuUD`_5H$-T0Y-yWWfX0>rao`&_^m`GwV%OG z&cOInY{;l}{ss_vD-aS289V)tp_ViSDd_7~&^%Aqe5~FX@W2kF?whHWji8+w1=haZ zr*|X&n)1-*g%|%0N1Y@fIInh?dn%pF^`TzQxeW09a6bm|IBVtWAeQb55LO}`#l%5| z&zzR$w6jFYGH-M3GBY@acwMVce`EvA-X6ZDT!x&3SOM5mJh<7T z+oL)A$1}yyTPK|u!Bp~BMnY&`s%%O_tCAo6_V}-cjv%rcO7w++sKF~JbuzD2b)d23 z-TO7^(sj1EISX~ocMKs~6fibclHhtMknHPlEyx1G^mhBre%KRo8)Q`=<0WZNxwOiZ ztYd(%I#AQNN7g@#E|i_MDvV#{?fr86;H}yBjo-qkXAR5AnG%K>)kM(HIji|;tp4&3 zwR^hyyl%ANs*gz!usDyv}ypP z@tA7^Splks6VGFf5>bq4nF-*%Gx1I9IwNpbyvpB2xn1n^FIt02#vEy? zhj^7~p1V-#{(?L1U9n-rC8j7GoQj{=1#hNXU3dB$+xG8l1z3ny(w2o(%B1frIW)`* zZ;?lwkDN`>guz|^&k$@TWie~sR{z0^n2zv>M^6?VWly5YO4?B@R>L)H1(PB=!~+26 zsqi^C8_tdrCARWuWHprC&vaPqo-@oKGnsI45Zxw*G6|N z-Q|?m@Xc$$h~QiNuL8Rfv|E|1K(>Dw7+k~#%yZG9)nCmz|JLN7JWv}`7(iuMV0Kra zw1m&ar+9hP+Pr?!VS;aFAbZH4>tq1y;0)uiT797av{nICyrYmNMrb7h5aXCKO{@W% zpiJ;JMs!}2m+OeaL9U{m&J~W48r?*#PZHZLQezY~tEV+667*Gmu7E&6CiXKQN1`8Z zK|LC!_tIYz{UpDyW5Od2lG_eAlyEinIct>MLij%0bXM${qH^AYNjRc5+4Z5cf2StK*k zF6iu_VMNA0=cw&%ZI_@Vor*WH$u{pcMpdH*)Pd-6=~$*7yYGKP`$3G0Vp*}&v$S@u zehSNkgs~IhQOcn4rQO^2hzrm+B_2xsvAH$6cpy)8+LC+uYEN+-V2S+N%DHBi4ZkQT zv3Qv(bh4Bh7KXSa*0;Zp2&&vDH7YmbRmEbeo|sH%p>belora9(U9C_S5Oo*9{Wf53 z*pWRYdItA@QT)MU9pl^r|C#CuqM_tiAY`+%j0>-Jz==KJV-~kEF938bfo3>@ktWiH zwF8mhmEQ&t)my+KXExo^q#!-%%KY=NZGE|`zjMiIn?tX8>OuVF{PuT(`sR(+YeL0q zob!^te~@XW6O)6PbhO8MgsfZ7qWkou8JAG-_+EUjQAP4GpP^z^S4D)bT#iNNfuokJ$?U+xL2;Lp^8_Vb2KNGUjzn0q`O>FnPt_?y~w;7xY`ncI#*jXB;>o~nrZ@o0=JwfHpjl;V^f9HQRd#yc>Z~)||C%KDsXhEa2gkd8^GP!o($$1fpT+|0r7VR?_w5c<$B{dQHK;L?Y;zx7nH17 z!e#n@uQhl7sP`;tHh3-(8;@SfTv}v_*_`W5 zDGr)fpCrrh(%Ds@6ea@P1{{l2P0b4i3nq1PA^_a|BQYRQtR@kXN=kpDDzF|{n!sDZ z|Mn8yMq|zx9dCZnhF|f5BV)XK!$4+O@PU_$l~KLKM|JN5d&|bxlJ%M?^vY%W7_~?< zW$8zfw8tLu34sTSq*fqHk%kO4iIieqtp>ad(J5n=WF;DzZK8Dj#WKS9@@H&%;a4w; z6$WUykj$TBSb|c(n99oyhSq@>V@M8?E!YK7?=vf#W&TOAyGLiTbk}fdGq1L%c3xz?$urjo2vJ_Mqye;05SW{GcSH%nMWv=&{CmNwK6_Xg2w$!X z`maqCsr`LsR01Tj;io|yX<>KX=3)5t26uOFbY=xYPM+Y0lq(_(MQj)LY5T_2hu;sF zda_JE4K5V1#`tPhDtBUAa^^H112-CFP;Vhbd>yf4paWwqx&$_@d|$VggEvVRE`ad7 zZG@pPfGoAWU(V#kBEu$tCuauQ2sCGWyu@ee(kcC91NnquE z+QFW3g)QmK!l{OM6$t@~hBoG3ei0SGz$GBh2LNhRH?ny2yzr&^$ELtFTS?9?mm66` zdyO&ch?3R3!ewZV-yU}47a&?$EdWE~HCc+>&r~qjC)boa*LOcqiYa^puFw-XA{<WgVAgLBB-)f&-WjZ}Rt6 z11+NID;G%OCZQ3UGYc&&Eb?0IPysP#`FhBPnI`B({DLZX4^i6mE#v%!l{SN^uZi0f z;ukZmEf)QQ-doH0wy;7;|8%H8B>Wn|na9gqHvmAVPdRQb*9=0tCUTj5yo zaxb0C0pYF03@NZz06;&YNb%_X2OcR$z0MQg)EOL(bqcnH~FTpo^O&t2SVgR51WLD{LC;9Jp_B+RYmhM-GI z*GKpsk#pxe1&cb>-K3W=gW9u_xTw%cSQpk*SmD>Zfi83LfPK0RK7dpqP72r%{FV%c zt-1yLXgcEr>Sz`*>anJtEi~_HiPQ^pEHNqUsvRWwG^ zdf3NwGaDr3*Yar$8rqzg8A^0RIJJMfD_0Bp3TbG=O661{mb`q^j~E^U~@17QE6J?+Gomx z#=m-ZQ;;_s!%Z(s{!xIeIS4~7Yc6T-!biG1HBru8jqtr<3j>gAJ@bYBK^>tzFsA>F z)c1Fb@zWssY59eFxWS`WZ+@T$v$0ZeHr@co*ZflW?qF0zt6+i0%={N5HuU&E%HwjS z{BMNyUb@BcB5i91_EO{LnO0Hx{P3+FsP6CJ7U zm|DhXroqD`I3d7-_7UC`wxamH*S$o-I=-L|1$7vJC1H~ZO+|poG5|Itkunlpu$<#)8S3jHOAQj71Ugi?c*Sf^N{w@Cr zSycsC14=8(@6U@>tCwN<=_7oDZX?uQXKn(?#aiiY_SwCIcp6kcj^xpa+oJF#r+Ca; zgKS-|jx*jks~Lni9WBUPgEF(gepEi=1`G+DKs-* zVBErxZGLOsd@4|fQRFBJjFD?=Sm3*X(s~0HPDVU4od#g(U=E7~x z73)lg|7MgFX;6c{dcIu|(z^>{e9ObU{P18X-*o4uVOm>zEZ+$r#HTLTw@U<$=VJg` zcMxGJi95ndG}+$^ns<2+cz3tf=dMe$cUPdbSbJg{Dbl7nQXhv^3r?k}ya8aGk)S;w zk5D&vwt-S=4jAV$VNF$n(uFLP47Gw2b6fXozi!h8{)|@uY z4z@SEoulWWB0?CtG_gG&lMH-}c-7q_n)JZwzP;^R$52TD3+786gFA6!62j=H9cL4r zyfQYRm{}7^iRB$g=U2JiD2$4ODIesizB&@JYeRF9xnw&gX6pq5DHso$;&Fgvp%f<2 zyo2)g??orfsE#x@e=^$6EE*_kZ$j$D)ua|?-bW6B@i%)SWX1`7mQ zig%JhD$ND#(vSV{k%<03X|fTyEKs2N_m{D@hd1h_{Z=}LF^=z7sv6yW5tE~fk1%S) zjDDrNO>bb6pqz;q+5yLD?3{qy%|EM28}cfEIWKIT{E85;PBM(Lq04dmop+q%a)?A`*6zDSz74I|-oA(Wl6vS}l3$`OV4O6?NKdom;J-%^0OKl5dWn&?81 zAxQCVv|8@@M9gM6`*N7R^xK$If1KX6 z+^N*^M<|-QI!-RjotF=~u{|qjo$Zuo0pN0IM;;aE?R$WZ0UFdFbUr9OsxU1fn8l4> zXaUF==OhPr+`RQ*cJzRlza)3!clnJL$BmxrB5qHQlnwK`(988COmNF29%$fZEY4Py3du_$eHL zK}?bf&%#|}m$UcZ62bPu*x{^LZ~S*EagCEfe#fKl5*vK$7Zn2h;qt*NzZj7MhMiGr zq;llt*d81WreV~gH_$eW7}30i4y~smLh$0z_PE4PAJL774?MC)Lz7zHO-bDNWxD`;r-@so117_rB>=*=U&0oOPt@oa-(niAw6@ zw@kPP#`i+bDUSe)+ioToh7d<%cfkwYPMJfQ@L}eTx^1BueqZ57PYL|_$T!}xh%4>H zc9L^jkiEg>FPFrom-VE&SP+6D5fP~TIQh4`FG(nGyODO}@Z;U3zbz2$AfbKNFs-V! zYh>z21aBxK`SoT14lkyKxW+$@bX=CF4}HJ9;Sl+o1qA^hmI>@60k6$C=~0b8;ily3 zAoXMO7WrWNN}|kckFEfz3EUMSMK#7$Nb*gX=3?#l`U5{7s$_!t>ijt*Eqkk&w0u- z7Hi;VzSsc2OamKJ78(Wvi9v*WM;k3Wk5ee&w6(3L*zVkiZMzHt8kzLI>s-cYaQzpk zlayAO1%h*X%t@ebA2r(SNxAE5c>>??EIu-nWfL$NeKO|UbPl31kjyVS|LIZBWHr*z zy8!#sX1UY>&y`5G{h(t@+YlLcNkMP%1+@9e-r0bQD{0nMkN77XX0q}VZ(pK82+>A1 z*@4d}N2oKx5th^zw~|G%(98J|t-GZmQ>Q&K5fG(dxzB^en4Kucxwk)k3-46v74ji` zdC;N6>Zr~^HuC64yYwJ*uSTaq!S7Mh#WZhLVD8EHB+bu!K4^=hMCkq^WG&|O;X3N~ zKB9oLqRxoB%Vuow^98W$?4*u}O4dU``JB2H-{din7PHILWxdUSC**+ViQ4J1gn2*es9dl7c+L@2m-l#YR zC@0dy>tYzKY$z#XcCckK=1-fUTnLEZtUSP%uB6&jYH)LOeBb7gjglf?Sauj&Sukw4 zr6_zGOm0rQ>mF%?z0=pDnCTHy*hY2KSpn;ZJ}UQdX5nRCawi@Y*|Aps4TMz&xTK;d zu1cZ;+1nCI=iB`RC$vTN361yaZH=sd-e(B8NZ77l4NY2ZJx`&QmYvEkOfTe55LJLU zC6ASBLf5=br*)=8^w%1rbs(?gbcct=oI+iA5z>HRRTZ;&IIRtJ!Z&C8Sb$t%J-umU^nwMXoQ`$d+FJM}!S zTw(GG;mc7I(Una3*Dg(c*;Tcz-`s#0wN24Y<3EHT0ft4?!M0D7BK^EYPo2|`I6+%h zk2P2!xU4N;&tb=zNN9Gpq#q?@u4?I>8MYeNI&!$Cd8X85&cuK7Iqlq*_ZE@X^IrM} z@Gr(qpWWN_CA7j}I87=OocXD5AZ58({V#6LS#y@RIH$#+{80{A9WI>iHSz(!$#qZP zB!=XD2jHz2S1lj%(4gz>?7S7A166408t1#zU;MZ!%^_~in~o_yIg|Z&2JWWBt?pE< zOq8ZLD|}>TtY|V2jb}+zTIGJ5q^G}#^Gg;aQ4ALcar^O&P^emJr#kn0p;XluL!$s& z-?Q51GJ*z_1u=wlCqySkSs4MUqgLNju#0|yUovQ^;V|QiaciVh3S}pUw)-Elw`1FI zgLlsx<0U_JOU|!PMSomT-yiL0uopCi0jA~x;OqihJulWFGCgJSO@cmDc-a-#yv~1G zn@Vl3Hfm>VVH%!-T3i@SJ!+3Kd}(`T7`!g1aZZX{**H*(GxeA7bYlQgy&_Drm);ja zVk7^AJ6N87wc)cg;zWX^?4SX#it0++fu=H(T@F}OcLkOa7QOLH!2=xNm0k#o-~hL6 ztAujE6p^c*U8f|}*$}COcEzt`B`t5AomA@B0ZF%v9-%O(Ic$2`oG#dH`RtUXE{cez z){XTb?}Q}Ac-`C8oOggLW>4!y(rErW6xBwQ3c}be;op;i!|M~im<{YA^1(4PUzt75@*E3uHD)4@D0Z-~znqUJX)8H3L&g69hxX#EsXD*lfh<-f`F_v*|56hoA0 zrG8U`I*jDbOa@@esw7!2_74rVY{oAf4X6!vPPU`D84HXG{p4*J?9i^aU#-JLPNyG> zc&Lp2x-??GwG#Z%4>@FI9D_PXYc&0o0(`Qo#yj)lnY;2+RR_qQmI z^60LSh7rJDAI$*c)$`kj+#u1yI+TUB`HaeFwtBTjI zq1F0Cl638IpUn+{|H8cOUsg4zZqL_2lOk}y6rl^Th2w~?sn9j%74O@i`=C0M49+t~ zF02a?9CMSBZ;jd~(Z$#mSCPKW2m@cdG-mMAC+mws3@M zm{mLHX{tjOLV2e>w4&TMQ)Bc)9e|~}tHM5G-uD9v!EvEsUNn-=I|G%(GJCAn9NT%- z4;?^byl(~l$|hTOG*P=JG|pSl0gZ-&z(dn4YSIfQTj@Qe9^{Jq`WS-opc z%L@^_+ca6%-P6TLd+l*7jSL|y{~BE!{3+Hh?(RqOQLy*YIIewH|PFsq1>i!=hLAiVL-m>`U zKzreKj{ySLl1Dft z_E$nKt>ScR3yv^4C&dyLq?y4CpmeTAuB-vACE9z%LouZ|O9>x)nDY36lTkdda~42w zR#)0ns)u>9B`8PBJ2yd@N>#aa+@ECr<(}>%fvkUG0dhpT$%#mmNAbg1fl^ki<_4R8 z>SRT-SBUGZl3!@d2K&OQ!KsbvVR=jFEK}WLAn3`RtH-my#^^xJ!cL6^Jt3O1q@O*L z;!VPFpp{Z<$)d)q(tl}jdy4yBgVzFhsnt)F-{ho*Cc@TLz!IkF;|~pqcI6a{m!N>X zj^b(m70pqM2ITtRCC}9Y(S?du2l1wIpM(m_W>2cy4wRRU-Dy7fd%_c;Cq0(4{LM%` z$^phG#`IdCfV?w`N&bPU=dFcB^(MnpPo$m z!n>+9P6QJB>IB+DFk<2NXA&t^TtPWS7+v1Ux8d|zeNGmtP#S3iuuwJQR|fUbHb!2E zi4CDJ137q1oo1IhO1xD zwhfMqKB)KL@=g+K>MQpxYm55$?Q)Sevike-W}B4xCD~KYSk_vPtdB4v9m(@MZ<^qlv%me{rJ zqI0D zQrL78syaxacPB*4A7X%2k0c@shk!2byk)NPQ>; z$rM1Lg6^!cWKvQ^ka_L8_xb!3{CAM+Gz`b-PI0<%TE>ZGZ~_1{alk?MrEdMxe*{kx zHB{wjd1wie3K473D?lp+7hSol)(8W3I)?(?v+d%oV2`E^g#xc-*tlkItS3g62&0p_ zT(X0hf6KhSWJ&|jr=_B0l&B|7X{C2He3}_*au)q0o`wC{1nD>Rgk_wcvWb2INw?l_ zo{E-}`Y5b|oCgrIXR4irzyTqJ`xl;aKF2ZG6)d0Of#1WqzH1Lvf_3Cg8#M! z??4Z7$rfh>`kg#Oh|cV$i=Y+KI&qvxEv_qd0#Am}T@29M!ru6uiah38+e@U|CPJcc zbtkLA&t}ba8Gtp;0B94c-bt^?Yp-}9AxXJHUkn?Y8fyV(XqI4PABQo?bM!ICY*2BT zxpxhtSg-Q0ZWGDP9L1rkfQyvr(7V(hVYLbe7aT4mfkgJK<=Yuzxm-tH_W+(i_$tA= zycG8y?*Ohrp zca9T)@$YLiVn#phWeSqG@HpP)xxKaDc=wpkY#1qviT=JS}$$;DAvo17F zPCITwf}YglhYy}(gM|Xqu~f!2bdqpCjcIu9X#m)VRxwwNJbCtG>dp#s>d+K(mc|QL z?=`iw7p9$rfFxHa2&e>tiNI~{3hlciOk6?lt9Avgn}Q3~iWg8MEg(K6(f{AwqA}ZBOvu6MHPkhyjO!y44hn5`W^n%ZGDPuL}N@y}_ZL9ou#A^~{@@ga=^6z4h|E#yIDoHl6%ZfK=V~f8pG8 z&JYc89(XGxyFO~4BoP{6Uu>=JUk!Fy>INiW9OgtuhrClI%frf>S8Y1T=0}o&g;|i; zvq^9Eqv2WsRpDM)i>wE?ogHO$>8yQ*C?Y7ZA4~|0fGG49`C_IbjE2Y`Rm&dh>tyX( zmr#?pf)!Ci^u1J*n2vp$n`_{qkf^AJ;bL4_DjG{Rgv-hK`0zr15@id(VL0yjX#%`W zP4tX_DPIbUpc1_5lr%c79v=mWyTNyZ`}xz{a)+ywU)y)Jp+7OHgxB5v{csnXY!-nG z2VM8|VTq|uC3w5GXh{MOfvD>NOLVba?$lGBhL2a9`_VlI_xXQ#zevPw=zN2@KcVG% zoq(zRYnU9Ye!jbsWX4=;tBZhlmI4IXH>%>cjvmEs?q@Mq`q1`p1Ib!SuXzc*$PFqV zbG@AzBnty&#D$uxAw<`FM{ChN-p;?$jw#Id2z_IW@<~^M50R!{p(0y(vT*9ue%}zdf~ZexwuIbxTai7)#5V{wH?|&KqL2tArSF+jXV-6OaRShg>u0*t zYrbbcf6abWa%8Mb&!3)q#pi z0LDG{vgi{7q+ z40T~(lq|R7WH#N#|K5rA8URM!Niym4Z_1ObJBe@J>5h^`aNCHtT*G_uD?w7r%6^Yak^33?xFO3cP6I!#7P2BFRG}nkUx}6%|?AWN0 zf`b0g6vHwHp~sXNbN4y8p%VHGImIa|Z`M@E-pG{|um^LuloZ_XjsO-&qAEJe`O@=< zc{o0Y$oV>SUqt^dD+PccqHsM}r?LRsg<*_JV!4sVBt7ZLic;!GWQV`2c|C`!$2<5M zjPanx_)Yr$?zH*Fy$y?hc0#L?vO2s|*h2lhJcSMpWhJAJW)NkoqCKwsh%yL#h?Ic~ zlkHalA)TZcm@KjqMF8xioCYcH?{8>!1|UNGJqRqMs9Z5@ZUW`k@X&oN+bsP(@zqS~ z8a!531&_@%<(47WcnjV%GSMzp$IRca7y`Q*<$t^5abYGAWRsXrUa#KQjV+5gA1CI< z4VEMIAa}$TV5iYFVz_G>nEkQaH1;* zL3lZ+V|u@-g1GClApjc+L| zzu@8Ju>GZzArh6(Us}c|UsBEMeB##Y=4G@i zHeS46nH~%s?mUgNh|oP6XC$#dH(d=WA^kei75qYvZ(t5JO3(pXu;0SPh03&xEBJKw z2q@1vh7`h4?D^T+?s&BDD&*4#Qbj~cE&TCe{2!AJ zc z1{x7KEzsRUCwD!W)3JZkW<#)zAL2q>}WOKUH?q8z5_RC{d-OjpEUY9Q$@_?vc#lsPW$utoEUpGE<@xgK7Ax-I@ zTIePZ)!^(^NFx>@4j&&pt3teQf8o+OLmfebSceFKm?*cksRFknY{_}ckH zsvQc!s0g&?g2Jp14A3c=HM#ex?ufi0QSD|Sv-@kCvcNpxE81n z8zAzZn?ID$;F;h6B@x6KdE6Ng#PL0>86*#Q9+3#z=ma+y6u1t5PEZlEC)f|Dz&`9p zrgR{JSA#z9r)FYG<9>w7 z@}DJP69ws?e~he+R4VY`kibQP9A|{vCxJm=@@Ru&TazD@Pl#D5?8kL%1^__)gD|}b zBoAZ_D3|df2yGM*g!ojj{$f=S__frXm6Fo^W;`4J&wW4}89)PN?KBiL47y96hj>k1 z$A^;Ie`jZwGohCT<6hqOkjE(pn$(IM^)f}COi!}(elxW^fot)E)q$v);aMas0y5Kr zD}3>%@qYS~eGyQ6w!*zTB|UvnUH01EZxi2qJqUi$H+RK!cV}k}On|+2TY)jh3?m_V zt#X24^%YorcRECRZgdvG{!*^Uf*jrY03v*9JNfTyYkpB5_5J~tCqn4=(hN?4M*5#x z@t~4m+rb$*MN|+80@JcSCJsIf)tNc5>9E6?8nF0k7E z5(aiI0AawKaC5+maMShp`BnN66ZuwPrO95wK8kEII@CWjgzWY59}Ft6{OL=K9Ja-| z>78AAO@+PwVB+{AV;9wackleY_}O@U=jRx|+!ohTDR*Yhli82O2a@Z_Djo(1$Sk#NS=(pr64y2~dd#*j689sBqg zawAENT?>iOW;144f~43YcQE!jKJG?z?gwOe=4OuFaDM-1&(GpR}XD0hfk+n-AJ4kzMZi=zotYxMRaMxNRbZ=v}>k`bZ>XK`3 zNlh zRU?NG)IY>jG@{2Cbu}<$$Q*jC&7Lz+IJ(vBbHhureuq(li26`Lca$8})Kp&G!InF` zVlGb(T92v*xSToF!EKv=MhMkqF90$c+s-GD)x4j2_~E$kzv@mb!U}BSF%NU{^?93D z!aA8!arc3=QR*}Bk}q*NKTU+Ly4iC>S1t1@H`AQD&&@+Ws?^c=PG^|c=XIBY_WVyc zMo5(}j{;h9BF<`G(ZwUbIcA^iN;mjSS3Hm5I@UbChxD({So@gBdX)QWt{qzwcc12l znpp1>6l}2jPAUvve=yK3F-FW~BV>7SSLs2hX?6fB9?xw^zs1+*D3qiFNO#GU5EfkJ zX7J#^3@W2f3hb7CLN=$-?RRD*x7*vK{X+YV*ysJF(8N;4S99VhXPCNn7QGdc_9Jmp zO!75|$uw)%QTojgr zV39qrnXpsT8hXAh6e+;T;<`=m&(ExBa-Fz-fNgAfzH#l{I`|#z-g{niVCaMxC;COI zzTRj#)^>IJ{QhEVM0f=H#WDk9(FK|I)2ct_17`6yoRA}>!vkt_R*jRgb`-U)@q*;u z@Zt8ny6(~)e8{@8rupfc<4v`GiB@+SjI}xN#j#hid7rm^IM0(++M5bWo(^JD!Xwy# z<2&cMewm&))pxiYZNd{=JilNi+kK3Pz10R1_u)7;g*5&(bxC5c0W*c0QXjLoeU$00 z=zYv$*hz5*mACnSj)l3N3|MDUx^l$YC|V8=8hdRJCIBA!D6;qieaa^8?jFb%yP%3W-B&WG>g6i`NRkp4Eq|Z5 zb(5+KyrO@*V#>JlfLH3SKBDL79lTYI3#r+DvASI9r9RSiv&uF~hLM~1XlxN;vV73T z7@NrO$(xsisAy4K#7Gn)lVEB&=|a_9JT$Ppdr26SEYv2opzobbugYK#+N;_F_G3jo zQsQUvAG7}~{Ie)_fdW(dGv;T1)wTsq#oMQ+)+c0Yk{<`0k^Q{Z_gIGWf`cK%XN1Oo zZ5GOLG3FDH#1y92cD@{Bg-3Niez6t~=yH{2 zv|JfV16yWKc2D1GFXH_r(yuFoV+Q4H1D6yXqV z^lW!(VlfTNI%-sO+it8C0>vaK)4a(QZc9>>5>)n!%J=SNPs{jE2vk41LaNC5+qv?J z5lRO}t9=u@J^4PbXTd93>-(*Ttdk5!SLH4#0Ut0d6l59V{!xW=4?<)i} zsxe>Vsi#RRoY9=V-EFnb&=#LBA%VA%eYO-h`%EU>y9q2+AV92Y06TF7dvYP$^eMNA ziv-y}Fy}4{W3RBczwM%LA-tOee zy1ubi9U0Ti?58HFQ(*!`<4{D)UVIjz_ese~$wPG1c1b%Q;M9dE+(vO0^qQ^DnDx-eEATetf^sKIEghJOXKNchRz#Ac1D7`?9-FzS5|gIMx=q14_sm5wT393P;(!_GohnA z5MhhK+fHy>OujJB23RzPKA~z#@}2*mTH$O0~R99y1ZdnR$?jcGb*36FS)oc z>W+FEN!}_UgXhapjdd?le$#Cj7mDuQ!DOoiEy!pXn;^3NE!ym4E#8cM3zFuDR(z{L zN;7ZsN3GX)u8fsEZuFBsU8+lRGV{50_>uc6-W8$==Zj@mI?Flhe^kwZ`{!-|JD(2>>P4NUuQS>#trVOD?Kr#+!+&^Dgv!2Ba|OCBM5{_;fPHa(pq?rT&A)@kf7D z;m8JN?84P)xP{s>WaG7ir^px@;w{by$#hJm-L&h@&CA@*7t<#yd@GUCvcft1554%( zNMzb0bT5s&P5P^Yg3I`KbFs?K#<`qzQ@V>P-vb+LrkqS}Tve5vX-WB%tc3d|a9Tet z5bzyCMmK5$E+H~#c@e8~SPK%IXh@T-)n(6{JD5dLp?7w#N;VkwmxCb;^(X{I+^RCs z$jxprU|v$OQ8V~idC3e%S91OVw|haet*sJ-Nc%)R!C&+VeRdyPBwt;Ajjojv60w~l z={m?choMK~^~^d_wJC#(=85Z?j@WWa1w3x(L`|`mar6GvShv9YeAQwL7gILn~hm(9ae~9$NWPklsUsI7-wiN?POV$ z(cEheT?$f$aN#|;OmwOhhm-JYS>el<+fc6P571pDyW;&kEDvC5a-<;n!KNMlG&!{C z+yq)2st~j4J8MkDr{O7$swCg+1AgnRYRI?1_RM&>Zeib6cufC#L}O--ptLoYvsK(9 zsN8K6{g~x6Se~Jp0U5q^VHWE&l2y>6eKO5u;H|C4*N$gOuVBiv4m`$zTknFt z@s27cr}e%P1>L+8*H~+ph%gZmsKWY+;v}vYmL4ZO_V@h?Nh_UP^Fk2j_@<*FAR)c+ z1Rl(En*xJO!HBawoq+cm%X4u}RW0mZGC<;sMbeS2&!IC5;E5&AVf$_KDy5I$w@)*S$Er6o*C*3E@HdA%6rDz7#K>LFG)Ijlk*(|9Gy1isqqIXtCgPca8D zL?zAa*+z@Ejv#0jK&~~|Rx6q=iR5bPe+{a|#1m~FD!-BWK>dz6Ix@CGp^iEe+UV|o ztEFiP9gi@Hh;TU(!qzOf4lH)2)4FUL@Cn%*(T38<{E@bWjKKaD_sAM>#iGA#B`8~3zS{DB73r$#wZ=fIK7HY6`>ntp8n}Vylk4sS(M%S(Y@NkmEh!v z7d>0{o?xHg0D$kFpioUhfUlB%CF3IPfiWwNKO=NXbHS(@3iI@5ZG*t^sxrgtL5YNJ zdb3ypjoB$T$rOGmY zET(C#u;{rADUS2y(uLd%VyxL(yc(qEV%3ZRw{fxe96vIwf_34s>FR7n)wT!ZE|TWl zGJ031H%JmG4sHWXp>XAq>@yn6nfA|!RrBwS%9s~5MxGbK{@=ISuM}{RZW^WNRQc>) z6e&&?;n579f$ESw=o-s=d*D93qxKwx znbJa71G#yT@VB)j=zcaUDso$gdwflhBfb7yd~ zQMDC&g9+e_`T2!;abZ0~0_z^ra>ik)jkZ#SnELS;2u58jj zCjHP!1fId+ZLP7pbjlU~p5<*yp%WjXyE1bu7FZ}^?{+w&N;G2}7pqP7+_{DweO$wa z=LhED#5s=|he26&C7_vY3wTM+%*RDN5df0!C1vs=ud1i(eX%)K6|BmFMf3Q(Gy<$wze47?(MhW&j4XcKn68C3BjB(*D;^%*tNfBFgbBhqXG`g?M+3&8fVFz8Sc(LxqB+Ss-`Ka^wNgBk8|B(WI3^S_0Xy0o z4q8^{)%5Ym6?yu7GLFi#;1l)<=gEy>F9@WWy7N~r*`9R;jWkhjVgcem9~P&4^8Bn( zSMydMJl5T@XS||1W1McW`htsqcaEF%T1R7!Rh9(Wwx{7s8z;Aqg&V0~5#-t@D}PfD zxEQavB_YW$>}`_;X^|GRk!3rjfh{~6R~vY^8)F%x9{kK0d3v$;cqntZ?9Wb$@tad; zVDTmN(sRwdJA#QaCjC4cLZ*T;yt&%{{5I(ov2i+hur{YWm0jtgAX!_g=F>DW-|0D=TeDnzLP}MA z9ThuRz~Pqc%@E77SR|Q|5v7mBD@23x>30Q!&Rf@0ssUw5a7x<=E3VIKzvbpDuj6); zEGTJH`!-W{-Na;i783*-;4>Qc)`DT#y*zqz57sv&6L0GhPk^ZSq{WM6$!yb#;RQl0 z(Jkj7N!8zFc=hnriu)=86VH}sEX7Kt??I$w7}_M>4@`ZFHTN;Z?IKOV2QX)SQq7tq z@L9M7X8$Tg?uj6aPX!onz5|1KL)TI)=wI(qdBI_PPY<^e^BH3zfe%+2E;W%H*-s^v zwB)nagug%;+sP*-YubMyd|JBX-$71?7kBU=(W4Ccl@uMEhG+i}=<7B|Zep<=)s5+) zTAAX+`|(g*XM&-)fqI|PysA%A`Fg()f~ujFP!zH*PmWrJM=UO>GZSSa++Sa&bC>y= zyiR|IuljGRo0d0Zfv6J=gOD%N2sb0*Uy^MTtba zA&-?9bfuR1@#q18k`j-I-T>I%RcL+>8Z)fdjMrtX0J7LA!B6)zyp(Mx-`iJMo+GuH zOG~?Hx-3^2Wd(Swuvj7(Cg&fWUP#{;ZXvVvTb-m%XFNzBfpVwiecP*ME^+!!uBJnO zquz|UcRg+UYvYlKV71I7q#DMyfaHJ#Jh2(NE1M;=(QzMs_ihFPBv!yi|82Hs34GUZm> zY$2D=GzzfNq>+Ho8PS+TT0Fj|C!ASFs0<5 zO@QwB{iQisT~bY@33~`ArKy?8mr5;dGD{z~N}FE_DBSSSsXyU4JbC`tX?=fz$&T!> zlK!cAA|gj>w$P&DG*h|gNw#&$^5NyrfCW*1xI0i%k9f|W;)+5X(jC6(7e+=0$0`o@ z>^8IpN?2=!wq#3r+_VePw-ZnR;fAtY2GCT_v?}wE z$@pd%pnFR1$f8+09#u5LzPuP2)(ZndtirTGX7MUYmc!Kz6bwhldPAt~G5bv!TpCk7cSD_veh0_oER4(A2k6$_=_MHXE&^GG_P&bv_9LCQcT4}EnJ z2Lkoa^}K35qU7DIml6nH;DYoL)JlJh(W5YSnw0g425Y}dUvTrQ<9C}vc4I(xIqMw> z@b+#A4*jap;cY~o3UY>bQNVCo*@|pCg1X}R+7FF@8}w58{3?^-AFmrL#shzednnj< zdiSgrdA)TWacJh%%tBm>3on)SR;b-;^mY8}K}2U|+fE`j2Mz6AcWSVr^)v0GR0#}7 z#z~-kp<|j7;}ctKUcF~ivYh-Q{Abut;N8dXF$=DtRRd^{*b4;q*$QCYum`2)0G_O_6k1_DEpdww1*LsI76z$}7fWjx4Ze8yg+_`_Be%=!z$fy|}{ z_|xG6AH?)@M@Ix)YTK|2MB=H7ni-3|C#XdK;zz=$*`q#x9y^NnU06<=UglA)J^RT8 zrjJ6KsqMI+)cJYEsKR6~^iMqXNp93#qh#Av$BG0mSH4`3?w;EW;bCa{q8g#hk(v{= zKTD5%$rF|}!9tFj2f25uwV>uDFqtGdNs>T^R5TsG&RO6Pf%di>%I<;fi@_jw`=`uZ zmqW@j%?HiBr87(y$;+rg==>7dCc#Y98q0n_US)ycLwGG)zqZ|Xrt{x3FZX6eJQ3P| zvl_aPG4w-M^mI{l_w#$>0y=u$^Ogi?=hkY%tUnYiz};5yF3r;og|)@8jqjn}8iX8a`fs!~-8r%?o^5$ZKdJ6I4Kur> z>WtRyT1KBr54L4|mpOkNGcANP21^v22{r$Ptfw~LMTyUkQL}KwHVf!JyqNU3+z}tQ z>y4Hoc*o5Y{kEiQlgl`u1eAtkg!2%kQ8&9U0sGeKcyj-iY@pH;^AjGg>KRXE76P+F zN>i=%)dd%^Ot9-lJT9cu3bEnp+moH3n1q)>e#f+LEN)=JOHP#G^(UxDZcl|j1Qq{) zQ`S?N_W)I16N!X|qs}AL&SJ0egsICaj27FGY3m0{uW=c`RY_+A6WCe>Ma>pEUY5S! zZjcD$kKy<6GrF21L>>n0690G z*>Sv5zr|#`|5hpI*^9=r9eR)zYZfSz21{UGe8UPuLb2^yGG>jg4m=U;?`3fgObVIc zAE}Y5ZV!OW5k=(W14c4I0e3dIO)5X!CmM88q~}TzO4riMH2(OLcS&6qY8a6#w1`R* z5$nnbv*w=T1-@vkpZ2FM!kD|{}t(chL7D$QIor{+Zd^g!mbQGNT!(4Sg@E6`MmbDvI%nc!wm ztl8~){QXW*m{|LK61tPsXw9mBI#vKZ9EZ@ZZ2gM2EI`#q5!mRIEwzqdiXub-_=~BO z^J)4{)O3PR!np|2{l?Pv0!<=&W#Fz!QE#l$`l24U0(5-bANLB?i51zcoN;4G9*&Gi zz_`s?qM4>I3`8cS-M`xW9`t>;bxk3hg@^->UrD2r+LH1&@vk3jD9H5THW)CdugG#j zA#v}JLA=ee;CMw#30EaomKQIgBaTN}$Y01u{({%Nyper^JL<@z z!}q}h4yzy_hBH#|z&zTkn|JVOInQPoW!N?emj4u7DJ>x2jgZ)P&M|i~nsU>f+D=!) zpDHRWUSwwNuHlaO6{et$^YKCr>Ty6xJk*zdqy^R=m;WMg`)xE#vHY;kPDp5AjqwU8 zm9V%rK>KGGVkS?A>KXR4D(h~}V?DV6&cTTH7ed3rNNIabci}RsliXGmxUq1-NvF1g zdw@l0J(C)7p-PF3UxsG*z(hC+Cm9z-znDC01*C0Qx#$L}kx?IG0(gngw0k%;tJ*$! z)En>ujRNZn-cVtJyb3o zja69bb2tLWoh|uU#cTb!ot1%A%k{xECfC0=8M8XJ{^13v_Hzmn$NOt~1C?G{mn`<@ zS});C?W+BsP10l1w>WhUb-KxNsS{C>)iNN|uu4{~kh@Cg;IY4wI}F6WWHEgN{%~8AQT= z!@O}k5q?1ZB6fC%%xlP{0FU^i8>)I{)6!x@2X2dzNwVr(jW+z6mDkDCE>mV|$}kPg zXCvSg5Y$1uZ-yiV`G-pc^_Y^wH}b6|f2cAtNKO(9`09`d%2Xc>0Mj;kuNDSw@j)Si zq47UzmK?^?_vO>hll6rOk%!%LWVIq#h@wnMmb(|_E5%#r)yD1%`_p&Xun}|4x@9S8 z5LkyMd!B9Tc7tE{XZ5|?4m;hvQ2>J7(ss-x=9j6?@FIPQ@6}`Rj^R`oVtMW@_5G_~ zB%wbrQvM$l5Z?bu0m-1B0w(}x&yb!1r(k2{U}0lpW&MZ$VC7+C;iP6^p{7M(R&+9# zFm<;8&`9vHvHTyBjJzpuSs)`D69*$J69)?uD?5Nj!$Jq3VB=u{_@`!Lmas6hF?FN` z*g2cJTf1490z52S-E5p30bES1Of0krLP7uwM{_4LTLf0t|3)U!@OHKUFe{tcs=GTN zFe?GrIsbzkadmSCuyOMIS3MAbm79YT0LZ`~0;dM**r~7cp?%~V7bQF?Q6HO*rCViA ziFozO!8_0*xs6az-8f*VuiNZ?zIM{<$J=9ATSvHb{VrY1chj;n6~*192qlq)ipY@` zpn^k<{G01sKyxSxdjq|J3*Sa&Vly0-DB-q~tUoiPEPxCmKbQ=U*V0Sv0&HBRVW3*Mmv@_V)b zhS3^BPg=6te9_xa+%mp4DjL{R2xH{a8j*W;z~>dXi;f4G#}02l^9(N^w9w&SCld@{ zahzG8F;SKV6J#s?kw!U>3MgZ1pP|N`Fy@~o8p)Mn#mOZosGmuco zWMEm>^EiQv7!fh5f9I%cP47A&Kn~3T^i=blqKETto=^M8i*Zn($ zvdtluiJGcsT&e)$MT+23&Q%(oAA-($-r@z!*%Z>H6Cb|-gPj5{7&#UlC{IAx=XUq6 zlX8jR+K8o>ip@&EYwMcsO?#0cOXt~HD}1pUJ5##0thoiNOmCX5+#z3|_=X8ck76ij zkY~_Sqx9H50aUC)A>iB9iEY@!cuQ>Mw)F1ShiGZLt~qYtlRt|cjFr}^iv3d|=g@TW zs}X12!yxUZmL!F&R-GG^cBuGj^1G<6qjUObP(yF?%V0Sa}qr>Qi9QS9t65H4Ib*jb!k(qTvj<6~;PSso3Va~JrlWLMS;{1Ygt(-dLVv~x znV1#~J`EYN(GlRGge+}aNch5g-QxfF;tcFomWH+B2fMy^#u9N}89E2~xJQ79{@*74PGBJ*dRKws|$@1BQCEI~_2yJbjLKenodQmib?SQ=!c-fA#bD&{X3h7C9>R)Ft1c>H9IInFgyu(|BL{+0e>z7s= zjo1^8EYKYcPd7?i9Y0Wdx%so$vmZVy*QKDII-aa$^q`d4nAKRnKxs zQ>7z6+ZRONRS3=9WKC2*8O9e&E%~=N#h%E0q@cF0)#qv|`D9a|SEk&`#%pfKZ3Dr) zhsqGusJF~HxX`hR>j%>2DVa_inWne6R4?g1*Tt-1hxF44sUWbZ{2o%U9H&WHcs6ot z7M!Sb-bNyVqwMKk=mngcCvgs)NLVm-A5ZbP*IlgKT}nNB%IsCe!6JJ$_i&7y(VBH? zFB4l>ov&Q@Sou|^0NBpNu?m^~w3c+dVJR>#mF%ay5oMSVl=EFf#eSZ0@RSk~LzZlq>b4Yqyq z4kiLU4dPPp3$}KrueTSb5lJntKq!5mRG(-y7~|hjm^MF!}8bSEK)H%MnUOu4{%eAj=C)BMmm~G%ZsKKqg+of2vMr;W~IOw_@v@PR9=K z+CC{sgBIf+ngM1~?Urmkt00d-C+&s-gF^5`g`R^KS#2Jk@j@ng-I$qWAafrkvo0$x442xjz4MlF;je8{ z2!UA}pw9|m2mEJE&B@6fz`^rxzuJG~mQDbU|AhblOe6sM0_@^aJd&IoVqBc!tUQt| zJZ$2eViKZa9Bdp?oLt;oTta~VNErVAnt#VASU6g_TLW1Cos`1DL<1z6;K%3(`xdtA zMn;T|K1dGNk3wT}9)y=OV{xdh-3TxX{sCS8Zj^v0!pnS-Hh_kj0!*!<}-I}*9QM%9bDuH75D#6gxuUsUERH0|6L>x3kM4i M0wtxSvJ}Gq09BPW`2YX_ From 8a9ade00254e403f15471b17ce9fe75fcf0da084 Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Thu, 11 Jun 2020 10:58:44 -0500 Subject: [PATCH 053/869] remove extra semicolon --- gtsam/base/serialization.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/gtsam/base/serialization.h b/gtsam/base/serialization.h index 088029903..191e0ecfb 100644 --- a/gtsam/base/serialization.h +++ b/gtsam/base/serialization.h @@ -108,7 +108,7 @@ bool serializeToXMLFile(const T& input, const std::string& filename, const std:: return false; { boost::archive::xml_oarchive out_archive(out_archive_stream); - out_archive << boost::serialization::make_nvp(name.c_str(), input);; + out_archive << boost::serialization::make_nvp(name.c_str(), input); } out_archive_stream.close(); return true; From c83a4976a4681506d0576db06e108cd353f25d8b Mon Sep 17 00:00:00 2001 From: Jose Luis Blanco Claraco Date: Sat, 13 Jun 2020 08:11:31 +0200 Subject: [PATCH 054/869] Remove all debian package files from this repository. They should belong to the new repository https://github.com/borglab/gtsam-packaging. Read: https://github.com/borglab/gtsam-packaging/issues/1 --- debian/README.md | 12 -- debian/changelog | 5 - debian/compat | 1 - debian/control | 15 -- debian/copyright | 15 -- debian/gtsam-docs.docs | 0 debian/rules | 29 --- debian/source/format | 1 - package_scripts/README.md | 44 ----- package_scripts/compile_static_boost.sh | 8 - package_scripts/prepare_debian.sh | 187 ------------------ .../prepare_debian_gen_snapshot_version.sh | 25 --- package_scripts/prepare_release.sh | 71 ------- .../prepare_ubuntu_pkgs_for_ppa.sh | 123 ------------ package_scripts/toolbox_package_unix.sh | 64 ------ package_scripts/upload_all_gtsam_ppa.sh | 31 --- 16 files changed, 631 deletions(-) delete mode 100644 debian/README.md delete mode 100644 debian/changelog delete mode 100644 debian/compat delete mode 100644 debian/control delete mode 100644 debian/copyright delete mode 100644 debian/gtsam-docs.docs delete mode 100755 debian/rules delete mode 100644 debian/source/format delete mode 100644 package_scripts/README.md delete mode 100755 package_scripts/compile_static_boost.sh delete mode 100755 package_scripts/prepare_debian.sh delete mode 100755 package_scripts/prepare_debian_gen_snapshot_version.sh delete mode 100755 package_scripts/prepare_release.sh delete mode 100755 package_scripts/prepare_ubuntu_pkgs_for_ppa.sh delete mode 100755 package_scripts/toolbox_package_unix.sh delete mode 100755 package_scripts/upload_all_gtsam_ppa.sh diff --git a/debian/README.md b/debian/README.md deleted file mode 100644 index 74eb351cd..000000000 --- a/debian/README.md +++ /dev/null @@ -1,12 +0,0 @@ -# How to build a GTSAM debian package - -To use the ``debuild`` command, install the ``devscripts`` package - - sudo apt install devscripts - -Change into the gtsam directory, then run: - - debuild -us -uc -j4 - -Adjust the ``-j4`` depending on how many CPUs you want to build on in -parallel. diff --git a/debian/changelog b/debian/changelog deleted file mode 100644 index ef5d5ab97..000000000 --- a/debian/changelog +++ /dev/null @@ -1,5 +0,0 @@ -gtsam (4.0.0-1berndpfrommer) bionic; urgency=medium - - * initial release - - -- Bernd Pfrommer Wed, 18 Jul 2018 20:36:44 -0400 diff --git a/debian/compat b/debian/compat deleted file mode 100644 index ec635144f..000000000 --- a/debian/compat +++ /dev/null @@ -1 +0,0 @@ -9 diff --git a/debian/control b/debian/control deleted file mode 100644 index 9b3ae5308..000000000 --- a/debian/control +++ /dev/null @@ -1,15 +0,0 @@ -Source: gtsam -Section: libs -Priority: optional -Maintainer: Frank Dellaert -Uploaders: Jose Luis Blanco Claraco , Bernd Pfrommer -Build-Depends: cmake, libboost-all-dev (>= 1.58), libeigen3-dev, libtbb-dev, debhelper (>=9) -Standards-Version: 3.9.7 -Homepage: https://github.com/borglab/gtsam -Vcs-Browser: https://github.com/borglab/gtsam - -Package: libgtsam-dev -Architecture: any -Depends: ${shlibs:Depends}, ${misc:Depends}, libboost-serialization-dev, libboost-system-dev, libboost-filesystem-dev, libboost-thread-dev, libboost-program-options-dev, libboost-date-time-dev, libboost-timer-dev, libboost-chrono-dev, libboost-regex-dev -Description: Georgia Tech Smoothing and Mapping Library - gtsam: Georgia Tech Smoothing and Mapping library for SLAM type applications diff --git a/debian/copyright b/debian/copyright deleted file mode 100644 index c2f41d83d..000000000 --- a/debian/copyright +++ /dev/null @@ -1,15 +0,0 @@ -Format: https://www.debian.org/doc/packaging-manuals/copyright-format/1.0/ -Upstream-Name: gtsam -Source: https://bitbucket.org/gtborg/gtsam.git - -Files: * -Copyright: 2017, Frank Dellaert -License: BSD - -Files: gtsam/3rdparty/CCOLAMD/* -Copyright: 2005-2011, Univ. of Florida. Authors: Timothy A. Davis, Sivasankaran Rajamanickam, and Stefan Larimore. Closely based on COLAMD by Davis, Stefan Larimore, in collaboration with Esmond Ng, and John Gilbert. http://www.cise.ufl.edu/research/sparse -License: GNU LESSER GENERAL PUBLIC LICENSE - -Files: gtsam/3rdparty/Eigen/* -Copyright: 2017, Multiple Authors -License: MPL2 diff --git a/debian/gtsam-docs.docs b/debian/gtsam-docs.docs deleted file mode 100644 index e69de29bb..000000000 diff --git a/debian/rules b/debian/rules deleted file mode 100755 index fab798f6e..000000000 --- a/debian/rules +++ /dev/null @@ -1,29 +0,0 @@ -#!/usr/bin/make -f -# See debhelper(7) (uncomment to enable) -# output every command that modifies files on the build system. -export DH_VERBOSE = 1 - -# Makefile target name for running unit tests: -GTSAM_TEST_TARGET = check - -# see FEATURE AREAS in dpkg-buildflags(1) -#export DEB_BUILD_MAINT_OPTIONS = hardening=+all - -# see ENVIRONMENT in dpkg-buildflags(1) -# package maintainers to append CFLAGS -#export DEB_CFLAGS_MAINT_APPEND = -Wall -pedantic -# package maintainers to append LDFLAGS -#export DEB_LDFLAGS_MAINT_APPEND = -Wl,--as-needed - -%: - dh $@ --parallel - -# dh_make generated override targets -# This is example for Cmake (See https://bugs.debian.org/641051 ) -override_dh_auto_configure: - dh_auto_configure -- -DCMAKE_BUILD_TYPE=RelWithDebInfo -DCMAKE_INSTALL_PREFIX=/usr -DGTSAM_BUILD_EXAMPLES_ALWAYS=OFF -DGTSAM_BUILD_TESTS=ON -DGTSAM_BUILD_WRAP=OFF -DGTSAM_BUILD_DOCS=OFF -DGTSAM_INSTALL_CPPUNITLITE=OFF -DGTSAM_INSTALL_GEOGRAPHICLIB=OFF -DGTSAM_BUILD_TYPE_POSTFIXES=OFF -DGTSAM_BUILD_WITH_MARCH_NATIVE=OFF - -override_dh_auto_test-arch: - # Tests for arch-dependent : - echo "[override_dh_auto_test-arch]" - dh_auto_build -O--buildsystem=cmake -- $(GTSAM_TEST_TARGET) diff --git a/debian/source/format b/debian/source/format deleted file mode 100644 index 163aaf8d8..000000000 --- a/debian/source/format +++ /dev/null @@ -1 +0,0 @@ -3.0 (quilt) diff --git a/package_scripts/README.md b/package_scripts/README.md deleted file mode 100644 index e27747717..000000000 --- a/package_scripts/README.md +++ /dev/null @@ -1,44 +0,0 @@ -# How to build Debian and Ubuntu Packages - -## Preparations - -Packages must be signed with a GPG key. First have a look of the keys -you have available: - - gpg --list-secret-keys - -If you don't have one, create one, then list again. - -Pick a secret key you like from the listed keys, for instance -"Your Name ". Then unlock that key by -signing a dummy file. The following line should pop up a window to -enter the passphrase: - - echo | gpg --local-user "Your Name " -s >/dev/null - -Now you can run the below scripts. Without this step they will fail -with "No secret key" or similar messages. - -## How to generate a Debian package - -Run the package script, providing a name/email that matches your PGP key. - - cd [GTSAM_SOURCE_ROOT] - bash package_scripts/prepare_debian.sh -e "Your Name " - - -## How to generate Ubuntu packages for a PPA - -Run the packaging script, passing the name of the gpg key -(see above) with the "-e" option: - - cd [GTSAM_SOURCE_ROOT] - bash package_scripts/prepare_ubuntu_pkgs_for_ppa.sh -e "Your Name " - -Check that you have uploaded this key to the ubuntu key server, and -have added the key to your account. - -Upload the package to your ppa: - - cd ~/gtsam_ubuntu - bash [GTSAM_SOURCE_ROOT]/package_scripts/upload_all_gtsam_ppa.sh -p "ppa:your-name/ppa-name" diff --git a/package_scripts/compile_static_boost.sh b/package_scripts/compile_static_boost.sh deleted file mode 100755 index ca3b99e09..000000000 --- a/package_scripts/compile_static_boost.sh +++ /dev/null @@ -1,8 +0,0 @@ -#!/bin/sh - -# Compile boost statically, with -fPIC to allow linking it into the mex -# module (which is a dynamic library). --disable-icu prevents depending -# on libicu, which is unneeded and would require then linking the mex -# module with it as well. We just stage instead of install, then the -# toolbox_package_unix.sh script uses the staged boost. -./b2 link=static threading=multi cxxflags=-fPIC cflags=-fPIC --disable-icu -a -j4 stage diff --git a/package_scripts/prepare_debian.sh b/package_scripts/prepare_debian.sh deleted file mode 100755 index 5dd191fc6..000000000 --- a/package_scripts/prepare_debian.sh +++ /dev/null @@ -1,187 +0,0 @@ -#!/bin/bash -# Prepare to build a Debian package. -# Jose Luis Blanco Claraco, 2019 (for GTSAM) -# Jose Luis Blanco Claraco, 2008-2018 (for MRPT) - -set -e # end on error -#set -x # for debugging - -APPEND_SNAPSHOT_NUM=0 -IS_FOR_UBUNTU=0 -APPEND_LINUX_DISTRO="" -VALUE_EXTRA_CMAKE_PARAMS="" -while getopts "sud:c:e:" OPTION -do - case $OPTION in - s) - APPEND_SNAPSHOT_NUM=1 - ;; - u) - IS_FOR_UBUNTU=1 - ;; - d) - APPEND_LINUX_DISTRO=$OPTARG - ;; - c) - VALUE_EXTRA_CMAKE_PARAMS=$OPTARG - ;; - e) - PACKAGER_EMAIL=$OPTARG - ;; - ?) - echo "Unknown command line argument!" - exit 1 - ;; - esac -done - -if [ -z ${PACKAGER_EMAIL+x} ]; then - echo "must specify packager email via -e option!" - exit -1 -fi - -if [ -f CMakeLists.txt ]; -then - source package_scripts/prepare_debian_gen_snapshot_version.sh -else - echo "Error: cannot find CMakeList.txt. This script is intended to be run from the root of the source tree." - exit 1 -fi - -# Append snapshot? -if [ $APPEND_SNAPSHOT_NUM == "1" ]; -then - CUR_SCRIPT_DIR="$( cd "$( dirname "${BASH_SOURCE[0]}" )" && pwd )" - source $CUR_SCRIPT_DIR/prepare_debian_gen_snapshot_version.sh # populate GTSAM_SNAPSHOT_VERSION - - GTSAM_VERSION_STR="${GTSAM_VERSION_STR}~snapshot${GTSAM_SNAPSHOT_VERSION}${APPEND_LINUX_DISTRO}" -else - GTSAM_VERSION_STR="${GTSAM_VERSION_STR}${APPEND_LINUX_DISTRO}" -fi - -# Call prepare_release -GTSAMSRC=`pwd` - -if [ -f $HOME/gtsam_release/gtsam*.tar.gz ]; -then - echo "## release file already exists. Reusing it." -else - source package_scripts/prepare_release.sh - echo - echo "## Done prepare_release.sh" -fi - -echo "=========== Generating GTSAM ${GTSAM_VER_MMP} Debian package ==============" -cd $GTSAMSRC - -set -x -if [ -z "$GTSAM_DEB_DIR" ]; then - GTSAM_DEB_DIR="$HOME/gtsam_debian" -fi -GTSAM_EXTERN_DEBIAN_DIR="$GTSAMSRC/debian/" -GTSAM_EXTERN_UBUNTU_PPA_DIR="$GTSAMSRC/debian/" - -if [ -f ${GTSAM_EXTERN_DEBIAN_DIR}/control ]; -then - echo "Using debian dir: ${GTSAM_EXTERN_DEBIAN_DIR}" -else - echo "ERROR: Cannot find ${GTSAM_EXTERN_DEBIAN_DIR}" - exit 1 -fi - -GTSAM_DEBSRC_DIR=$GTSAM_DEB_DIR/gtsam-${GTSAM_VERSION_STR} - -echo "GTSAM_VERSION_STR: ${GTSAM_VERSION_STR}" -echo "GTSAM_DEBSRC_DIR: ${GTSAM_DEBSRC_DIR}" - -# Prepare a directory for building the debian package: -# -rm -fR $GTSAM_DEB_DIR || true -mkdir -p $GTSAM_DEB_DIR || true - -# Orig tarball: -echo "Copying orig tarball: gtsam_${GTSAM_VERSION_STR}.orig.tar.gz" -cp $HOME/gtsam_release/gtsam*.tar.gz $GTSAM_DEB_DIR/gtsam_${GTSAM_VERSION_STR}.orig.tar.gz -cd ${GTSAM_DEB_DIR} -tar -xf gtsam_${GTSAM_VERSION_STR}.orig.tar.gz - -if [ ! -d "${GTSAM_DEBSRC_DIR}" ]; -then - mv gtsam-* ${GTSAM_DEBSRC_DIR} # fix different dir names for Ubuntu PPA packages -fi - -if [ ! -f "${GTSAM_DEBSRC_DIR}/CMakeLists.txt" ]; -then - echo "*ERROR*: Seems there was a problem copying sources to ${GTSAM_DEBSRC_DIR}... aborting script." - exit 1 -fi - -cd ${GTSAM_DEBSRC_DIR} - -# Copy debian directory: -#mkdir debian -cp -r ${GTSAM_EXTERN_DEBIAN_DIR}/* debian - -# Use modified control & rules files for Ubuntu PPA packages: -#if [ $IS_FOR_UBUNTU == "1" ]; -#then - # already done: cp ${GTSAM_EXTERN_UBUNTU_PPA_DIR}/control.in debian/ - # Ubuntu: force use of gcc-7: - #sed -i '9i\export CXX=/usr/bin/g++-7\' debian/rules - #sed -i '9i\export CC=/usr/bin/gcc-7\' debian/rules7 -#fi - -# Export signing pub key: -mkdir debian/upstream/ -gpg --export --export-options export-minimal --armor > debian/upstream/signing-key.asc - -# Parse debian/ control.in --> control -#mv debian/control.in debian/control -#sed -i "s/@GTSAM_VER_MM@/${GTSAM_VER_MM}/g" debian/control - -# Replace the text "REPLACE_HERE_EXTRA_CMAKE_PARAMS" in the "debian/rules" file -# with: ${${VALUE_EXTRA_CMAKE_PARAMS}} -RULES_FILE=debian/rules -sed -i -e "s/REPLACE_HERE_EXTRA_CMAKE_PARAMS/${VALUE_EXTRA_CMAKE_PARAMS}/g" $RULES_FILE -echo "Using these extra parameters for CMake: '${VALUE_EXTRA_CMAKE_PARAMS}'" - -# Strip my custom files... -rm debian/*.new || true - - -# Figure out the next Debian version number: -echo "Detecting next Debian version number..." - -CHANGELOG_UPSTREAM_VER=$( dpkg-parsechangelog | sed -n 's/Version:.*\([0-9]\.[0-9]*\.[0-9]*.*snapshot.*\)-.*/\1/p' ) -CHANGELOG_LAST_DEBIAN_VER=$( dpkg-parsechangelog | sed -n 's/Version:.*\([0-9]\.[0-9]*\.[0-9]*\).*-\([0-9]*\).*/\2/p' ) - -echo " -> PREVIOUS UPSTREAM: $CHANGELOG_UPSTREAM_VER -> New: ${GTSAM_VERSION_STR}" -echo " -> PREVIOUS DEBIAN VERSION: $CHANGELOG_LAST_DEBIAN_VER" - -# If we have the same upstream versions, increase the Debian version, otherwise create a new entry: -if [ "$CHANGELOG_UPSTREAM_VER" = "$GTSAM_VERSION_STR" ]; -then - NEW_DEBIAN_VER=$[$CHANGELOG_LAST_DEBIAN_VER + 1] - echo "Changing to a new Debian version: ${GTSAM_VERSION_STR}-${NEW_DEBIAN_VER}" - DEBCHANGE_CMD="--newversion ${GTSAM_VERSION_STR}-${NEW_DEBIAN_VER}" -else - DEBCHANGE_CMD="--newversion ${GTSAM_VERSION_STR}-1" -fi - -echo "Adding a new entry to debian/changelog..." - -DEBEMAIL=${PACKAGER_EMAIL} debchange $DEBCHANGE_CMD -b --distribution unstable --force-distribution New version of upstream sources. - -echo "Copying back the new changelog to a temporary file in: ${GTSAM_EXTERN_DEBIAN_DIR}changelog.new" -cp debian/changelog ${GTSAM_EXTERN_DEBIAN_DIR}changelog.new - -set +x - -echo "==============================================================" -echo "Now, you can build the source Deb package with 'debuild -S -sa'" -echo "==============================================================" - -cd .. -ls -lh - -exit 0 diff --git a/package_scripts/prepare_debian_gen_snapshot_version.sh b/package_scripts/prepare_debian_gen_snapshot_version.sh deleted file mode 100755 index 589d422fe..000000000 --- a/package_scripts/prepare_debian_gen_snapshot_version.sh +++ /dev/null @@ -1,25 +0,0 @@ -#!/bin/bash - -# See https://reproducible-builds.org/specs/source-date-epoch/ -# get SOURCE_DATE_EPOCH with UNIX time_t -if [ -d ".git" ]; -then - SOURCE_DATE_EPOCH=$(git log -1 --pretty=%ct) -else - echo "Error: intended for use from within a git repository" - exit 1 -fi -GTSAM_SNAPSHOT_VERSION=$(date -d @$SOURCE_DATE_EPOCH +%Y%m%d-%H%M) - -GTSAM_SNAPSHOT_VERSION+="-git-" -GTSAM_SNAPSHOT_VERSION+=`git rev-parse --short=8 HEAD` -GTSAM_SNAPSHOT_VERSION+="-" - -# x.y.z version components: -GTSAM_VERSION_MAJOR=$(grep "(GTSAM_VERSION_MAJOR" CMakeLists.txt | sed -r 's/^.*GTSAM_VERSION_MAJOR\s*([0-9])*.*$/\1/g') -GTSAM_VERSION_MINOR=$(grep "(GTSAM_VERSION_MINOR" CMakeLists.txt | sed -r 's/^.*GTSAM_VERSION_MINOR\s*([0-9])*.*$/\1/g') -GTSAM_VERSION_PATCH=$(grep "(GTSAM_VERSION_PATCH" CMakeLists.txt | sed -r 's/^.*GTSAM_VERSION_PATCH\s*([0-9])*.*$/\1/g') - -GTSAM_VER_MM="${GTSAM_VERSION_MAJOR}.${GTSAM_VERSION_MINOR}" -GTSAM_VER_MMP="${GTSAM_VERSION_MAJOR}.${GTSAM_VERSION_MINOR}.${GTSAM_VERSION_PATCH}" -GTSAM_VERSION_STR=$GTSAM_VER_MMP diff --git a/package_scripts/prepare_release.sh b/package_scripts/prepare_release.sh deleted file mode 100755 index 750fc27b3..000000000 --- a/package_scripts/prepare_release.sh +++ /dev/null @@ -1,71 +0,0 @@ -#!/bin/bash -# Export sources from a git tree and prepare it for a public release. -# Jose Luis Blanco Claraco, 2019 (for GTSAM) -# Jose Luis Blanco Claraco, 2008-2018 (for MRPT) - -set -e # exit on error -#set -x # for debugging - -# Checks -# -------------------------------- -if [ -f version_prefix.txt ]; -then - if [ -z ${GTSAM_VERSION_STR+x} ]; - then - source package_scripts/prepare_debian_gen_snapshot_version.sh - fi - echo "ERROR: Run this script from the GTSAM source tree root directory." - exit 1 -fi - -GTSAM_SRC=`pwd` -OUT_RELEASES_DIR="$HOME/gtsam_release" - -OUT_DIR=$OUT_RELEASES_DIR/gtsam-${GTSAM_VERSION_STR} - -echo "=========== Generating GTSAM release ${GTSAM_VER_MMP} ==================" -echo "GTSAM_VERSION_STR : ${GTSAM_VERSION_STR}" -echo "OUT_DIR : ${OUT_DIR}" -echo "============================================================" -echo - -# Prepare output directory: -rm -fR $OUT_RELEASES_DIR || true -mkdir -p ${OUT_DIR} - -# Export / copy sources to target dir: -if [ -d "$GTSAM_SRC/.git" ]; -then - echo "# Exporting git source tree to ${OUT_DIR}" - git archive --format=tar HEAD | tar -x -C ${OUT_DIR} - - # Remove VCS control files: - find ${OUT_DIR} -name '.gitignore' | xargs rm - - # Generate ./SOURCE_DATE_EPOCH with UNIX time_t - SOURCE_DATE_EPOCH=$(git log -1 --pretty=%ct) -else - echo "# Copying sources to ${OUT_DIR}" - cp -R . ${OUT_DIR} - - # Generate ./SOURCE_DATE_EPOCH with UNIX time_t - SOURCE_DATE_EPOCH=$(date +%s) -fi - -# See https://reproducible-builds.org/specs/source-date-epoch/ -echo $SOURCE_DATE_EPOCH > ${OUT_DIR}/SOURCE_DATE_EPOCH - -cd ${OUT_DIR} - -# Dont include Debian files in releases: -rm -fR package_scripts - -# Orig tarball: -cd .. -echo "# Creating orig tarball: gtsam-${GTSAM_VERSION_STR}.tar.gz" -tar czf gtsam-${GTSAM_VERSION_STR}.tar.gz gtsam-${GTSAM_VERSION_STR} - -rm -fr gtsam-${GTSAM_VERSION_STR} - -# GPG signature: -gpg --armor --detach-sign gtsam-${GTSAM_VERSION_STR}.tar.gz diff --git a/package_scripts/prepare_ubuntu_pkgs_for_ppa.sh b/package_scripts/prepare_ubuntu_pkgs_for_ppa.sh deleted file mode 100755 index 33c016b94..000000000 --- a/package_scripts/prepare_ubuntu_pkgs_for_ppa.sh +++ /dev/null @@ -1,123 +0,0 @@ -#!/bin/bash -# Creates a set of packages for each different Ubuntu distribution, with the -# intention of uploading them to a PPA on launchpad -# -# JLBC, 2010 -# [Addition 2012:] -# -# You can declare a variable (in the caller shell) with extra flags for the -# CMake in the final ./configure like: -# -# GTSAM_PKG_CUSTOM_CMAKE_PARAMS="\"-DDISABLE_SSE3=ON\"" -# - - -function show_help { - echo "USAGE:" - echo "" - echo "- to display this help: " - echo "prepare_ubuntu_packages_for_ppa.sh -h or -?" - echo "" - echo "- to package to your PPA: " - echo "prepare_ubuntu_packages_for_ppa.sh -e email_of_your_gpg_key" - echo "" - echo "to pass custom config for GTSAM, set the following" - echo "environment variable beforehand: " - echo "" - echo "GTSAM_PKG_CUSTOM_CMAKE_PARAMS=\"\"-DDISABLE_SSE3=ON\"\"" - echo "" -} - -while getopts "h?e:" opt; do - case "$opt" in - h|\?) - show_help - exit 0 - ;; - e) PACKAGER_EMAIL=$OPTARG - ;; - esac -done - -if [ -z ${PACKAGER_EMAIL+x} ]; then - show_help - exit -1 -fi - - -set -e - -# List of distributions to create PPA packages for: -LST_DISTROS=(xenial bionic eoan focal) - -# Checks -# -------------------------------- -if [ -f CMakeLists.txt ]; -then - source package_scripts/prepare_debian_gen_snapshot_version.sh - echo "GTSAM version: ${GTSAM_VER_MMP}" -else - echo "ERROR: Run this script from the GTSAM root directory." - exit 1 -fi - -if [ -z "${gtsam_ubuntu_OUT_DIR}" ]; then - export gtsam_ubuntu_OUT_DIR="$HOME/gtsam_ubuntu" -fi -GTSAMSRC=`pwd` -if [ -z "${GTSAM_DEB_DIR}" ]; then - export GTSAM_DEB_DIR="$HOME/gtsam_debian" -fi -GTSAM_EXTERN_DEBIAN_DIR="$GTSAMSRC/debian/" - -# Clean out dirs: -rm -fr $gtsam_ubuntu_OUT_DIR/ - -# ------------------------------------------------------------------- -# And now create the custom packages for each Ubuntu distribution: -# ------------------------------------------------------------------- -count=${#LST_DISTROS[@]} -IDXS=$(seq 0 $(expr $count - 1)) - -cp ${GTSAM_EXTERN_DEBIAN_DIR}/changelog /tmp/my_changelog - -for IDX in ${IDXS}; -do - DEBIAN_DIST=${LST_DISTROS[$IDX]} - - # ------------------------------------------------------------------- - # Call the standard "prepare_debian.sh" script: - # ------------------------------------------------------------------- - cd ${GTSAMSRC} - bash package_scripts/prepare_debian.sh -e "$PACKAGER_EMAIL" -s -u -d ${DEBIAN_DIST} -c "${GTSAM_PKG_CUSTOM_CMAKE_PARAMS}" - - CUR_SCRIPT_DIR="$( cd "$( dirname "${BASH_SOURCE[0]}" )" && pwd )" - source $CUR_SCRIPT_DIR/prepare_debian_gen_snapshot_version.sh # populate GTSAM_SNAPSHOT_VERSION - - echo "===== Distribution: ${DEBIAN_DIST} =========" - cd ${GTSAM_DEB_DIR}/gtsam-${GTSAM_VER_MMP}~snapshot${GTSAM_SNAPSHOT_VERSION}${DEBIAN_DIST}/debian - #cp ${GTSAM_EXTERN_DEBIAN_DIR}/changelog changelog - cp /tmp/my_changelog changelog - DEBCHANGE_CMD="--newversion ${GTSAM_VERSION_STR}~snapshot${GTSAM_SNAPSHOT_VERSION}${DEBIAN_DIST}-1" - echo "Changing to a new Debian version: ${DEBCHANGE_CMD}" - echo "Adding a new entry to debian/changelog for distribution ${DEBIAN_DIST}" - DEBEMAIL="${PACKAGER_EMAIL}" debchange $DEBCHANGE_CMD -b --distribution ${DEBIAN_DIST} --force-distribution New version of upstream sources. - - cp changelog /tmp/my_changelog - - echo "Now, let's build the source Deb package with 'debuild -S -sa':" - cd .. - # -S: source package - # -sa: force inclusion of sources - # -d: don't check dependencies in this system - debuild -S -sa -d - - # Make a copy of all these packages: - cd .. - mkdir -p $gtsam_ubuntu_OUT_DIR/$DEBIAN_DIST - cp gtsam_* $gtsam_ubuntu_OUT_DIR/${DEBIAN_DIST}/ - echo ">>>>>> Saving packages to: $gtsam_ubuntu_OUT_DIR/$DEBIAN_DIST/" -done - - -exit 0 diff --git a/package_scripts/toolbox_package_unix.sh b/package_scripts/toolbox_package_unix.sh deleted file mode 100755 index 28de2572a..000000000 --- a/package_scripts/toolbox_package_unix.sh +++ /dev/null @@ -1,64 +0,0 @@ -#!/bin/sh - -# Script to build a tarball with the matlab toolbox - -# Detect platform -os=`uname -s` -arch=`uname -m` -if [ "$os" = "Linux" -a "$arch" = "x86_64" ]; then - platform=lin64 -elif [ "$os" = "Linux" -a "$arch" = "i686" ]; then - platform=lin32 -elif [ "$os" = "Darwin" -a "$arch" = "x86_64" ]; then - platform=mac64 -else - echo "Unrecognized platform" - exit 1 -fi - -echo "Platform is ${platform}" - -# Check for empty diectory -if [ ! -z "`ls`" ]; then - echo "Please run this script from an empty build directory" - exit 1 -fi - -# Check for boost -if [ -z "$1" ]; then - echo "Usage: $0 BOOSTTREE" - echo "BOOSTTREE should be a boost source tree compiled with toolbox_build_boost." - exit 1 -fi - -# Run cmake -cmake -DCMAKE_BUILD_TYPE=Release \ --DGTSAM_INSTALL_MATLAB_TOOLBOX:BOOL=ON \ --DCMAKE_INSTALL_PREFIX="$PWD/stage" \ --DBoost_NO_SYSTEM_PATHS:BOOL=ON \ --DBoost_USE_STATIC_LIBS:BOOL=ON \ --DBOOST_ROOT="$1" \ --DGTSAM_BUILD_TESTS:BOOL=OFF \ --DGTSAM_BUILD_TIMING:BOOL=OFF \ --DGTSAM_BUILD_EXAMPLES_ALWAYS:BOOL=OFF \ --DGTSAM_WITH_TBB:BOOL=OFF \ --DGTSAM_SUPPORT_NESTED_DISSECTION:BOOL=OFF \ --DGTSAM_INSTALL_GEOGRAPHICLIB:BOOL=OFF \ --DGTSAM_BUILD_UNSTABLE:BOOL=OFF \ --DGTSAM_MEX_BUILD_STATIC_MODULE:BOOL=ON .. - -if [ $? -ne 0 ]; then - echo "CMake failed" - exit 1 -fi - -# Compile -make -j8 install - -if [ $? -ne 0 ]; then - echo "Compile failed" - exit 1 -fi - -# Create package -tar czf gtsam-toolbox-3.2.0-$platform.tgz -C stage/gtsam_toolbox toolbox diff --git a/package_scripts/upload_all_gtsam_ppa.sh b/package_scripts/upload_all_gtsam_ppa.sh deleted file mode 100755 index f06d005fb..000000000 --- a/package_scripts/upload_all_gtsam_ppa.sh +++ /dev/null @@ -1,31 +0,0 @@ -#!/bin/bash - -function show_help { - echo "USAGE:" - echo "" - echo "- to display this help: " - echo "upload_all_gtsam_ppa.sh -h or -?" - echo "" - echo "- to upload to your PPA: " - echo "upload_all_gtsam_ppa.sh -p ppa:your_name/name_of_ppa" - echo "" -} - -while getopts "h?p:" opt; do - case "$opt" in - h|\?) - show_help - exit 0 - ;; - p) ppa_name=$OPTARG - ;; - esac -done - -if [ -z ${ppa_name+x} ]; then - show_help - exit -1 -fi - - -find . -name '*.changes' | xargs -I FIL dput ${ppa_name} FIL From 7b92ae8bd3856a2f6839bf6480524e83f4adb826 Mon Sep 17 00:00:00 2001 From: Frank dellaert Date: Tue, 16 Jun 2020 12:14:13 -0400 Subject: [PATCH 055/869] Fixed override warnings and added a few missing headers --- gtsam/slam/RegularImplicitSchurFactor.h | 49 +++++++++++++------------ 1 file changed, 26 insertions(+), 23 deletions(-) diff --git a/gtsam/slam/RegularImplicitSchurFactor.h b/gtsam/slam/RegularImplicitSchurFactor.h index f14df9658..71474a8ab 100644 --- a/gtsam/slam/RegularImplicitSchurFactor.h +++ b/gtsam/slam/RegularImplicitSchurFactor.h @@ -10,7 +10,11 @@ #include #include #include + #include +#include +#include +#include namespace gtsam { @@ -76,7 +80,7 @@ public: /// print void print(const std::string& s = "", const KeyFormatter& keyFormatter = - DefaultKeyFormatter) const { + DefaultKeyFormatter) const override { std::cout << " RegularImplicitSchurFactor " << std::endl; Factor::print(s); for (size_t pos = 0; pos < size(); ++pos) { @@ -88,7 +92,7 @@ public: } /// equals - bool equals(const GaussianFactor& lf, double tol) const { + bool equals(const GaussianFactor& lf, double tol) const override { const This* f = dynamic_cast(&lf); if (!f) return false; @@ -104,37 +108,36 @@ public: } /// Degrees of freedom of camera - virtual DenseIndex getDim(const_iterator variable) const { + DenseIndex getDim(const_iterator variable) const override { return D; } - virtual void updateHessian(const KeyVector& keys, - SymmetricBlockMatrix* info) const { + void updateHessian(const KeyVector& keys, + SymmetricBlockMatrix* info) const override { throw std::runtime_error( "RegularImplicitSchurFactor::updateHessian non implemented"); } - virtual Matrix augmentedJacobian() const { + Matrix augmentedJacobian() const override { throw std::runtime_error( "RegularImplicitSchurFactor::augmentedJacobian non implemented"); return Matrix(); } - virtual std::pair jacobian() const { + std::pair jacobian() const override { throw std::runtime_error( "RegularImplicitSchurFactor::jacobian non implemented"); return std::make_pair(Matrix(), Vector()); } /// *Compute* full augmented information matrix - virtual Matrix augmentedInformation() const { - + Matrix augmentedInformation() const override { // Do the Schur complement - SymmetricBlockMatrix augmentedHessian = // + SymmetricBlockMatrix augmentedHessian = Set::SchurComplement(FBlocks_, E_, b_); return augmentedHessian.selfadjointView(); } /// *Compute* full information matrix - virtual Matrix information() const { + Matrix information() const override { Matrix augmented = augmentedInformation(); int m = this->keys_.size(); size_t M = D * m; @@ -145,7 +148,7 @@ public: using GaussianFactor::hessianDiagonal; /// Add the diagonal of the Hessian for this factor to existing VectorValues - virtual void hessianDiagonalAdd(VectorValues &d) const override { + void hessianDiagonalAdd(VectorValues &d) const override { // diag(Hessian) = diag(F' * (I - E * PointCov * E') * F); for (size_t k = 0; k < size(); ++k) { // for each camera Key j = keys_[k]; @@ -176,7 +179,7 @@ public: * @brief add the contribution of this factor to the diagonal of the hessian * d(output) = d(input) + deltaHessianFactor */ - virtual void hessianDiagonal(double* d) const { + void hessianDiagonal(double* d) const override { // diag(Hessian) = diag(F' * (I - E * PointCov * E') * F); // Use eigen magic to access raw memory typedef Eigen::Matrix DVector; @@ -202,7 +205,7 @@ public: } /// Return the block diagonal of the Hessian for this factor - virtual std::map hessianBlockDiagonal() const { + std::map hessianBlockDiagonal() const override { std::map blocks; // F'*(I - E*P*E')*F for (size_t pos = 0; pos < size(); ++pos) { @@ -227,17 +230,18 @@ public: return blocks; } - virtual GaussianFactor::shared_ptr clone() const { + GaussianFactor::shared_ptr clone() const override { return boost::make_shared >(keys_, FBlocks_, PointCovariance_, E_, b_); throw std::runtime_error( "RegularImplicitSchurFactor::clone non implemented"); } - virtual bool empty() const { + + bool empty() const override { return false; } - virtual GaussianFactor::shared_ptr negate() const { + GaussianFactor::shared_ptr negate() const override { return boost::make_shared >(keys_, FBlocks_, PointCovariance_, E_, b_); throw std::runtime_error( @@ -288,7 +292,7 @@ public: * f = nonlinear error * (x'*H*x - 2*x'*eta + f) = x'*F'*Q*F*x - 2*x'*F'*Q *b + f = x'*F'*Q*(F*x - 2*b) + f */ - virtual double error(const VectorValues& x) const { + double error(const VectorValues& x) const override { // resize does not do malloc if correct size e1.resize(size()); @@ -383,13 +387,12 @@ public: void multiplyHessianAdd(double alpha, const double* x, double* y, std::vector keys) const { } - ; /** * @brief Hessian-vector multiply, i.e. y += F'*alpha*(I - E*P*E')*F*x */ void multiplyHessianAdd(double alpha, const VectorValues& x, - VectorValues& y) const { + VectorValues& y) const override { // resize does not do malloc if correct size e1.resize(size()); @@ -432,7 +435,7 @@ public: /** * Calculate gradient, which is -F'Q*b, see paper */ - VectorValues gradientAtZero() const { + VectorValues gradientAtZero() const override { // calculate Q*b e1.resize(size()); e2.resize(size()); @@ -454,7 +457,7 @@ public: /** * Calculate gradient, which is -F'Q*b, see paper - RAW MEMORY ACCESS */ - virtual void gradientAtZero(double* d) const { + void gradientAtZero(double* d) const override { // Use eigen magic to access raw memory typedef Eigen::Matrix DVector; @@ -474,7 +477,7 @@ public: } /// Gradient wrt a key at any values - Vector gradient(Key key, const VectorValues& x) const { + Vector gradient(Key key, const VectorValues& x) const override { throw std::runtime_error( "gradient for RegularImplicitSchurFactor is not implemented yet"); } From 86407a336334cadc91b241b91e982fc0c18bff1e Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Tue, 16 Jun 2020 12:21:50 -0400 Subject: [PATCH 056/869] renamed testScenarios to testScenarioRunner --- .../tests/{testScenarios.cpp => testScenarioRunner.cpp} | 0 1 file changed, 0 insertions(+), 0 deletions(-) rename gtsam/navigation/tests/{testScenarios.cpp => testScenarioRunner.cpp} (100%) diff --git a/gtsam/navigation/tests/testScenarios.cpp b/gtsam/navigation/tests/testScenarioRunner.cpp similarity index 100% rename from gtsam/navigation/tests/testScenarios.cpp rename to gtsam/navigation/tests/testScenarioRunner.cpp From d3591dac0b4fa96d98db4859863c9410a97b3e5a Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Tue, 16 Jun 2020 15:07:54 -0500 Subject: [PATCH 057/869] fix deprecation warnings from Matplotlib --- .../gtsam/examples/PreintegrationExample.py | 31 ++++++++++--------- 1 file changed, 17 insertions(+), 14 deletions(-) diff --git a/cython/gtsam/examples/PreintegrationExample.py b/cython/gtsam/examples/PreintegrationExample.py index 76520b355..68b1c8cc0 100644 --- a/cython/gtsam/examples/PreintegrationExample.py +++ b/cython/gtsam/examples/PreintegrationExample.py @@ -73,38 +73,41 @@ class PreintegrationExample(object): self.runner = gtsam.ScenarioRunner( self.scenario, self.params, self.dt, self.actualBias) + fig, self.axes = plt.subplots(4, 3) + fig.set_tight_layout(True) + def plotImu(self, t, measuredOmega, measuredAcc): plt.figure(IMU_FIG) # plot angular velocity omega_b = self.scenario.omega_b(t) for i, (label, color) in enumerate(zip(self.labels, self.colors)): - plt.subplot(4, 3, i + 1) - plt.scatter(t, omega_b[i], color='k', marker='.') - plt.scatter(t, measuredOmega[i], color=color, marker='.') - plt.xlabel('angular velocity ' + label) + ax = self.axes[0][i] + ax.scatter(t, omega_b[i], color='k', marker='.') + ax.scatter(t, measuredOmega[i], color=color, marker='.') + ax.set_xlabel('angular velocity ' + label) # plot acceleration in nav acceleration_n = self.scenario.acceleration_n(t) for i, (label, color) in enumerate(zip(self.labels, self.colors)): - plt.subplot(4, 3, i + 4) - plt.scatter(t, acceleration_n[i], color=color, marker='.') - plt.xlabel('acceleration in nav ' + label) + ax = self.axes[1][i] + ax.scatter(t, acceleration_n[i], color=color, marker='.') + ax.set_xlabel('acceleration in nav ' + label) # plot acceleration in body acceleration_b = self.scenario.acceleration_b(t) for i, (label, color) in enumerate(zip(self.labels, self.colors)): - plt.subplot(4, 3, i + 7) - plt.scatter(t, acceleration_b[i], color=color, marker='.') - plt.xlabel('acceleration in body ' + label) + ax = self.axes[2][i] + ax.scatter(t, acceleration_b[i], color=color, marker='.') + ax.set_xlabel('acceleration in body ' + label) # plot actual specific force, as well as corrupted actual = self.runner.actualSpecificForce(t) for i, (label, color) in enumerate(zip(self.labels, self.colors)): - plt.subplot(4, 3, i + 10) - plt.scatter(t, actual[i], color='k', marker='.') - plt.scatter(t, measuredAcc[i], color=color, marker='.') - plt.xlabel('specific force ' + label) + ax = self.axes[3][i] + ax.scatter(t, actual[i], color='k', marker='.') + ax.scatter(t, measuredAcc[i], color=color, marker='.') + ax.set_xlabel('specific force ' + label) def plotGroundTruthPose(self, t): # plot ground truth pose, as well as prediction from integrated IMU measurements From 3db8862480abf919f208065e1c2976c29f19b52c Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Tue, 16 Jun 2020 15:09:11 -0500 Subject: [PATCH 058/869] reduce for loops, add titles to plots, better space subplots for IMU data --- cython/gtsam/examples/ImuFactorExample.py | 36 +++++++++++------------ 1 file changed, 18 insertions(+), 18 deletions(-) diff --git a/cython/gtsam/examples/ImuFactorExample.py b/cython/gtsam/examples/ImuFactorExample.py index 0e01766e7..6cb06dcd0 100644 --- a/cython/gtsam/examples/ImuFactorExample.py +++ b/cython/gtsam/examples/ImuFactorExample.py @@ -69,32 +69,19 @@ class ImuFactorExample(PreintegrationExample): num_poses = T + 1 # assumes 1 factor per second initial = gtsam.Values() initial.insert(BIAS_KEY, self.actualBias) - for i in range(num_poses): - state_i = self.scenario.navState(float(i)) - - poseNoise = gtsam.Pose3.Expmap(np.random.randn(3)*0.1) - pose = state_i.pose().compose(poseNoise) - - velocity = state_i.velocity() + np.random.randn(3)*0.1 - - initial.insert(X(i), pose) - initial.insert(V(i), velocity) # simulate the loop i = 0 # state index actual_state_i = self.scenario.navState(0) + initial.insert(X(i), actual_state_i.pose()) + initial.insert(V(i), actual_state_i.velocity()) + for k, t in enumerate(np.arange(0, T, self.dt)): # get measurements and add them to PIM measuredOmega = self.runner.measuredAngularVelocity(t) measuredAcc = self.runner.measuredSpecificForce(t) pim.integrateMeasurement(measuredAcc, measuredOmega, self.dt) - poseNoise = gtsam.Pose3.Expmap(np.random.randn(3)*0.1) - - actual_state_i = gtsam.NavState( - actual_state_i.pose().compose(poseNoise), - actual_state_i.velocity() + np.random.randn(3)*0.1) - # Plot IMU many times if k % 10 == 0: self.plotImu(t, measuredOmega, measuredAcc) @@ -102,6 +89,7 @@ class ImuFactorExample(PreintegrationExample): # Plot every second if k % int(1 / self.dt) == 0: self.plotGroundTruthPose(t) + plt.title("Ground Truth Trajectory") # create IMU factor every second if (k + 1) % int(1 / self.dt) == 0: @@ -112,6 +100,17 @@ class ImuFactorExample(PreintegrationExample): print(factor) print(pim.predict(actual_state_i, self.actualBias)) pim.resetIntegration() + + rotationNoise = gtsam.Rot3.Expmap(np.random.randn(3)*0.1) + translationNoise = gtsam.Point3(np.random.randn(3)*0.1) + poseNoise = gtsam.Pose3(rotationNoise, translationNoise) + + actual_state_i = gtsam.NavState( + actual_state_i.pose().compose(poseNoise), + actual_state_i.velocity() + np.random.randn(3)*0.1) + + initial.insert(X(i+1), actual_state_i.pose()) + initial.insert(V(i+1), actual_state_i.velocity()) actual_state_i = self.scenario.navState(t + self.dt) i += 1 @@ -138,10 +137,11 @@ class ImuFactorExample(PreintegrationExample): i = 0 while result.exists(X(i)): pose_i = result.atPose3(X(i)) - plot_pose3(POSES_FIG, pose_i, 0.1) + plot_pose3(POSES_FIG+1, pose_i, 0.1) i += 1 + plt.title("Estimated Trajectory") - gtsam.utils.plot.set_axes_equal(POSES_FIG) + gtsam.utils.plot.set_axes_equal(POSES_FIG+1) print(result.atimuBias_ConstantBias(BIAS_KEY)) From 33a1628e84e5d9dbcc5bf88cd12156a74d6f2eae Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Tue, 16 Jun 2020 17:30:30 -0500 Subject: [PATCH 059/869] vastly improved the basic ImuFactorExample script --- cython/gtsam/examples/ImuFactorExample.py | 49 ++++++++++++++--------- 1 file changed, 31 insertions(+), 18 deletions(-) diff --git a/cython/gtsam/examples/ImuFactorExample.py b/cython/gtsam/examples/ImuFactorExample.py index 6cb06dcd0..d323c1b17 100644 --- a/cython/gtsam/examples/ImuFactorExample.py +++ b/cython/gtsam/examples/ImuFactorExample.py @@ -12,6 +12,7 @@ Author: Frank Dellaert, Varun Agrawal from __future__ import print_function +import argparse import math import gtsam @@ -33,24 +34,27 @@ np.set_printoptions(precision=3, suppress=True) class ImuFactorExample(PreintegrationExample): - def __init__(self): + def __init__(self, twist_scenario="sick_twist"): self.velocity = np.array([2, 0, 0]) self.priorNoise = gtsam.noiseModel_Isotropic.Sigma(6, 0.1) self.velNoise = gtsam.noiseModel_Isotropic.Sigma(3, 0.1) # Choose one of these twists to change scenario: - zero_twist = (np.zeros(3), np.zeros(3)) - forward_twist = (np.zeros(3), self.velocity) - loop_twist = (np.array([0, -math.radians(30), 0]), self.velocity) - sick_twist = ( - np.array([math.radians(30), -math.radians(30), 0]), self.velocity) + twist_scenarios = dict( + zero_twist=(np.zeros(3), np.zeros(3)), + forward_twist=(np.zeros(3), self.velocity), + loop_twist=(np.array([0, -math.radians(30), 0]), self.velocity), + sick_twist=(np.array([math.radians(30), -math.radians(30), 0]), + self.velocity) + ) accBias = np.array([-0.3, 0.1, 0.2]) gyroBias = np.array([0.1, 0.3, -0.1]) bias = gtsam.imuBias_ConstantBias(accBias, gyroBias) dt = 1e-2 - super(ImuFactorExample, self).__init__(sick_twist, bias, dt) + super(ImuFactorExample, self).__init__(twist_scenarios[twist_scenario], + bias, dt) def addPrior(self, i, graph): state = self.scenario.navState(i) @@ -59,13 +63,12 @@ class ImuFactorExample(PreintegrationExample): graph.push_back(gtsam.PriorFactorVector( V(i), state.velocity(), self.velNoise)) - def run(self): + def run(self, T=12, verbose=True): graph = gtsam.NonlinearFactorGraph() # initialize data structure for pre-integrated IMU measurements pim = gtsam.PreintegratedImuMeasurements(self.params, self.actualBias) - T = 12 num_poses = T + 1 # assumes 1 factor per second initial = gtsam.Values() initial.insert(BIAS_KEY, self.actualBias) @@ -86,32 +89,34 @@ class ImuFactorExample(PreintegrationExample): if k % 10 == 0: self.plotImu(t, measuredOmega, measuredAcc) - # Plot every second - if k % int(1 / self.dt) == 0: + if (k+1) % int(1 / self.dt) == 0: + # Plot every second self.plotGroundTruthPose(t) plt.title("Ground Truth Trajectory") - # create IMU factor every second - if (k + 1) % int(1 / self.dt) == 0: - factor = gtsam.ImuFactor(X(i), V(i), X( - i + 1), V(i + 1), BIAS_KEY, pim) + # create IMU factor every second + factor = gtsam.ImuFactor(X(i), V(i), + X(i + 1), V(i + 1), + BIAS_KEY, pim) graph.push_back(factor) - if True: + + if verbose: print(factor) print(pim.predict(actual_state_i, self.actualBias)) + pim.resetIntegration() rotationNoise = gtsam.Rot3.Expmap(np.random.randn(3)*0.1) translationNoise = gtsam.Point3(np.random.randn(3)*0.1) poseNoise = gtsam.Pose3(rotationNoise, translationNoise) + actual_state_i = self.scenario.navState(t + self.dt) actual_state_i = gtsam.NavState( actual_state_i.pose().compose(poseNoise), actual_state_i.velocity() + np.random.randn(3)*0.1) initial.insert(X(i+1), actual_state_i.pose()) initial.insert(V(i+1), actual_state_i.velocity()) - actual_state_i = self.scenario.navState(t + self.dt) i += 1 # add priors on beginning and end @@ -150,4 +155,12 @@ class ImuFactorExample(PreintegrationExample): if __name__ == '__main__': - ImuFactorExample().run() + parser = argparse.ArgumentParser("ImuFactorExample.py") + parser.add_argument("--twist_scenario", + default="sick_twist", + choices=("zero_twist", "forward_twist", "loop_twist", "sick_twist")) + parser.add_argument("--time", "-T", default=12, type=int, help="Total time in seconds") + parser.add_argument("--verbose", default=False, action='store_true') + args = parser.parse_args() + + ImuFactorExample().run(args.time, args.verbose) From e8986ba38266fe1f0d271ca5da0053813b49eebe Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Tue, 16 Jun 2020 18:18:27 -0500 Subject: [PATCH 060/869] move Eigen format definition to Matrix.h --- gtsam/base/Matrix.cpp | 10 ---------- gtsam/base/Matrix.h | 12 ++++++++++++ 2 files changed, 12 insertions(+), 10 deletions(-) diff --git a/gtsam/base/Matrix.cpp b/gtsam/base/Matrix.cpp index e2d8f71d1..1c34a71d4 100644 --- a/gtsam/base/Matrix.cpp +++ b/gtsam/base/Matrix.cpp @@ -139,16 +139,6 @@ Vector operator^(const Matrix& A, const Vector & v) { /* ************************************************************************* */ //3 argument call void print(const Matrix& A, const string &s, ostream& stream) { - static const Eigen::IOFormat matlab( - Eigen::StreamPrecision, // precision - 0, // flags - ", ", // coeffSeparator - ";\n", // rowSeparator - "\t", // rowPrefix - "", // rowSuffix - "[\n", // matPrefix - "\n]" // matSuffix - ); cout << s << A.format(matlab) << endl; } diff --git a/gtsam/base/Matrix.h b/gtsam/base/Matrix.h index fa70e5b00..61cbf3e2a 100644 --- a/gtsam/base/Matrix.h +++ b/gtsam/base/Matrix.h @@ -76,6 +76,18 @@ GTSAM_MAKE_MATRIX_DEFS(9); typedef Eigen::Block SubMatrix; typedef Eigen::Block ConstSubMatrix; +// Matrix formatting arguments when printing. Akin to Matlab style. +const Eigen::IOFormat matlab( + Eigen::StreamPrecision, // precision + 0, // flags + ", ", // coeffSeparator + ";\n", // rowSeparator + "\t", // rowPrefix + "", // rowSuffix + "[\n", // matPrefix + "\n]" // matSuffix +); + /** * equals with a tolerance */ From f235aaf8c4b5334dcb2f02ecb808ec4599835007 Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Tue, 16 Jun 2020 18:18:55 -0500 Subject: [PATCH 061/869] use Eigen formatting for Rot3 ostream --- gtsam/geometry/Rot3.cpp | 5 +---- 1 file changed, 1 insertion(+), 4 deletions(-) diff --git a/gtsam/geometry/Rot3.cpp b/gtsam/geometry/Rot3.cpp index 01f62b8cb..613c5b40f 100644 --- a/gtsam/geometry/Rot3.cpp +++ b/gtsam/geometry/Rot3.cpp @@ -222,10 +222,7 @@ pair RQ(const Matrix3& A) { /* ************************************************************************* */ ostream &operator<<(ostream &os, const Rot3& R) { - os << "\n"; - os << '|' << R.r1().x() << ", " << R.r2().x() << ", " << R.r3().x() << "|\n"; - os << '|' << R.r1().y() << ", " << R.r2().y() << ", " << R.r3().y() << "|\n"; - os << '|' << R.r1().z() << ", " << R.r2().z() << ", " << R.r3().z() << "|\n"; + os << R.matrix().format(matlab) << endl; return os; } From 52a8dde6a7f041c7b780b41865c7c95225e875a8 Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Wed, 17 Jun 2020 13:47:43 -0500 Subject: [PATCH 062/869] updated filename in brief --- examples/ImuFactorsExample.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/examples/ImuFactorsExample.cpp b/examples/ImuFactorsExample.cpp index a4707ea46..668b48934 100644 --- a/examples/ImuFactorsExample.cpp +++ b/examples/ImuFactorsExample.cpp @@ -10,7 +10,7 @@ * -------------------------------------------------------------------------- */ /** - * @file imuFactorsExample + * @file ImuFactorsExample * @brief Test example for using GTSAM ImuFactor and ImuCombinedFactor * navigation code. * @author Garrett (ghemann@gmail.com), Luca Carlone From 944a437272cd622515511ebc029923cb6038cb11 Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Wed, 17 Jun 2020 14:54:55 -0500 Subject: [PATCH 063/869] don't align matrix columns --- gtsam/base/Matrix.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/gtsam/base/Matrix.h b/gtsam/base/Matrix.h index 61cbf3e2a..e19fb9dd6 100644 --- a/gtsam/base/Matrix.h +++ b/gtsam/base/Matrix.h @@ -79,7 +79,7 @@ typedef Eigen::Block ConstSubMatrix; // Matrix formatting arguments when printing. Akin to Matlab style. const Eigen::IOFormat matlab( Eigen::StreamPrecision, // precision - 0, // flags + Eigen::DontAlignCols, // flags set such that rowSpacers are not added ", ", // coeffSeparator ";\n", // rowSeparator "\t", // rowPrefix From f7141f4333ebbebeac7e836ddfff3c62bd6520f2 Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Wed, 17 Jun 2020 14:55:52 -0500 Subject: [PATCH 064/869] fix print tests for Rot3 and Pose3 --- gtsam/geometry/tests/testPose3.cpp | 10 +++++++--- gtsam/geometry/tests/testRot3.cpp | 3 ++- 2 files changed, 9 insertions(+), 4 deletions(-) diff --git a/gtsam/geometry/tests/testPose3.cpp b/gtsam/geometry/tests/testPose3.cpp index 5808f36f8..0ad5f47b7 100644 --- a/gtsam/geometry/tests/testPose3.cpp +++ b/gtsam/geometry/tests/testPose3.cpp @@ -839,7 +839,8 @@ TEST( Pose3, stream) Pose3 T; std::ostringstream os; os << T; - EXPECT(os.str() == "\n|1, 0, 0|\n|0, 1, 0|\n|0, 0, 1|\n\n[0, 0, 0]';\n"); + string expected = "[\n\t1, 0, 0;\n\t0, 1, 0;\n\t0, 0, 1\n]\n\n[0, 0, 0]';\n"; + EXPECT(os.str() == expected); } //****************************************************************************** @@ -1009,19 +1010,22 @@ TEST(Pose3, print) { std::stringstream expected; Point3 translation(1, 2, 3); + // Add expected rotation + expected << "R:\n[\n\t1, 0, 0;\n\t0, 1, 0;\n\t0, 0, 1\n]\n"; + #ifdef GTSAM_TYPEDEF_POINTS_TO_VECTORS expected << "1\n" "2\n" "3;\n"; #else - expected << '[' << translation.x() << ", " << translation.y() << ", " << translation.z() << "]\';"; + expected << '[' << translation.x() << ", " << translation.y() << ", " << translation.z() << "]\';\n"; #endif // reset cout to the original stream std::cout.rdbuf(oldbuf); // Get substring corresponding to translation part - std::string actual = redirectStream.str().substr(38, 11); + std::string actual = redirectStream.str(); CHECK_EQUAL(expected.str(), actual); } diff --git a/gtsam/geometry/tests/testRot3.cpp b/gtsam/geometry/tests/testRot3.cpp index 598c57b24..4e3a6d85e 100644 --- a/gtsam/geometry/tests/testRot3.cpp +++ b/gtsam/geometry/tests/testRot3.cpp @@ -608,7 +608,8 @@ TEST( Rot3, stream) Rot3 R; std::ostringstream os; os << R; - EXPECT(os.str() == "\n|1, 0, 0|\n|0, 1, 0|\n|0, 0, 1|\n"); + string expected = "[\n\t1, 0, 0;\n\t0, 1, 0;\n\t0, 0, 1\n]\n"; + EXPECT(os.str() == expected); } /* ************************************************************************* */ From bd040c8b2287d08ffb07ace0a01ba2a789ce7cac Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Wed, 17 Jun 2020 15:02:24 -0500 Subject: [PATCH 065/869] set CMAKE_VERBOSE_MAKEFILE flag to OFF --- .travis.sh | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/.travis.sh b/.travis.sh index 9fc09a3f8..535a72f4b 100755 --- a/.travis.sh +++ b/.travis.sh @@ -63,7 +63,7 @@ function configure() -DGTSAM_BUILD_EXAMPLES_ALWAYS=${GTSAM_BUILD_EXAMPLES_ALWAYS:-ON} \ -DGTSAM_ALLOW_DEPRECATED_SINCE_V4=${GTSAM_ALLOW_DEPRECATED_SINCE_V4:-OFF} \ -DGTSAM_BUILD_WITH_MARCH_NATIVE=OFF \ - -DCMAKE_VERBOSE_MAKEFILE=ON + -DCMAKE_VERBOSE_MAKEFILE=OFF } From 0e42a96294a9c8ecbd9649876a89670427e68455 Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Thu, 18 Jun 2020 11:09:37 -0500 Subject: [PATCH 066/869] Cleaned up printing of Rot3 --- gtsam/geometry/Rot3.cpp | 5 +++-- gtsam/geometry/Rot3.h | 2 +- gtsam/geometry/tests/testRot3.cpp | 2 +- 3 files changed, 5 insertions(+), 4 deletions(-) diff --git a/gtsam/geometry/Rot3.cpp b/gtsam/geometry/Rot3.cpp index 613c5b40f..318655491 100644 --- a/gtsam/geometry/Rot3.cpp +++ b/gtsam/geometry/Rot3.cpp @@ -32,7 +32,8 @@ namespace gtsam { /* ************************************************************************* */ void Rot3::print(const std::string& s) const { - gtsam::print((Matrix)matrix(), s); + cout << (s.empty() ? "R: " : s + " "); + gtsam::print((Matrix)matrix()); } /* ************************************************************************* */ @@ -222,7 +223,7 @@ pair RQ(const Matrix3& A) { /* ************************************************************************* */ ostream &operator<<(ostream &os, const Rot3& R) { - os << R.matrix().format(matlab) << endl; + os << R.matrix().format(matlab); return os; } diff --git a/gtsam/geometry/Rot3.h b/gtsam/geometry/Rot3.h index fc3a8b3f2..8ab7dd377 100644 --- a/gtsam/geometry/Rot3.h +++ b/gtsam/geometry/Rot3.h @@ -254,7 +254,7 @@ namespace gtsam { /// @{ /** print */ - void print(const std::string& s="R") const; + void print(const std::string& s="") const; /** equals with an tolerance */ bool equals(const Rot3& p, double tol = 1e-9) const; diff --git a/gtsam/geometry/tests/testRot3.cpp b/gtsam/geometry/tests/testRot3.cpp index 4e3a6d85e..d5400494e 100644 --- a/gtsam/geometry/tests/testRot3.cpp +++ b/gtsam/geometry/tests/testRot3.cpp @@ -608,7 +608,7 @@ TEST( Rot3, stream) Rot3 R; std::ostringstream os; os << R; - string expected = "[\n\t1, 0, 0;\n\t0, 1, 0;\n\t0, 0, 1\n]\n"; + string expected = "[\n\t1, 0, 0;\n\t0, 1, 0;\n\t0, 0, 1\n]"; EXPECT(os.str() == expected); } From 7815a27e2159e7d816e0072bfeb38dc908ca4f48 Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Thu, 18 Jun 2020 11:10:24 -0500 Subject: [PATCH 067/869] Cleaned up printing of Pose3 --- gtsam/geometry/Pose3.cpp | 10 ++++------ gtsam/geometry/tests/testPose3.cpp | 6 +++--- 2 files changed, 7 insertions(+), 9 deletions(-) diff --git a/gtsam/geometry/Pose3.cpp b/gtsam/geometry/Pose3.cpp index 31033a027..e0fb6e5a5 100644 --- a/gtsam/geometry/Pose3.cpp +++ b/gtsam/geometry/Pose3.cpp @@ -104,9 +104,7 @@ Vector6 Pose3::adjointTranspose(const Vector6& xi, const Vector6& y, /* ************************************************************************* */ void Pose3::print(const string& s) const { - cout << s; - R_.print("R:\n"); - cout << t_ << ";" << endl; + cout << (s.empty() ? s : s + " ") << *this << endl; } /* ************************************************************************* */ @@ -436,9 +434,9 @@ boost::optional align(const vector& baPointPairs) { /* ************************************************************************* */ std::ostream &operator<<(std::ostream &os, const Pose3& pose) { - os << pose.rotation() << "\n"; - const Point3& t = pose.translation(); - os << '[' << t.x() << ", " << t.y() << ", " << t.z() << "]\';\n"; + // Both Rot3 and Point3 have ostream definitions so we use them. + os << "R: " << pose.rotation() << "\n"; + os << "t: " << pose.translation(); return os; } diff --git a/gtsam/geometry/tests/testPose3.cpp b/gtsam/geometry/tests/testPose3.cpp index 0ad5f47b7..caeed5770 100644 --- a/gtsam/geometry/tests/testPose3.cpp +++ b/gtsam/geometry/tests/testPose3.cpp @@ -839,7 +839,7 @@ TEST( Pose3, stream) Pose3 T; std::ostringstream os; os << T; - string expected = "[\n\t1, 0, 0;\n\t0, 1, 0;\n\t0, 0, 1\n]\n\n[0, 0, 0]';\n"; + string expected = "R: [\n\t1, 0, 0;\n\t0, 1, 0;\n\t0, 0, 1\n]\nt: [0, 0, 0]'"; EXPECT(os.str() == expected); } @@ -1011,14 +1011,14 @@ TEST(Pose3, print) { Point3 translation(1, 2, 3); // Add expected rotation - expected << "R:\n[\n\t1, 0, 0;\n\t0, 1, 0;\n\t0, 0, 1\n]\n"; + expected << "R: [\n\t1, 0, 0;\n\t0, 1, 0;\n\t0, 0, 1\n]\n"; #ifdef GTSAM_TYPEDEF_POINTS_TO_VECTORS expected << "1\n" "2\n" "3;\n"; #else - expected << '[' << translation.x() << ", " << translation.y() << ", " << translation.z() << "]\';\n"; + expected << "t: [" << translation.x() << ", " << translation.y() << ", " << translation.z() << "]'\n"; #endif // reset cout to the original stream From d3ac33ac18617cb7f8a6484a025f4ab34df0b65e Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Thu, 18 Jun 2020 11:10:44 -0500 Subject: [PATCH 068/869] Cleaned up printing of NavState --- gtsam/navigation/NavState.cpp | 8 ++++---- gtsam/navigation/tests/testNavState.cpp | 12 ++++++++++++ 2 files changed, 16 insertions(+), 4 deletions(-) diff --git a/gtsam/navigation/NavState.cpp b/gtsam/navigation/NavState.cpp index 50949c761..1d191416f 100644 --- a/gtsam/navigation/NavState.cpp +++ b/gtsam/navigation/NavState.cpp @@ -88,15 +88,15 @@ Matrix7 NavState::matrix() const { //------------------------------------------------------------------------------ ostream& operator<<(ostream& os, const NavState& state) { - os << "R:" << state.attitude(); - os << "p:" << state.position() << endl; - os << "v:" << Point3(state.velocity()) << endl; + os << "R: " << state.attitude() << "\n"; + os << "p: " << state.position() << "\n"; + os << "v: " << Point3(state.velocity()); return os; } //------------------------------------------------------------------------------ void NavState::print(const string& s) const { - cout << s << *this << endl; + cout << (s.empty() ? s : s + " ") << *this << endl; } //------------------------------------------------------------------------------ diff --git a/gtsam/navigation/tests/testNavState.cpp b/gtsam/navigation/tests/testNavState.cpp index 8ea8ce9b5..57945020c 100644 --- a/gtsam/navigation/tests/testNavState.cpp +++ b/gtsam/navigation/tests/testNavState.cpp @@ -237,6 +237,18 @@ TEST(NavState, CorrectPIM) { EXPECT(assert_equal(numericalDerivative22(correctPIM, kState1, xi), aH2)); } +/* ************************************************************************* */ +TEST(NavState, Stream) +{ + NavState state; + + std::ostringstream os; + os << state; + string expected = "R: [\n\t1, 0, 0;\n\t0, 1, 0;\n\t0, 0, 1\n]\np: [0, 0, 0]'\nv: [0, 0, 0]'"; + EXPECT(os.str() == expected); +} + + /* ************************************************************************* */ int main() { TestResult tr; From 741df283d098536857bdacfb9140828a0dc3aca2 Mon Sep 17 00:00:00 2001 From: Jose Luis Blanco-Claraco Date: Fri, 19 Jun 2020 09:00:15 +0200 Subject: [PATCH 069/869] Finish undo of #310 fill with zeros (not actually needed) --- gtsam/base/SymmetricBlockMatrix.h | 7 ++----- 1 file changed, 2 insertions(+), 5 deletions(-) diff --git a/gtsam/base/SymmetricBlockMatrix.h b/gtsam/base/SymmetricBlockMatrix.h index c2996109f..4e030606d 100644 --- a/gtsam/base/SymmetricBlockMatrix.h +++ b/gtsam/base/SymmetricBlockMatrix.h @@ -71,24 +71,22 @@ namespace gtsam { } /// Construct from a container of the sizes of each block. - /// Uninitialized blocks are filled with zeros. template SymmetricBlockMatrix(const CONTAINER& dimensions, bool appendOneDimension = false) : blockStart_(0) { fillOffsets(dimensions.begin(), dimensions.end(), appendOneDimension); - matrix_.setZero(variableColOffsets_.back(), variableColOffsets_.back()); + matrix_.resize(variableColOffsets_.back(), variableColOffsets_.back()); assertInvariants(); } /// Construct from iterator over the sizes of each vertical block. - /// Uninitialized blocks are filled with zeros. template SymmetricBlockMatrix(ITERATOR firstBlockDim, ITERATOR lastBlockDim, bool appendOneDimension = false) : blockStart_(0) { fillOffsets(firstBlockDim, lastBlockDim, appendOneDimension); - matrix_.setZero(variableColOffsets_.back(), variableColOffsets_.back()); + matrix_.resize(variableColOffsets_.back(), variableColOffsets_.back()); assertInvariants(); } @@ -418,4 +416,3 @@ namespace gtsam { class CholeskyFailed; } - From d7522ab97027d578ff1f76e1025e901edb57fb26 Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Fri, 19 Jun 2020 16:03:40 -0500 Subject: [PATCH 070/869] moved matlab-style matrix format definition back to cpp, updated all formatters --- gtsam/base/Matrix.cpp | 16 +++++++++++++++- gtsam/base/Matrix.h | 14 +++----------- gtsam/geometry/Rot3.cpp | 2 +- gtsam/linear/JacobianFactor.cpp | 12 +----------- 4 files changed, 20 insertions(+), 24 deletions(-) diff --git a/gtsam/base/Matrix.cpp b/gtsam/base/Matrix.cpp index 1c34a71d4..551bdac10 100644 --- a/gtsam/base/Matrix.cpp +++ b/gtsam/base/Matrix.cpp @@ -136,10 +136,24 @@ Vector operator^(const Matrix& A, const Vector & v) { return A.transpose() * v; } +const Eigen::IOFormat& matlabFormat() { + static const Eigen::IOFormat matlab( + Eigen::StreamPrecision, // precision + Eigen::DontAlignCols, // flags set such that rowSpacers are not added + ", ", // coeffSeparator + ";\n", // rowSeparator + "\t", // rowPrefix + "", // rowSuffix + "[\n", // matPrefix + "\n]" // matSuffix + ); + return matlab; +} + /* ************************************************************************* */ //3 argument call void print(const Matrix& A, const string &s, ostream& stream) { - cout << s << A.format(matlab) << endl; + cout << s << A.format(matlabFormat()) << endl; } /* ************************************************************************* */ diff --git a/gtsam/base/Matrix.h b/gtsam/base/Matrix.h index e19fb9dd6..776badcd1 100644 --- a/gtsam/base/Matrix.h +++ b/gtsam/base/Matrix.h @@ -76,17 +76,9 @@ GTSAM_MAKE_MATRIX_DEFS(9); typedef Eigen::Block SubMatrix; typedef Eigen::Block ConstSubMatrix; -// Matrix formatting arguments when printing. Akin to Matlab style. -const Eigen::IOFormat matlab( - Eigen::StreamPrecision, // precision - Eigen::DontAlignCols, // flags set such that rowSpacers are not added - ", ", // coeffSeparator - ";\n", // rowSeparator - "\t", // rowPrefix - "", // rowSuffix - "[\n", // matPrefix - "\n]" // matSuffix -); +// Matrix formatting arguments when printing. +// Akin to Matlab style. +const Eigen::IOFormat& matlabFormat(); /** * equals with a tolerance diff --git a/gtsam/geometry/Rot3.cpp b/gtsam/geometry/Rot3.cpp index 318655491..c1247da2e 100644 --- a/gtsam/geometry/Rot3.cpp +++ b/gtsam/geometry/Rot3.cpp @@ -223,7 +223,7 @@ pair RQ(const Matrix3& A) { /* ************************************************************************* */ ostream &operator<<(ostream &os, const Rot3& R) { - os << R.matrix().format(matlab); + os << R.matrix().format(matlabFormat()); return os; } diff --git a/gtsam/linear/JacobianFactor.cpp b/gtsam/linear/JacobianFactor.cpp index 09a9a6103..bb83b672d 100644 --- a/gtsam/linear/JacobianFactor.cpp +++ b/gtsam/linear/JacobianFactor.cpp @@ -421,21 +421,11 @@ JacobianFactor::JacobianFactor(const GaussianFactorGraph& graph, /* ************************************************************************* */ void JacobianFactor::print(const string& s, const KeyFormatter& formatter) const { - static const Eigen::IOFormat matlab( - Eigen::StreamPrecision, // precision - 0, // flags - " ", // coeffSeparator - ";\n", // rowSeparator - "\t", // rowPrefix - "", // rowSuffix - "[\n", // matPrefix - "\n ]" // matSuffix - ); if (!s.empty()) cout << s << "\n"; for (const_iterator key = begin(); key != end(); ++key) { cout << boost::format(" A[%1%] = ") % formatter(*key); - cout << getA(key).format(matlab) << endl; + cout << getA(key).format(matlabFormat()) << endl; } cout << formatMatrixIndented(" b = ", getb(), true) << "\n"; if (model_) From e4b30fd5805aa2cb027a609b72a777c948653708 Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Fri, 19 Jun 2020 16:06:33 -0500 Subject: [PATCH 071/869] use static_cast for Rot3 matrix --- gtsam/geometry/Rot3.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/gtsam/geometry/Rot3.cpp b/gtsam/geometry/Rot3.cpp index c1247da2e..aaf23e685 100644 --- a/gtsam/geometry/Rot3.cpp +++ b/gtsam/geometry/Rot3.cpp @@ -33,7 +33,7 @@ namespace gtsam { /* ************************************************************************* */ void Rot3::print(const std::string& s) const { cout << (s.empty() ? "R: " : s + " "); - gtsam::print((Matrix)matrix()); + gtsam::print(static_cast(matrix())); } /* ************************************************************************* */ From 0a44315a7f3b1b2f6e1953e5b73ece40c7097a01 Mon Sep 17 00:00:00 2001 From: David Date: Sat, 20 Jun 2020 08:46:06 +1000 Subject: [PATCH 072/869] Add Pose3-Point3 factor --- gtsam_unstable/slam/PoseToPointFactor.h | 95 +++++++++++++++++++ .../slam/tests/testPoseToPointFactor.h | 84 ++++++++++++++++ 2 files changed, 179 insertions(+) create mode 100644 gtsam_unstable/slam/PoseToPointFactor.h create mode 100644 gtsam_unstable/slam/tests/testPoseToPointFactor.h diff --git a/gtsam_unstable/slam/PoseToPointFactor.h b/gtsam_unstable/slam/PoseToPointFactor.h new file mode 100644 index 000000000..98efd6a0b --- /dev/null +++ b/gtsam_unstable/slam/PoseToPointFactor.h @@ -0,0 +1,95 @@ +/** + * @file PoseToPointFactor.hpp + * @brief This factor can be used to track a 3D landmark over time by providing + * local measurements of its location. + * @author David Wisth + **/ +#pragma once + +#include +#include +#include +#include + +namespace gtsam { + +/** + * A class for a measurement between a pose and a point. + * @addtogroup SLAM + */ +class PoseToPointFactor: public NoiseModelFactor2 { + +private: + + typedef PoseToPointFactor This; + typedef NoiseModelFactor2 Base; + + Point3 measured_; /** the point measurement */ + +public: + + // shorthand for a smart pointer to a factor + typedef boost::shared_ptr shared_ptr; + + /** default constructor - only use for serialization */ + PoseToPointFactor() {} + + /** Constructor */ + PoseToPointFactor(Key key1, Key key2, const Point3& measured, + const SharedNoiseModel& model) : + Base(model, key1, key2), measured_(measured) + { + } + + virtual ~PoseToPointFactor() {} + + /** implement functions needed for Testable */ + + /** print */ + virtual void print(const std::string& s, const KeyFormatter& keyFormatter = DefaultKeyFormatter) const { + std::cout << s << "PoseToPointFactor(" + << keyFormatter(this->key1()) << "," + << keyFormatter(this->key2()) << ")\n" + << " measured: " << measured_.transpose() << std::endl; + this->noiseModel_->print(" noise model: "); + } + + /** equals */ + virtual bool equals(const NonlinearFactor& expected, double tol=1e-9) const { + const This *e = dynamic_cast (&expected); + return e != nullptr && Base::equals(*e, tol) && traits::Equals(this->measured_, e->measured_, tol); + } + + /** implement functions needed to derive from Factor */ + + /** vector of errors + * Error = pose_est.inverse()*point_est - measured_ + * (The error is in the measurement coordinate system) + */ + Vector evaluateError(const Pose3& W_T_WI, + const Point3& W_r_WC, + boost::optional H1 = boost::none, + boost::optional H2 = boost::none) const + { + return W_T_WI.transformTo(W_r_WC, H1, H2) - measured_; + } + + /** return the measured */ + const Point3& measured() const { + return measured_; + } + +private: + + /** Serialization function */ + friend class boost::serialization::access; + template + void serialize(ARCHIVE & ar, const unsigned int /*version*/) { + ar & boost::serialization::make_nvp("NoiseModelFactor2", + boost::serialization::base_object(*this)); + ar & BOOST_SERIALIZATION_NVP(measured_); + } + +}; // \class PoseToPointFactor + +} /// namespace gtsam diff --git a/gtsam_unstable/slam/tests/testPoseToPointFactor.h b/gtsam_unstable/slam/tests/testPoseToPointFactor.h new file mode 100644 index 000000000..0a13e78e2 --- /dev/null +++ b/gtsam_unstable/slam/tests/testPoseToPointFactor.h @@ -0,0 +1,84 @@ +/** + * @file testPoseToPointFactor.cpp + * @brief + * @author David Wisth + * @date June 20, 2020 + */ + +#include +#include +#include + +using namespace gtsam; +using namespace gtsam::noiseModel; + +/// Verify zero error when there is no noise +TEST(LandmarkFactor, errorNoiseless) { + Pose3 pose = Pose3::identity(); + Point3 point(1.0, 2.0, 3.0); + Point3 noise(0.0, 0.0, 0.0); + Point3 measured = t + noise; + + Key pose_key(1); + Key point_key(2); + PoseToPointFactor factor(pose_key, point_key, measured, Isotropic::Sigma(3, 0.05)); + Vector expectedError = Vector3(0.0, 0.0, 0.0); + Vector actualError = factor.evaluateError(pose, point); + EXPECT(assert_equal(expectedError,actualError, 1E-5)); +} + +/// Verify expected error in test scenario +TEST(LandmarkFactor, errorNoise) { + Pose3 pose = Pose3::identity(); + Point3 point(1.0 , 2.0, 3.0); + Point3 noise(-1.0, 0.5, 0.3); + Point3 measured = t + noise; + + Key pose_key(1); + Key point_key(2); + PoseToPointFactor factor(pose_key, point_key, measured, Isotropic::Sigma(3, 0.05)); + Vector expectedError = noise; + Vector actualError = factor.evaluateError(pose, point); + EXPECT(assert_equal(expectedError,actualError, 1E-5)); +} + +/// Check Jacobians are correct +TEST(LandmarkFactor, jacobian) { + // Measurement + gtsam::Point3 l_meas = gtsam::Point3(1, 2, 3); + + // Linearisation point + gtsam::Point3 p_t = gtsam::Point3(-5, 12, 2); + gtsam::Rot3 p_R = gtsam::Rot3::RzRyRx(1.5*M_PI, -0.3*M_PI, 0.4*M_PI); + Pose3 p(p_R, p_t); + + gtsam::Point3 l = gtsam::Point3(3, 0, 5); + + // Factor + Key pose_key(1); + Key point_key(2); + SharedGaussian noise = noiseModel::Diagonal::Sigmas(Vector3(0.1, 0.1, 0.1)); + PoseToPointFactor factor(pose_key, point_key, l_meas, noise); + + // Calculate numerical derivatives + boost::function f = boost::bind( + &LandmarkFactor::evaluateError, factor, _1, _2, boost::none, boost::none); + Matrix numerical_H1 = numericalDerivative21(f, p, l); + Matrix numerical_H2 = numericalDerivative22(f, p, l); + + // Use the factor to calculate the derivative + Matrix actual_H1; + Matrix actual_H2; + factor.evaluateError(p, l, actual_H1, actual_H2); + + // Verify we get the expected error + EXPECT_TRUE(assert_equal(numerical_H1, actual_H1, 1e-8)); + EXPECT_TRUE(assert_equal(numerical_H2, actual_H2, 1e-8)); +} + +/* ************************************************************************* */ +int main() { + TestResult tr; + return TestRegistry::runAllTests(tr); +} +/* ************************************************************************* */ From c422815b9402a0a0840c2902b8df647e6d527ca5 Mon Sep 17 00:00:00 2001 From: David Date: Sat, 20 Jun 2020 09:03:17 +1000 Subject: [PATCH 073/869] Update incorrect test name --- gtsam_unstable/slam/tests/testPoseToPointFactor.h | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/gtsam_unstable/slam/tests/testPoseToPointFactor.h b/gtsam_unstable/slam/tests/testPoseToPointFactor.h index 0a13e78e2..4b2793700 100644 --- a/gtsam_unstable/slam/tests/testPoseToPointFactor.h +++ b/gtsam_unstable/slam/tests/testPoseToPointFactor.h @@ -13,7 +13,7 @@ using namespace gtsam; using namespace gtsam::noiseModel; /// Verify zero error when there is no noise -TEST(LandmarkFactor, errorNoiseless) { +TEST(PoseToPointFactor, errorNoiseless) { Pose3 pose = Pose3::identity(); Point3 point(1.0, 2.0, 3.0); Point3 noise(0.0, 0.0, 0.0); @@ -28,7 +28,7 @@ TEST(LandmarkFactor, errorNoiseless) { } /// Verify expected error in test scenario -TEST(LandmarkFactor, errorNoise) { +TEST(PoseToPointFactor, errorNoise) { Pose3 pose = Pose3::identity(); Point3 point(1.0 , 2.0, 3.0); Point3 noise(-1.0, 0.5, 0.3); @@ -43,7 +43,7 @@ TEST(LandmarkFactor, errorNoise) { } /// Check Jacobians are correct -TEST(LandmarkFactor, jacobian) { +TEST(PoseToPointFactor, jacobian) { // Measurement gtsam::Point3 l_meas = gtsam::Point3(1, 2, 3); From 0ee4e3b77eaaa879d5e995d92714698e94d11455 Mon Sep 17 00:00:00 2001 From: David Date: Sat, 20 Jun 2020 09:45:24 +1000 Subject: [PATCH 074/869] Add more documentation and clang-format --- gtsam_unstable/slam/PoseToPointFactor.h | 81 +++++++++---------- .../slam/tests/testPoseToPointFactor.h | 22 ++--- 2 files changed, 50 insertions(+), 53 deletions(-) diff --git a/gtsam_unstable/slam/PoseToPointFactor.h b/gtsam_unstable/slam/PoseToPointFactor.h index 98efd6a0b..ec7da22ef 100644 --- a/gtsam_unstable/slam/PoseToPointFactor.h +++ b/gtsam_unstable/slam/PoseToPointFactor.h @@ -1,15 +1,15 @@ /** * @file PoseToPointFactor.hpp - * @brief This factor can be used to track a 3D landmark over time by providing - * local measurements of its location. + * @brief This factor can be used to track a 3D landmark over time by + *providing local measurements of its location. * @author David Wisth **/ #pragma once -#include -#include #include #include +#include +#include namespace gtsam { @@ -17,17 +17,14 @@ namespace gtsam { * A class for a measurement between a pose and a point. * @addtogroup SLAM */ -class PoseToPointFactor: public NoiseModelFactor2 { - -private: - +class PoseToPointFactor : public NoiseModelFactor2 { + private: typedef PoseToPointFactor This; typedef NoiseModelFactor2 Base; - Point3 measured_; /** the point measurement */ - -public: + Point3 measured_; /** the point measurement in local coordinates */ + public: // shorthand for a smart pointer to a factor typedef boost::shared_ptr shared_ptr; @@ -36,60 +33,58 @@ public: /** Constructor */ PoseToPointFactor(Key key1, Key key2, const Point3& measured, - const SharedNoiseModel& model) : - Base(model, key1, key2), measured_(measured) - { - } + const SharedNoiseModel& model) + : Base(model, key1, key2), measured_(measured) {} virtual ~PoseToPointFactor() {} /** implement functions needed for Testable */ /** print */ - virtual void print(const std::string& s, const KeyFormatter& keyFormatter = DefaultKeyFormatter) const { - std::cout << s << "PoseToPointFactor(" - << keyFormatter(this->key1()) << "," - << keyFormatter(this->key2()) << ")\n" - << " measured: " << measured_.transpose() << std::endl; + virtual void print(const std::string& s, const KeyFormatter& keyFormatter = + DefaultKeyFormatter) const { + std::cout << s << "PoseToPointFactor(" << keyFormatter(this->key1()) << "," + << keyFormatter(this->key2()) << ")\n" + << " measured: " << measured_.transpose() << std::endl; this->noiseModel_->print(" noise model: "); } /** equals */ - virtual bool equals(const NonlinearFactor& expected, double tol=1e-9) const { - const This *e = dynamic_cast (&expected); - return e != nullptr && Base::equals(*e, tol) && traits::Equals(this->measured_, e->measured_, tol); + virtual bool equals(const NonlinearFactor& expected, + double tol = 1e-9) const { + const This* e = dynamic_cast(&expected); + return e != nullptr && Base::equals(*e, tol) && + traits::Equals(this->measured_, e->measured_, tol); } /** implement functions needed to derive from Factor */ /** vector of errors - * Error = pose_est.inverse()*point_est - measured_ - * (The error is in the measurement coordinate system) - */ - Vector evaluateError(const Pose3& W_T_WI, - const Point3& W_r_WC, + * @brief Error = wTwi.inverse()*wPwp - measured_ + * @param wTwi The pose of the sensor in world coordinates + * @param wPwp The estimated point location in world coordinates + * + * Note: measured_ and the error are in local coordiantes. + */ + Vector evaluateError(const Pose3& wTwi, const Point3& wPwp, boost::optional H1 = boost::none, - boost::optional H2 = boost::none) const - { - return W_T_WI.transformTo(W_r_WC, H1, H2) - measured_; + boost::optional H2 = boost::none) const { + return wTwi.transformTo(wPwp, H1, H2) - measured_; } /** return the measured */ - const Point3& measured() const { - return measured_; - } - -private: + const Point3& measured() const { return measured_; } + private: /** Serialization function */ friend class boost::serialization::access; - template - void serialize(ARCHIVE & ar, const unsigned int /*version*/) { - ar & boost::serialization::make_nvp("NoiseModelFactor2", - boost::serialization::base_object(*this)); - ar & BOOST_SERIALIZATION_NVP(measured_); + template + void serialize(ARCHIVE& ar, const unsigned int /*version*/) { + ar& boost::serialization::make_nvp( + "NoiseModelFactor2", boost::serialization::base_object(*this)); + ar& BOOST_SERIALIZATION_NVP(measured_); } -}; // \class PoseToPointFactor +}; // \class PoseToPointFactor -} /// namespace gtsam +} // namespace gtsam diff --git a/gtsam_unstable/slam/tests/testPoseToPointFactor.h b/gtsam_unstable/slam/tests/testPoseToPointFactor.h index 4b2793700..8f8563e9d 100644 --- a/gtsam_unstable/slam/tests/testPoseToPointFactor.h +++ b/gtsam_unstable/slam/tests/testPoseToPointFactor.h @@ -5,9 +5,9 @@ * @date June 20, 2020 */ +#include #include #include -#include using namespace gtsam; using namespace gtsam::noiseModel; @@ -21,25 +21,27 @@ TEST(PoseToPointFactor, errorNoiseless) { Key pose_key(1); Key point_key(2); - PoseToPointFactor factor(pose_key, point_key, measured, Isotropic::Sigma(3, 0.05)); + PoseToPointFactor factor(pose_key, point_key, measured, + Isotropic::Sigma(3, 0.05)); Vector expectedError = Vector3(0.0, 0.0, 0.0); Vector actualError = factor.evaluateError(pose, point); - EXPECT(assert_equal(expectedError,actualError, 1E-5)); + EXPECT(assert_equal(expectedError, actualError, 1E-5)); } /// Verify expected error in test scenario TEST(PoseToPointFactor, errorNoise) { Pose3 pose = Pose3::identity(); - Point3 point(1.0 , 2.0, 3.0); + Point3 point(1.0, 2.0, 3.0); Point3 noise(-1.0, 0.5, 0.3); Point3 measured = t + noise; Key pose_key(1); Key point_key(2); - PoseToPointFactor factor(pose_key, point_key, measured, Isotropic::Sigma(3, 0.05)); + PoseToPointFactor factor(pose_key, point_key, measured, + Isotropic::Sigma(3, 0.05)); Vector expectedError = noise; Vector actualError = factor.evaluateError(pose, point); - EXPECT(assert_equal(expectedError,actualError, 1E-5)); + EXPECT(assert_equal(expectedError, actualError, 1E-5)); } /// Check Jacobians are correct @@ -48,8 +50,8 @@ TEST(PoseToPointFactor, jacobian) { gtsam::Point3 l_meas = gtsam::Point3(1, 2, 3); // Linearisation point - gtsam::Point3 p_t = gtsam::Point3(-5, 12, 2); - gtsam::Rot3 p_R = gtsam::Rot3::RzRyRx(1.5*M_PI, -0.3*M_PI, 0.4*M_PI); + gtsam::Point3 p_t = gtsam::Point3(-5, 12, 2); + gtsam::Rot3 p_R = gtsam::Rot3::RzRyRx(1.5 * M_PI, -0.3 * M_PI, 0.4 * M_PI); Pose3 p(p_R, p_t); gtsam::Point3 l = gtsam::Point3(3, 0, 5); @@ -61,8 +63,8 @@ TEST(PoseToPointFactor, jacobian) { PoseToPointFactor factor(pose_key, point_key, l_meas, noise); // Calculate numerical derivatives - boost::function f = boost::bind( - &LandmarkFactor::evaluateError, factor, _1, _2, boost::none, boost::none); + auto f = boost::bind(&PoseToPointFactor::evaluateError, factor, _1, _2, + boost::none, boost::none); Matrix numerical_H1 = numericalDerivative21(f, p, l); Matrix numerical_H2 = numericalDerivative22(f, p, l); From 0bd81430573a32712642a546880600f498cac745 Mon Sep 17 00:00:00 2001 From: Frank Dellaert Date: Fri, 19 Jun 2020 23:33:29 -0400 Subject: [PATCH 075/869] Importing Frobenius error factors from Shonan effort --- cython/gtsam/tests/test_FrobeniusFactor.py | 56 +++++ gtsam.h | 29 +++ gtsam/slam/FrobeniusFactor.cpp | 117 ++++++++++ gtsam/slam/FrobeniusFactor.h | 145 ++++++++++++ gtsam/slam/tests/testFrobeniusFactor.cpp | 244 +++++++++++++++++++++ timing/timeFrobeniusFactor.cpp | 110 ++++++++++ 6 files changed, 701 insertions(+) create mode 100644 cython/gtsam/tests/test_FrobeniusFactor.py create mode 100644 gtsam/slam/FrobeniusFactor.cpp create mode 100644 gtsam/slam/FrobeniusFactor.h create mode 100644 gtsam/slam/tests/testFrobeniusFactor.cpp create mode 100644 timing/timeFrobeniusFactor.cpp diff --git a/cython/gtsam/tests/test_FrobeniusFactor.py b/cython/gtsam/tests/test_FrobeniusFactor.py new file mode 100644 index 000000000..82d1fb410 --- /dev/null +++ b/cython/gtsam/tests/test_FrobeniusFactor.py @@ -0,0 +1,56 @@ +""" +GTSAM Copyright 2010-2019, Georgia Tech Research Corporation, +Atlanta, Georgia 30332-0415 +All Rights Reserved + +See LICENSE for the license information + +FrobeniusFactor unit tests. +Author: Frank Dellaert +""" +# pylint: disable=no-name-in-module, import-error, invalid-name +import unittest + +import numpy as np +from gtsam import (SO3, SO4, FrobeniusBetweenFactorSO4, FrobeniusFactorSO4, + FrobeniusWormholeFactor, SOn) + +id = SO4() +v1 = np.array([0, 0, 0, 0.1, 0, 0]) +Q1 = SO4.Expmap(v1) +v2 = np.array([0, 0, 0, 0.01, 0.02, 0.03]) +Q2 = SO4.Expmap(v2) + + +class TestFrobeniusFactorSO4(unittest.TestCase): + """Test FrobeniusFactor factors.""" + + def test_frobenius_factor(self): + """Test creation of a factor that calculates the Frobenius norm.""" + factor = FrobeniusFactorSO4(1, 2) + actual = factor.evaluateError(Q1, Q2) + expected = (Q2.matrix()-Q1.matrix()).transpose().reshape((16,)) + np.testing.assert_array_equal(actual, expected) + + def test_frobenius_between_factor(self): + """Test creation of a Frobenius BetweenFactor.""" + factor = FrobeniusBetweenFactorSO4(1, 2, Q1.between(Q2)) + actual = factor.evaluateError(Q1, Q2) + expected = np.zeros((16,)) + np.testing.assert_array_almost_equal(actual, expected) + + def test_frobenius_wormhole_factor(self): + """Test creation of a factor that calculates Shonan error.""" + R1 = SO3.Expmap(v1[3:]) + R2 = SO3.Expmap(v2[3:]) + factor = FrobeniusWormholeFactor(1, 2, R1.between(R2), p=4) + I4 = SOn(4) + Q1 = I4.retract(v1) + Q2 = I4.retract(v2) + actual = factor.evaluateError(Q1, Q2) + expected = np.zeros((12,)) + np.testing.assert_array_almost_equal(actual, expected, decimal=4) + + +if __name__ == "__main__": + unittest.main() diff --git a/gtsam.h b/gtsam.h index 614db91c7..cbf737390 100644 --- a/gtsam.h +++ b/gtsam.h @@ -598,6 +598,7 @@ class SOn { // Standard Constructors SOn(size_t n); static gtsam::SOn FromMatrix(Matrix R); + static gtsam::SOn Lift(size_t n, Matrix R); // Testable void print(string s) const; @@ -2835,6 +2836,34 @@ virtual class KarcherMeanFactor : gtsam::NonlinearFactor { KarcherMeanFactor(const gtsam::KeyVector& keys); }; +#include +gtsam::noiseModel::Isotropic* ConvertPose3NoiseModel( + gtsam::noiseModel::Base* model, size_t d); + +template +virtual class FrobeniusFactor : gtsam::NoiseModelFactor { + FrobeniusFactor(size_t key1, size_t key2); + FrobeniusFactor(size_t key1, size_t key2, gtsam::noiseModel::Base* model); + + Vector evaluateError(const T& R1, const T& R2); +}; + +template +virtual class FrobeniusBetweenFactor : gtsam::NoiseModelFactor { + FrobeniusBetweenFactor(size_t key1, size_t key2, const T& R12); + FrobeniusBetweenFactor(size_t key1, size_t key2, const T& R12, gtsam::noiseModel::Base* model); + + Vector evaluateError(const T& R1, const T& R2); +}; + +virtual class FrobeniusWormholeFactor : gtsam::NoiseModelFactor { + FrobeniusWormholeFactor(size_t key1, size_t key2, const gtsam::Rot3& R12, + size_t p); + FrobeniusWormholeFactor(size_t key1, size_t key2, const gtsam::Rot3& R12, + size_t p, gtsam::noiseModel::Base* model); + Vector evaluateError(const gtsam::SOn& Q1, const gtsam::SOn& Q2); +}; + //************************************************************************* // Navigation //************************************************************************* diff --git a/gtsam/slam/FrobeniusFactor.cpp b/gtsam/slam/FrobeniusFactor.cpp new file mode 100644 index 000000000..904addb03 --- /dev/null +++ b/gtsam/slam/FrobeniusFactor.cpp @@ -0,0 +1,117 @@ +/* ---------------------------------------------------------------------------- + + * GTSAM Copyright 2010-2019, Georgia Tech Research Corporation, + * Atlanta, Georgia 30332-0415 + * All Rights Reserved + * Authors: Frank Dellaert, et al. (see THANKS for the full author list) + + * See LICENSE for the license information + + * -------------------------------------------------------------------------- */ + +/** + * @file FrobeniusFactor.cpp + * @date March 2019 + * @author Frank Dellaert + * @brief Various factors that minimize some Frobenius norm + */ + +#include + +#include +#include +#include + +#include +#include +#include + +using namespace std; + +namespace gtsam { + +//****************************************************************************** +boost::shared_ptr ConvertPose3NoiseModel( + const SharedNoiseModel& model, size_t d, bool defaultToUnit) { + double sigma = 1.0; + if (model != nullptr) { + if (model->dim() != 6) { + if (!defaultToUnit) + throw std::runtime_error("Can only convert Pose3 noise models"); + } else { + auto sigmas = model->sigmas().head(3).eval(); + if (sigmas(1) != sigmas(0) || sigmas(2) != sigmas(0)) { + if (!defaultToUnit) + throw std::runtime_error("Can only convert isotropic rotation noise"); + } else { + sigma = sigmas(0); + } + } + } + return noiseModel::Isotropic::Sigma(d, sigma); +} + +//****************************************************************************** +FrobeniusWormholeFactor::FrobeniusWormholeFactor(Key j1, Key j2, const Rot3& R12, + size_t p, + const SharedNoiseModel& model) + : NoiseModelFactor2(ConvertPose3NoiseModel(model, p * 3), j1, j2), + M_(R12.matrix()), // 3*3 in all cases + p_(p), // 4 for SO(4) + pp_(p * p), // 16 for SO(4) + dimension_(SOn::Dimension(p)), // 6 for SO(4) + G_(pp_, dimension_) // 16*6 for SO(4) +{ + // Calculate G matrix of vectorized generators + Matrix Z = Matrix::Zero(p, p); + for (size_t j = 0; j < dimension_; j++) { + const auto X = SOn::Hat(Eigen::VectorXd::Unit(dimension_, j)); + G_.col(j) = Eigen::Map(X.data(), pp_, 1); + } + assert(noiseModel()->dim() == 3 * p_); +} + +//****************************************************************************** +Vector FrobeniusWormholeFactor::evaluateError( + const SOn& Q1, const SOn& Q2, boost::optional H1, + boost::optional H2) const { + gttic(FrobeniusWormholeFactorP_evaluateError); + + const Matrix& M1 = Q1.matrix(); + const Matrix& M2 = Q2.matrix(); + assert(M1.rows() == p_ && M2.rows() == p_); + + const size_t dim = 3 * p_; // Stiefel manifold dimension + Vector fQ2(dim), hQ1(dim); + + // Vectorize and extract only d leftmost columns, i.e. vec(M2*P) + fQ2 << Eigen::Map(M2.data(), dim, 1); + + // Vectorize M1*P*R12 + const Matrix Q1PR12 = M1.leftCols<3>() * M_; + hQ1 << Eigen::Map(Q1PR12.data(), dim, 1); + + // If asked, calculate Jacobian as (M \otimes M1) * G + if (H1) { + const size_t p2 = 2 * p_; + Matrix RPxQ = Matrix::Zero(dim, pp_); + RPxQ.block(0, 0, p_, dim) << M1 * M_(0, 0), M1 * M_(1, 0), M1 * M_(2, 0); + RPxQ.block(p_, 0, p_, dim) << M1 * M_(0, 1), M1 * M_(1, 1), M1 * M_(2, 1); + RPxQ.block(p2, 0, p_, dim) << M1 * M_(0, 2), M1 * M_(1, 2), M1 * M_(2, 2); + *H1 = -RPxQ * G_; + } + if (H2) { + const size_t p2 = 2 * p_; + Matrix PxQ = Matrix::Zero(dim, pp_); + PxQ.block(0, 0, p_, p_) = M2; + PxQ.block(p_, p_, p_, p_) = M2; + PxQ.block(p2, p2, p_, p_) = M2; + *H2 = PxQ * G_; + } + + return fQ2 - hQ1; +} + +//****************************************************************************** + +} // namespace gtsam diff --git a/gtsam/slam/FrobeniusFactor.h b/gtsam/slam/FrobeniusFactor.h new file mode 100644 index 000000000..60fa82ab4 --- /dev/null +++ b/gtsam/slam/FrobeniusFactor.h @@ -0,0 +1,145 @@ +/* ---------------------------------------------------------------------------- + + * GTSAM Copyright 2010-2019, Georgia Tech Research Corporation, + * Atlanta, Georgia 30332-0415 + * All Rights Reserved + * Authors: Frank Dellaert, et al. (see THANKS for the full author list) + + * See LICENSE for the license information + + * -------------------------------------------------------------------------- */ + +/** + * @file FrobeniusFactor.h + * @date March 2019 + * @author Frank Dellaert + * @brief Various factors that minimize some Frobenius norm + */ + +#pragma once + +#include +#include +#include + +namespace gtsam { + +/** + * When creating (any) FrobeniusFactor we convert a 6-dimensional Pose3 + * BetweenFactor noise model into an 9 or 16-dimensional isotropic noise + * model used to weight the Frobenius norm. If the noise model passed is + * null we return a Dim-dimensional isotropic noise model with sigma=1.0. If + * not, we we check if the 3-dimensional noise model on rotations is + * isotropic. If it is, we extend to 'Dim' dimensions, otherwise we throw an + * error. If defaultToUnit == false throws an exception on unexepcted input. + */ +boost::shared_ptr ConvertPose3NoiseModel( + const SharedNoiseModel& model, size_t d, bool defaultToUnit = true); + +/** + * FrobeniusPrior calculates the Frobenius norm between a given matrix and an + * element of SO(3) or SO(4). + */ +template +class FrobeniusPrior : public NoiseModelFactor1 { + enum { Dim = Rot::VectorN2::RowsAtCompileTime }; + using MatrixNN = typename Rot::MatrixNN; + Eigen::Matrix vecM_; ///< vectorized matrix to approximate + + public: + /// Constructor + FrobeniusPrior(Key j, const MatrixNN& M, + const SharedNoiseModel& model = nullptr) + : NoiseModelFactor1(ConvertPose3NoiseModel(model, Dim), j) { + vecM_ << Eigen::Map(M.data(), Dim, 1); + } + + /// Error is just Frobenius norm between Rot element and vectorized matrix M. + Vector evaluateError(const Rot& R, + boost::optional H = boost::none) const { + return R.vec(H) - vecM_; // Jacobian is computed only when needed. + } +}; + +/** + * FrobeniusFactor calculates the Frobenius norm between rotation matrices. + * The template argument can be any fixed-size SO. + */ +template +class FrobeniusFactor : public NoiseModelFactor2 { + enum { Dim = Rot::VectorN2::RowsAtCompileTime }; + + public: + /// Constructor + FrobeniusFactor(Key j1, Key j2, const SharedNoiseModel& model = nullptr) + : NoiseModelFactor2(ConvertPose3NoiseModel(model, Dim), j1, + j2) {} + + /// Error is just Frobenius norm between rotation matrices. + Vector evaluateError(const Rot& R1, const Rot& R2, + boost::optional H1 = boost::none, + boost::optional H2 = boost::none) const { + Vector error = R2.vec(H2) - R1.vec(H1); + if (H1) *H1 = -*H1; + return error; + } +}; + +/** + * FrobeniusBetweenFactor is a BetweenFactor that evaluates the Frobenius norm + * of the rotation error between measured and predicted (rather than the + * Logmap of the error). This factor is only defined for fixed-dimension types, + * and in fact only SO3 and SO4 really work, as we need SO::AdjointMap. + */ +template +class FrobeniusBetweenFactor : public NoiseModelFactor2 { + Rot R12_; ///< measured rotation between R1 and R2 + Eigen::Matrix + R2hat_H_R1_; ///< fixed derivative of R2hat wrpt R1 + enum { Dim = Rot::VectorN2::RowsAtCompileTime }; + + public: + /// Constructor + FrobeniusBetweenFactor(Key j1, Key j2, const Rot& R12, + const SharedNoiseModel& model = nullptr) + : NoiseModelFactor2( + ConvertPose3NoiseModel(model, Dim), j1, j2), + R12_(R12), + R2hat_H_R1_(R12.inverse().AdjointMap()) {} + + /// Error is Frobenius norm between R1*R12 and R2. + Vector evaluateError(const Rot& R1, const Rot& R2, + boost::optional H1 = boost::none, + boost::optional H2 = boost::none) const { + const Rot R2hat = R1.compose(R12_); + Eigen::Matrix vec_H_R2hat; + Vector error = R2.vec(H2) - R2hat.vec(H1 ? &vec_H_R2hat : nullptr); + if (H1) *H1 = -vec_H_R2hat * R2hat_H_R1_; + return error; + } +}; + +/** + * FrobeniusWormholeFactor is a BetweenFactor that moves in SO(p), but will + * land on the SO(3) sub-manifold of SO(p) at the global minimum. It projects + * the SO(p) matrices down to a Stiefel manifold of p*d matrices. + * TODO(frank): template on D=2 or 3 + */ +class FrobeniusWormholeFactor : public NoiseModelFactor2 { + Matrix M_; ///< measured rotation between R1 and R2 + size_t p_, pp_, dimension_; ///< dimensionality constants + Matrix G_; ///< matrix of vectorized generators + + public: + /// Constructor. Note we convert to 3*p-dimensional noise model. + FrobeniusWormholeFactor(Key j1, Key j2, const Rot3& R12, size_t p = 4, + const SharedNoiseModel& model = nullptr); + + /// Error is Frobenius norm between Q1*P*R12 and Q2*P, where P=[I_3x3;0] + /// projects down from SO(p) to the Stiefel manifold of px3 matrices. + Vector evaluateError(const SOn& Q1, const SOn& Q2, + boost::optional H1 = boost::none, + boost::optional H2 = boost::none) const; +}; + +} // namespace gtsam diff --git a/gtsam/slam/tests/testFrobeniusFactor.cpp b/gtsam/slam/tests/testFrobeniusFactor.cpp new file mode 100644 index 000000000..3aefeeb1a --- /dev/null +++ b/gtsam/slam/tests/testFrobeniusFactor.cpp @@ -0,0 +1,244 @@ +/* ---------------------------------------------------------------------------- + + * GTSAM Copyright 2010-2019, Georgia Tech Research Corporation, + * Atlanta, Georgia 30332-0415 + * All Rights Reserved + * Authors: Frank Dellaert, et al. (see THANKS for the full author list) + + * See LICENSE for the license information + + * -------------------------------------------------------------------------- */ + +/** + * testFrobeniusFactor.cpp + * + * @file testFrobeniusFactor.cpp + * @date March 2019 + * @author Frank Dellaert + * @brief Check evaluateError for various Frobenius norm + */ + +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#include + +using namespace std; +using namespace gtsam; + +//****************************************************************************** +namespace so3 { +SO3 id; +Vector3 v1 = (Vector(3) << 0.1, 0, 0).finished(); +SO3 R1 = SO3::Expmap(v1); +Vector3 v2 = (Vector(3) << 0.01, 0.02, 0.03).finished(); +SO3 R2 = SO3::Expmap(v2); +SO3 R12 = R1.between(R2); +} // namespace so3 + +/* ************************************************************************* */ +TEST(FrobeniusPriorSO3, evaluateError) { + using namespace ::so3; + auto factor = FrobeniusPrior(1, R2.matrix()); + Vector actual = factor.evaluateError(R1); + Vector expected = R1.vec() - R2.vec(); + EXPECT(assert_equal(expected, actual, 1e-9)); + + Values values; + values.insert(1, R1); + EXPECT_CORRECT_FACTOR_JACOBIANS(factor, values, 1e-7, 1e-5); +} + +/* ************************************************************************* */ +TEST(FrobeniusPriorSO3, ClosestTo) { + // Example top-left of SO(4) matrix not quite on SO(3) manifold + Matrix3 M; + M << 0.79067393, 0.6051136, -0.0930814, // + 0.4155925, -0.64214347, -0.64324489, // + -0.44948549, 0.47046326, -0.75917576; + + SO3 expected = SO3::ClosestTo(M); + + // manifold optimization gets same result as SVD solution in ClosestTo + NonlinearFactorGraph graph; + graph.emplace_shared >(1, M); + + Values initial; + initial.insert(1, SO3(I_3x3)); + auto result = GaussNewtonOptimizer(graph, initial).optimize(); + EXPECT_DOUBLES_EQUAL(0.0, graph.error(result), 1e-6); + EXPECT(assert_equal(expected, result.at(1), 1e-6)); +} + +/* ************************************************************************* */ +TEST(FrobeniusPriorSO3, ChordalL2mean) { + // See Hartley13ijcv: + // Cost function C(R) = \sum FrobeniusPrior(R,R_i) + // Closed form solution = ClosestTo(C_e), where + // C_e = \sum R_i !!!! + + // We will test by computing mean of R1=exp(v1) R1^T=exp(-v1): + using namespace ::so3; + SO3 expected; // identity + Matrix3 M = R1.matrix() + R1.matrix().transpose(); + EXPECT(assert_equal(expected, SO3::ClosestTo(M), 1e-6)); + EXPECT(assert_equal(expected, SO3::ChordalMean({R1, R1.inverse()}), 1e-6)); + + // manifold optimization gets same result as ChordalMean + NonlinearFactorGraph graph; + graph.emplace_shared >(1, R1.matrix()); + graph.emplace_shared >(1, R1.matrix().transpose()); + + Values initial; + initial.insert(1, R1.inverse()); + auto result = GaussNewtonOptimizer(graph, initial).optimize(); + EXPECT_DOUBLES_EQUAL(0.0, graph.error(result), 0.1); // Why so loose? + EXPECT(assert_equal(expected, result.at(1), 1e-5)); +} + +/* ************************************************************************* */ +TEST(FrobeniusFactorSO3, evaluateError) { + using namespace ::so3; + auto factor = FrobeniusFactor(1, 2); + Vector actual = factor.evaluateError(R1, R2); + Vector expected = R2.vec() - R1.vec(); + EXPECT(assert_equal(expected, actual, 1e-9)); + + Values values; + values.insert(1, R1); + values.insert(2, R2); + EXPECT_CORRECT_FACTOR_JACOBIANS(factor, values, 1e-7, 1e-5); +} + +/* ************************************************************************* */ +// Commented out as SO(n) not yet supported (and might never be) +// TEST(FrobeniusBetweenFactorSOn, evaluateError) { +// using namespace ::so3; +// auto factor = +// FrobeniusBetweenFactor(1, 2, SOn::FromMatrix(R12.matrix())); +// Vector actual = factor.evaluateError(SOn::FromMatrix(R1.matrix()), +// SOn::FromMatrix(R2.matrix())); +// Vector expected = Vector9::Zero(); +// EXPECT(assert_equal(expected, actual, 1e-9)); + +// Values values; +// values.insert(1, R1); +// values.insert(2, R2); +// EXPECT_CORRECT_FACTOR_JACOBIANS(factor, values, 1e-7, 1e-5); +// } + +/* ************************************************************************* */ +TEST(FrobeniusBetweenFactorSO3, evaluateError) { + using namespace ::so3; + auto factor = FrobeniusBetweenFactor(1, 2, R12); + Vector actual = factor.evaluateError(R1, R2); + Vector expected = Vector9::Zero(); + EXPECT(assert_equal(expected, actual, 1e-9)); + + Values values; + values.insert(1, R1); + values.insert(2, R2); + EXPECT_CORRECT_FACTOR_JACOBIANS(factor, values, 1e-7, 1e-5); +} + +//****************************************************************************** +namespace so4 { +SO4 id; +Vector6 v1 = (Vector(6) << 0.1, 0, 0, 0, 0, 0).finished(); +SO4 Q1 = SO4::Expmap(v1); +Vector6 v2 = (Vector(6) << 0.01, 0.02, 0.03, 0.04, 0.05, 0.06).finished(); +SO4 Q2 = SO4::Expmap(v2); +} // namespace so4 + +/* ************************************************************************* */ +TEST(FrobeniusFactorSO4, evaluateError) { + using namespace ::so4; + auto factor = FrobeniusFactor(1, 2, noiseModel::Unit::Create(6)); + Vector actual = factor.evaluateError(Q1, Q2); + Vector expected = Q2.vec() - Q1.vec(); + EXPECT(assert_equal(expected, actual, 1e-9)); + + Values values; + values.insert(1, Q1); + values.insert(2, Q2); + EXPECT_CORRECT_FACTOR_JACOBIANS(factor, values, 1e-7, 1e-5); +} + +/* ************************************************************************* */ +TEST(FrobeniusBetweenFactorSO4, evaluateError) { + using namespace ::so4; + Matrix4 M{I_4x4}; + M.topLeftCorner<3, 3>() = ::so3::R12.matrix(); + auto factor = FrobeniusBetweenFactor(1, 2, Q1.between(Q2)); + Matrix H1, H2; + Vector actual = factor.evaluateError(Q1, Q2, H1, H2); + Vector expected = SO4::VectorN2::Zero(); + EXPECT(assert_equal(expected, actual, 1e-9)); + + Values values; + values.insert(1, Q1); + values.insert(2, Q2); + EXPECT_CORRECT_FACTOR_JACOBIANS(factor, values, 1e-7, 1e-5); +} + +//****************************************************************************** +namespace submanifold { +SO4 id; +Vector6 v1 = (Vector(6) << 0, 0, 0, 0.1, 0, 0).finished(); +SO3 R1 = SO3::Expmap(v1.tail<3>()); +SO4 Q1 = SO4::Expmap(v1); +Vector6 v2 = (Vector(6) << 0, 0, 0, 0.01, 0.02, 0.03).finished(); +SO3 R2 = SO3::Expmap(v2.tail<3>()); +SO4 Q2 = SO4::Expmap(v2); +SO3 R12 = R1.between(R2); +} // namespace submanifold + +/* ************************************************************************* */ +TEST(FrobeniusWormholeFactor, evaluateError) { + auto model = noiseModel::Isotropic::Sigma(6, 1.2); // dimension = 6 not 16 + for (const size_t p : {5, 4, 3}) { + Matrix M = Matrix::Identity(p, p); + M.topLeftCorner(3, 3) = submanifold::R1.matrix(); + SOn Q1(M); + M.topLeftCorner(3, 3) = submanifold::R2.matrix(); + SOn Q2(M); + auto factor = + FrobeniusWormholeFactor(1, 2, Rot3(::so3::R12.matrix()), p, model); + Matrix H1, H2; + factor.evaluateError(Q1, Q2, H1, H2); + + // Test derivatives + Values values; + values.insert(1, Q1); + values.insert(2, Q2); + EXPECT_CORRECT_FACTOR_JACOBIANS(factor, values, 1e-7, 1e-5); + } +} + +/* ************************************************************************* */ +TEST(FrobeniusWormholeFactor, equivalenceToSO3) { + using namespace ::submanifold; + auto R12 = ::so3::R12.retract(Vector3(0.1, 0.2, -0.1)); + auto model = noiseModel::Isotropic::Sigma(6, 1.2); // wrong dimension + auto factor3 = FrobeniusBetweenFactor(1, 2, R12, model); + auto factor4 = FrobeniusWormholeFactor(1, 2, Rot3(R12.matrix()), 4, model); + const Eigen::Map E3(factor3.evaluateError(R1, R2).data()); + const Eigen::Map E4( + factor4.evaluateError(SOn(Q1.matrix()), SOn(Q2.matrix())).data()); + EXPECT(assert_equal((Matrix)E4.topLeftCorner<3, 3>(), E3, 1e-9)); + EXPECT(assert_equal((Matrix)E4.row(3), Matrix13::Zero(), 1e-9)); +} + +/* ************************************************************************* */ +int main() { + TestResult tr; + return TestRegistry::runAllTests(tr); +} +/* ************************************************************************* */ diff --git a/timing/timeFrobeniusFactor.cpp b/timing/timeFrobeniusFactor.cpp new file mode 100644 index 000000000..c8bdd8fec --- /dev/null +++ b/timing/timeFrobeniusFactor.cpp @@ -0,0 +1,110 @@ +/* ---------------------------------------------------------------------------- + + * GTSAM Copyright 2010, Georgia Tech Research Corporation, + * Atlanta, Georgia 30332-0415 + * All Rights Reserved + * Authors: Frank Dellaert, et al. (see THANKS for the full author list) + + * See LICENSE for the license information + + * -------------------------------------------------------------------------- */ + +/** + * @file timeFrobeniusFactor.cpp + * @brief time FrobeniusFactor with BAL file + * @author Frank Dellaert + * @date June 6, 2015 + */ + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#include +#include +#include + +using namespace std; +using namespace gtsam; + +static SharedNoiseModel gNoiseModel = noiseModel::Unit::Create(2); + +int main(int argc, char* argv[]) { + // primitive argument parsing: + if (argc > 3) { + throw runtime_error("Usage: timeFrobeniusFactor [g2oFile]"); + } + + string g2oFile; + try { + if (argc > 1) + g2oFile = argv[argc - 1]; + else + g2oFile = + "/Users/dellaert/git/2019c-notes-shonanrotationaveraging/matlabCode/" + "datasets/randomTorus3D.g2o"; + // g2oFile = findExampleDataFile("sphere_smallnoise.graph"); + } catch (const exception& e) { + cerr << e.what() << '\n'; + exit(1); + } + + // Read G2O file + const auto factors = parse3DFactors(g2oFile); + const auto poses = parse3DPoses(g2oFile); + + // Build graph + NonlinearFactorGraph graph; + // graph.add(NonlinearEquality(0, SO4())); + auto priorModel = noiseModel::Isotropic::Sigma(6, 10000); + graph.add(PriorFactor(0, SO4(), priorModel)); + for (const auto& factor : factors) { + const auto& keys = factor->keys(); + const auto& Tij = factor->measured(); + const auto& model = factor->noiseModel(); + graph.emplace_shared( + keys[0], keys[1], SO3(Tij.rotation().matrix()), model); + } + + boost::mt19937 rng(42); + + // Set parameters to be similar to ceres + LevenbergMarquardtParams params; + LevenbergMarquardtParams::SetCeresDefaults(¶ms); + params.setLinearSolverType("MULTIFRONTAL_QR"); + // params.setVerbosityLM("SUMMARY"); + // params.linearSolverType = LevenbergMarquardtParams::Iterative; + // auto pcg = boost::make_shared(); + // pcg->preconditioner_ = + // boost::make_shared(); + // boost::make_shared(); + // params.iterativeParams = pcg; + + // Optimize + for (size_t i = 0; i < 100; i++) { + gttic_(optimize); + Values initial; + initial.insert(0, SO4()); + for (size_t j = 1; j < poses.size(); j++) { + initial.insert(j, SO4::Random(rng)); + } + LevenbergMarquardtOptimizer lm(graph, initial, params); + Values result = lm.optimize(); + cout << "cost = " << graph.error(result) << endl; + } + + tictoc_finishedIteration_(); + tictoc_print_(); + + return 0; +} From 604f1511ccd6bab7e14b6eb71249d29606e5188f Mon Sep 17 00:00:00 2001 From: Fan Jiang Date: Sat, 20 Jun 2020 12:09:03 -0400 Subject: [PATCH 076/869] Fix UAF --- gtsam/slam/tests/testFrobeniusFactor.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/gtsam/slam/tests/testFrobeniusFactor.cpp b/gtsam/slam/tests/testFrobeniusFactor.cpp index 3aefeeb1a..9cb0c19fa 100644 --- a/gtsam/slam/tests/testFrobeniusFactor.cpp +++ b/gtsam/slam/tests/testFrobeniusFactor.cpp @@ -229,8 +229,8 @@ TEST(FrobeniusWormholeFactor, equivalenceToSO3) { auto model = noiseModel::Isotropic::Sigma(6, 1.2); // wrong dimension auto factor3 = FrobeniusBetweenFactor(1, 2, R12, model); auto factor4 = FrobeniusWormholeFactor(1, 2, Rot3(R12.matrix()), 4, model); - const Eigen::Map E3(factor3.evaluateError(R1, R2).data()); - const Eigen::Map E4( + const Matrix3 E3(factor3.evaluateError(R1, R2).data()); + const Matrix43 E4( factor4.evaluateError(SOn(Q1.matrix()), SOn(Q2.matrix())).data()); EXPECT(assert_equal((Matrix)E4.topLeftCorner<3, 3>(), E3, 1e-9)); EXPECT(assert_equal((Matrix)E4.row(3), Matrix13::Zero(), 1e-9)); From 37673771aec059e14705fad69a0282a9c55e3eba Mon Sep 17 00:00:00 2001 From: Fan Jiang Date: Sat, 20 Jun 2020 22:21:17 -0400 Subject: [PATCH 077/869] Fixed all alignment problems --- gtsam.h | 2 +- gtsam/base/make_shared.h | 44 ++++++++++++++++++++++++++++++++++++++++ gtsam/base/types.h | 26 ++++++++++++++++++++++++ gtsam/geometry/SOn.h | 4 ++-- wrap/Module.cpp | 5 ++++- 5 files changed, 77 insertions(+), 4 deletions(-) create mode 100644 gtsam/base/make_shared.h diff --git a/gtsam.h b/gtsam.h index 614db91c7..cf232efa5 100644 --- a/gtsam.h +++ b/gtsam.h @@ -281,7 +281,7 @@ virtual class Value { }; #include -template +template virtual class GenericValue : gtsam::Value { void serializable() const; }; diff --git a/gtsam/base/make_shared.h b/gtsam/base/make_shared.h new file mode 100644 index 000000000..c8b63f5d4 --- /dev/null +++ b/gtsam/base/make_shared.h @@ -0,0 +1,44 @@ +/* ---------------------------------------------------------------------------- + + * GTSAM Copyright 2020, Georgia Tech Research Corporation, + * Atlanta, Georgia 30332-0415 + * All Rights Reserved + * Authors: Frank Dellaert, et al. (see THANKS for the full author list) + + * See LICENSE for the license information + + * -------------------------------------------------------------------------- */ + +/** + * @file make_shared.h + * @brief make_shared trampoline function to ensure proper alignment + * @author Fan Jiang + */ + +#pragma once + +#include +#include + +#include + +#include + +namespace gtsam { + + /** + * And our own `make_shared` as a layer of wrapping on `boost::make_shared` + */ + template + boost::enable_if_t::value, boost::shared_ptr> make_shared(Args&&... args) + { + return boost::allocate_shared(Eigen::aligned_allocator(), std::forward (args)...); + } + + template + boost::enable_if_t::value, boost::shared_ptr> make_shared(Args&&... args) + { + return boost::make_shared(std::forward (args)...); + } + +} \ No newline at end of file diff --git a/gtsam/base/types.h b/gtsam/base/types.h index 2fa6eebb6..3abbdfe81 100644 --- a/gtsam/base/types.h +++ b/gtsam/base/types.h @@ -230,3 +230,29 @@ namespace std { #ifdef ERROR #undef ERROR #endif + +namespace gtsam { + + /** + * A trait to mark classes that need special alignment. + * Please refer to https://github.com/PointCloudLibrary/pcl/pull/3163 + */ +#if __cplusplus < 201703L + template using void_t = void; +#endif + + template> + struct has_custom_allocator : std::false_type { + }; + template + struct has_custom_allocator> : std::true_type { + }; + +} + +/** + * This is necessary for the Cython wrapper to work properly, and possibly reduce future misalignment problems. + */ +#define GTSAM_MAKE_ALIGNED_OPERATOR_NEW \ + EIGEN_MAKE_ALIGNED_OPERATOR_NEW \ + using _custom_allocator_type_trait = void; \ No newline at end of file diff --git a/gtsam/geometry/SOn.h b/gtsam/geometry/SOn.h index 5313d3018..767b12020 100644 --- a/gtsam/geometry/SOn.h +++ b/gtsam/geometry/SOn.h @@ -20,8 +20,8 @@ #include #include +#include #include - #include #include // TODO(frank): how to avoid? @@ -54,7 +54,7 @@ class SO : public LieGroup, internal::DimensionSO(N)> { using VectorN2 = Eigen::Matrix; using MatrixDD = Eigen::Matrix; - EIGEN_MAKE_ALIGNED_OPERATOR_NEW + GTSAM_MAKE_ALIGNED_OPERATOR_NEW protected: MatrixNN matrix_; ///< Rotation matrix diff --git a/wrap/Module.cpp b/wrap/Module.cpp index a7db9e1f6..ec02dc412 100644 --- a/wrap/Module.cpp +++ b/wrap/Module.cpp @@ -350,7 +350,10 @@ void Module::emit_cython_pxd(FileWriter& pxdFile) const { " T* get()\n" " long use_count() const\n" " T& operator*()\n\n" - " cdef shared_ptr[T] dynamic_pointer_cast[T,U](const shared_ptr[U]& r)\n" + " cdef shared_ptr[T] dynamic_pointer_cast[T,U](const shared_ptr[U]& r)\n\n"; + + // gtsam alignment-friendly shared_ptr + pxdFile.oss << "cdef extern from \"gtsam/base/make_shared.h\" namespace \"gtsam\":\n" " cdef shared_ptr[T] make_shared[T](const T& r)\n\n"; for(const TypedefPair& types: typedefs) From fad4fe39f28797f11a61461f3f0224f173046b2e Mon Sep 17 00:00:00 2001 From: Fan Jiang Date: Sat, 20 Jun 2020 22:48:40 -0400 Subject: [PATCH 078/869] Add missing include --- gtsam/base/make_shared.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/gtsam/base/make_shared.h b/gtsam/base/make_shared.h index c8b63f5d4..c5ac98f9c 100644 --- a/gtsam/base/make_shared.h +++ b/gtsam/base/make_shared.h @@ -20,7 +20,7 @@ #include #include -#include +#include #include From 693253f3768bbd618a688a8c173b6f1bd576fdec Mon Sep 17 00:00:00 2001 From: Fan Jiang Date: Sat, 20 Jun 2020 22:52:58 -0400 Subject: [PATCH 079/869] Fix wrap tests --- wrap/tests/expected-cython/geometry.pxd | 2 ++ 1 file changed, 2 insertions(+) diff --git a/wrap/tests/expected-cython/geometry.pxd b/wrap/tests/expected-cython/geometry.pxd index 0d9adac5f..3527840a3 100644 --- a/wrap/tests/expected-cython/geometry.pxd +++ b/wrap/tests/expected-cython/geometry.pxd @@ -16,6 +16,8 @@ cdef extern from "boost/shared_ptr.hpp" namespace "boost": T& operator*() cdef shared_ptr[T] dynamic_pointer_cast[T,U](const shared_ptr[U]& r) + +cdef extern from "gtsam/base/make_shared.h" namespace "gtsam": cdef shared_ptr[T] make_shared[T](const T& r) cdef extern from "gtsam/geometry/Point2.h" namespace "gtsam": From eab53f69de01ac06b9d2d20821539b4be4fade21 Mon Sep 17 00:00:00 2001 From: Fan Jiang Date: Mon, 22 Jun 2020 13:37:50 -0400 Subject: [PATCH 080/869] Address Frank's comments --- gtsam/base/make_shared.h | 14 +++++++------- 1 file changed, 7 insertions(+), 7 deletions(-) diff --git a/gtsam/base/make_shared.h b/gtsam/base/make_shared.h index c5ac98f9c..03de30497 100644 --- a/gtsam/base/make_shared.h +++ b/gtsam/base/make_shared.h @@ -17,28 +17,28 @@ #pragma once -#include #include -#include - #include +#include +#include + + namespace gtsam { - /** - * And our own `make_shared` as a layer of wrapping on `boost::make_shared` - */ + /// Add our own `make_shared` as a layer of wrapping on `boost::make_shared` template boost::enable_if_t::value, boost::shared_ptr> make_shared(Args&&... args) { return boost::allocate_shared(Eigen::aligned_allocator(), std::forward (args)...); } + /// Fall back to the boost version if no need for alignment template boost::enable_if_t::value, boost::shared_ptr> make_shared(Args&&... args) { return boost::make_shared(std::forward (args)...); } -} \ No newline at end of file +} From 8f923fa081f0702cb36681675833476c17f692ce Mon Sep 17 00:00:00 2001 From: Fan Jiang Date: Mon, 22 Jun 2020 15:18:31 -0400 Subject: [PATCH 081/869] Move away from boost --- gtsam/base/make_shared.h | 13 ++++++++++--- 1 file changed, 10 insertions(+), 3 deletions(-) diff --git a/gtsam/base/make_shared.h b/gtsam/base/make_shared.h index 03de30497..966dd516d 100644 --- a/gtsam/base/make_shared.h +++ b/gtsam/base/make_shared.h @@ -22,21 +22,28 @@ #include #include -#include +#include + +#if __cplusplus <= 201103L +namespace gtsam { + template + using enable_if_t = typename std::enable_if::type; +} +#endif namespace gtsam { /// Add our own `make_shared` as a layer of wrapping on `boost::make_shared` template - boost::enable_if_t::value, boost::shared_ptr> make_shared(Args&&... args) + gtsam::enable_if_t::value, boost::shared_ptr> make_shared(Args&&... args) { return boost::allocate_shared(Eigen::aligned_allocator(), std::forward (args)...); } /// Fall back to the boost version if no need for alignment template - boost::enable_if_t::value, boost::shared_ptr> make_shared(Args&&... args) + gtsam::enable_if_t::value, boost::shared_ptr> make_shared(Args&&... args) { return boost::make_shared(std::forward (args)...); } From 263a1d2afa7714a76b00771579202bbc543fa872 Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Mon, 22 Jun 2020 16:47:37 -0500 Subject: [PATCH 082/869] export cython install path so it can be picked up by other cmake projects --- gtsam_extra.cmake.in | 1 + 1 file changed, 1 insertion(+) diff --git a/gtsam_extra.cmake.in b/gtsam_extra.cmake.in index 8a9a13648..01ac00b37 100644 --- a/gtsam_extra.cmake.in +++ b/gtsam_extra.cmake.in @@ -9,5 +9,6 @@ set (GTSAM_USE_TBB @GTSAM_USE_TBB@) set (GTSAM_DEFAULT_ALLOCATOR @GTSAM_DEFAULT_ALLOCATOR@) if("@GTSAM_INSTALL_CYTHON_TOOLBOX@") + list(APPEND GTSAM_CYTHON_INSTALL_PATH "@GTSAM_CYTHON_INSTALL_PATH@") list(APPEND GTSAM_EIGENCY_INSTALL_PATH "@GTSAM_EIGENCY_INSTALL_PATH@") endif() From 1725a577cf881ae5478dbe08cef19b4b3f5a4f55 Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Sat, 21 Mar 2020 14:52:17 -0400 Subject: [PATCH 083/869] cmake function to install python package once make install is completed --- cmake/GtsamCythonWrap.cmake | 7 +++++++ cython/CMakeLists.txt | 2 ++ 2 files changed, 9 insertions(+) diff --git a/cmake/GtsamCythonWrap.cmake b/cmake/GtsamCythonWrap.cmake index f1382729f..3ca8b903f 100644 --- a/cmake/GtsamCythonWrap.cmake +++ b/cmake/GtsamCythonWrap.cmake @@ -279,3 +279,10 @@ function(install_cython_files source_files dest_directory) endfunction() +function(install_python_package install_path) + set(package_path "${install_path}${GTSAM_BUILD_TAG}") + # set cython directory permissions to user so we don't get permission denied + install(CODE "execute_process(COMMAND sh \"-c\" \"chown -R $(logname):$(logname) ${package_path}\")") + # go to cython directory and run setup.py + install(CODE "execute_process(COMMAND sh \"-c\" \"cd ${package_path} && python setup.py install\")") +endfunction() diff --git a/cython/CMakeLists.txt b/cython/CMakeLists.txt index 4cc9d2f5d..96503b82f 100644 --- a/cython/CMakeLists.txt +++ b/cython/CMakeLists.txt @@ -45,4 +45,6 @@ if (GTSAM_INSTALL_CYTHON_TOOLBOX) install_cython_scripts("${PROJECT_SOURCE_DIR}/cython/gtsam" "${GTSAM_CYTHON_INSTALL_PATH}" "*.py") install_cython_scripts("${PROJECT_SOURCE_DIR}/cython/gtsam_unstable" "${GTSAM_CYTHON_INSTALL_PATH}" "*.py") + install_python_package("${GTSAM_CYTHON_INSTALL_PATH}") + endif () From a796f74b8004d7cc12acaf3d20c9b3827a590770 Mon Sep 17 00:00:00 2001 From: Gerry Chen Date: Mon, 22 Jun 2020 20:24:32 -0400 Subject: [PATCH 084/869] use boost paths append to have platform agnostic path separators --- gtsam/base/serializationTestHelpers.h | 27 ++++++++++++++------------- 1 file changed, 14 insertions(+), 13 deletions(-) diff --git a/gtsam/base/serializationTestHelpers.h b/gtsam/base/serializationTestHelpers.h index 031a6278f..602fd68f6 100644 --- a/gtsam/base/serializationTestHelpers.h +++ b/gtsam/base/serializationTestHelpers.h @@ -42,10 +42,11 @@ T create() { } // Creates or empties a folder in the build folder and returns the relative path -std::string resetFilesystem() { - boost::filesystem::remove_all("actual"); - boost::filesystem::create_directory("actual"); - return "actual/"; +boost::filesystem::path resetFilesystem( + boost::filesystem::path folder = "actual") { + boost::filesystem::remove_all(folder); + boost::filesystem::create_directory(folder); + return folder; } // Templated round-trip serialization @@ -61,10 +62,10 @@ void roundtrip(const T& input, T& output) { // Templated round-trip serialization using a file template void roundtripFile(const T& input, T& output) { - std::string path = resetFilesystem(); + boost::filesystem::path path = resetFilesystem()/"graph.dat"; - serializeToFile(input, path + "graph.dat"); - deserializeFromFile(path + "graph.dat", output); + serializeToFile(input, path.string()); + deserializeFromFile(path.string(), output); } // This version requires equality operator @@ -109,13 +110,13 @@ void roundtripXML(const T& input, T& output) { // Templated round-trip serialization using XML File template void roundtripXMLFile(const T& input, T& output) { - std::string path = resetFilesystem(); + boost::filesystem::path path = resetFilesystem()/"graph.xml"; // Serialize - serializeToXMLFile(input, path + "graph.xml"); + serializeToXMLFile(input, path.string()); // De-serialize - deserializeFromXMLFile(path + "graph.xml", output); + deserializeFromXMLFile(path.string(), output); } // This version requires equality operator @@ -160,11 +161,11 @@ void roundtripBinary(const T& input, T& output) { // Templated round-trip serialization using Binary file template void roundtripBinaryFile(const T& input, T& output) { - std::string path = resetFilesystem(); + boost::filesystem::path path = resetFilesystem()/"graph.bin"; // Serialize - serializeToBinaryFile(input, path + "graph.bin"); + serializeToBinaryFile(input, path.string()); // De-serialize - deserializeFromBinaryFile(path + "graph.bin", output); + deserializeFromBinaryFile(path.string(), output); } // This version requires equality operator From 93a00a38a40a21e21a1c20da9209192a7076fc85 Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Mon, 22 Jun 2020 20:14:03 -0500 Subject: [PATCH 085/869] add new make command for installing python wrapper --- cmake/GtsamCythonWrap.cmake | 17 ++++++++++++----- cython/CMakeLists.txt | 3 +++ cython/scripts/install.bat | 0 cython/scripts/install.sh | 21 +++++++++++++++++++++ 4 files changed, 36 insertions(+), 5 deletions(-) create mode 100755 cython/scripts/install.bat create mode 100755 cython/scripts/install.sh diff --git a/cmake/GtsamCythonWrap.cmake b/cmake/GtsamCythonWrap.cmake index 3ca8b903f..361038ce0 100644 --- a/cmake/GtsamCythonWrap.cmake +++ b/cmake/GtsamCythonWrap.cmake @@ -280,9 +280,16 @@ function(install_cython_files source_files dest_directory) endfunction() function(install_python_package install_path) - set(package_path "${install_path}${GTSAM_BUILD_TAG}") - # set cython directory permissions to user so we don't get permission denied - install(CODE "execute_process(COMMAND sh \"-c\" \"chown -R $(logname):$(logname) ${package_path}\")") - # go to cython directory and run setup.py - install(CODE "execute_process(COMMAND sh \"-c\" \"cd ${package_path} && python setup.py install\")") +#TODO this will only work for Linux. Need to make it work on macOS and Windows as well +#TODO Running `sudo make install` makes this run in admin space causing Python 2.7 to be picked up. + # # go to cython directory and run setup.py + # install(CODE "execute_process(COMMAND sh \"-c\" \"cd ${package_path} && python setup.py install\")") + if(CMAKE_SYSTEM_NAME STREQUAL "Windows") + set(PYTHON_INSTALL_SCRIPT "install.bat") + elseif(CMAKE_SYSTEM_NAME STREQUAL "Linux" OR CMAKE_SYSTEM_NAME STREQUAL "Darwin") + set(PYTHON_INSTALL_SCRIPT "install.sh") + endif() + + configure_file(${PROJECT_SOURCE_DIR}/cython/scripts/${PYTHON_INSTALL_SCRIPT} ${PROJECT_BINARY_DIR}/cython/scripts/${PYTHON_INSTALL_SCRIPT}) + add_custom_target(python-install "${PROJECT_BINARY_DIR}/cython/scripts/${PYTHON_INSTALL_SCRIPT}") endfunction() diff --git a/cython/CMakeLists.txt b/cython/CMakeLists.txt index 96503b82f..638bdfb2d 100644 --- a/cython/CMakeLists.txt +++ b/cython/CMakeLists.txt @@ -45,6 +45,9 @@ if (GTSAM_INSTALL_CYTHON_TOOLBOX) install_cython_scripts("${PROJECT_SOURCE_DIR}/cython/gtsam" "${GTSAM_CYTHON_INSTALL_PATH}" "*.py") install_cython_scripts("${PROJECT_SOURCE_DIR}/cython/gtsam_unstable" "${GTSAM_CYTHON_INSTALL_PATH}" "*.py") + # file(GLOB GTSAM_PYTHON_INSTALL_SCRIPTS "scripts/*") + # file(COPY ${GTSAM_PYTHON_INSTALL_SCRIPTS} DESTINATION ${PROJECT_BINARY_DIR}/cython/scripts) + install_python_package("${GTSAM_CYTHON_INSTALL_PATH}") endif () diff --git a/cython/scripts/install.bat b/cython/scripts/install.bat new file mode 100755 index 000000000..e69de29bb diff --git a/cython/scripts/install.sh b/cython/scripts/install.sh new file mode 100755 index 000000000..04759ca5e --- /dev/null +++ b/cython/scripts/install.sh @@ -0,0 +1,21 @@ +#!/bin/sh +echo "Installing GTSAM Python Wrapper" + +PACKAGE_PATH=${GTSAM_CYTHON_INSTALL_PATH}${GTSAM_BUILD_TAG} + +if [ ! -d "$PACKAGE_PATH" ] +then + echo "Directory $PACKAGE_PATH DOES NOT exist. Please run 'make install' first."; + exit 1; +fi + +# set cython directory permissions to user so we don't get permission denied +if [ "$(whoami)" != "root" ] +then + sudo chown -R $(logname) ${GTSAM_CYTHON_INSTALL_PATH} +else + chown -R $(logname) ${GTSAM_CYTHON_INSTALL_PATH} +fi + +echo "Running setup.py in $PACKAGE_PATH" +${PYTHON_EXECUTABLE} $PACKAGE_PATH/setup.py install From 327cbc515ff93db6f6547ed3deead1bdf9cfdb2e Mon Sep 17 00:00:00 2001 From: Gerry Chen Date: Mon, 22 Jun 2020 21:15:07 -0400 Subject: [PATCH 086/869] Separate stream creation and serialization Recommended by @ProfFan in #343 with the objective of making (de)serialize to string and to file more similar --- gtsam/base/serialization.h | 86 +++++++++++++++++++++++--------------- 1 file changed, 53 insertions(+), 33 deletions(-) diff --git a/gtsam/base/serialization.h b/gtsam/base/serialization.h index 191e0ecfb..031ee3a3e 100644 --- a/gtsam/base/serialization.h +++ b/gtsam/base/serialization.h @@ -44,18 +44,28 @@ namespace gtsam { // Serialization directly to strings in compressed format template -std::string serialize(const T& input) { - std::ostringstream out_archive_stream; +void serialize(const T& input, std::ostream & out_archive_stream) { boost::archive::text_oarchive out_archive(out_archive_stream); out_archive << input; +} + +template +void deserialize(std::istream & in_archive_stream, T& output) { + boost::archive::text_iarchive in_archive(in_archive_stream); + in_archive >> output; +} + +template +std::string serialize(const T& input) { + std::ostringstream out_archive_stream; + serialize(input, out_archive_stream); return out_archive_stream.str(); } template void deserialize(const std::string& serialized, T& output) { std::istringstream in_archive_stream(serialized); - boost::archive::text_iarchive in_archive(in_archive_stream); - in_archive >> output; + deserialize(in_archive_stream, output); } template @@ -63,8 +73,7 @@ bool serializeToFile(const T& input, const std::string& filename) { std::ofstream out_archive_stream(filename.c_str()); if (!out_archive_stream.is_open()) return false; - boost::archive::text_oarchive out_archive(out_archive_stream); - out_archive << input; + serialize(input, out_archive_stream); out_archive_stream.close(); return true; } @@ -74,31 +83,37 @@ bool deserializeFromFile(const std::string& filename, T& output) { std::ifstream in_archive_stream(filename.c_str()); if (!in_archive_stream.is_open()) return false; - boost::archive::text_iarchive in_archive(in_archive_stream); - in_archive >> output; + deserialize(in_archive_stream, output); in_archive_stream.close(); return true; } // Serialization to XML format with named structures +template +void serializeXML(const T& input, std::ostream& out_archive_stream, + const std::string& name = "data") { + boost::archive::xml_oarchive out_archive(out_archive_stream); + out_archive << boost::serialization::make_nvp(name.c_str(), input); +} + +template +void deserializeXML(std::istream& in_archive_stream, T& output, + const std::string& name = "data") { + boost::archive::xml_iarchive in_archive(in_archive_stream); + in_archive >> boost::serialization::make_nvp(name.c_str(), output); +} + template std::string serializeXML(const T& input, const std::string& name="data") { std::ostringstream out_archive_stream; - // braces to flush out_archive as it goes out of scope before taking str() - // fixes crash with boost 1.66-1.68 - // see https://github.com/boostorg/serialization/issues/82 - { - boost::archive::xml_oarchive out_archive(out_archive_stream); - out_archive << boost::serialization::make_nvp(name.c_str(), input); - } + serializeXML(input, out_archive_stream, name); return out_archive_stream.str(); } template void deserializeXML(const std::string& serialized, T& output, const std::string& name="data") { std::istringstream in_archive_stream(serialized); - boost::archive::xml_iarchive in_archive(in_archive_stream); - in_archive >> boost::serialization::make_nvp(name.c_str(), output); + deserializeXML(in_archive_stream, output, name); } template @@ -106,10 +121,7 @@ bool serializeToXMLFile(const T& input, const std::string& filename, const std:: std::ofstream out_archive_stream(filename.c_str()); if (!out_archive_stream.is_open()) return false; - { - boost::archive::xml_oarchive out_archive(out_archive_stream); - out_archive << boost::serialization::make_nvp(name.c_str(), input); - } + serializeXML(input, out_archive_stream, name); out_archive_stream.close(); return true; } @@ -119,28 +131,38 @@ bool deserializeFromXMLFile(const std::string& filename, T& output, const std::s std::ifstream in_archive_stream(filename.c_str()); if (!in_archive_stream.is_open()) return false; - { - boost::archive::xml_iarchive in_archive(in_archive_stream); - in_archive >> boost::serialization::make_nvp(name.c_str(), output); - } + deserializeXML(in_archive_stream, output, name); in_archive_stream.close(); return true; } +// Serialization to binary format with named structures +template +void serializeBinary(const T& input, std::ostream& out_archive_stream, + const std::string& name = "data") { + boost::archive::binary_oarchive out_archive(out_archive_stream); + out_archive << boost::serialization::make_nvp(name.c_str(), input); +} + +template +void deserializeBinary(std::istream& in_archive_stream, T& output, + const std::string& name = "data") { + boost::archive::binary_iarchive in_archive(in_archive_stream); + in_archive >> boost::serialization::make_nvp(name.c_str(), output); +} + // Serialization to binary format with named structures template std::string serializeBinary(const T& input, const std::string& name="data") { std::ostringstream out_archive_stream; - boost::archive::binary_oarchive out_archive(out_archive_stream); - out_archive << boost::serialization::make_nvp(name.c_str(), input); + serializeBinary(input, out_archive_stream, name); return out_archive_stream.str(); } template void deserializeBinary(const std::string& serialized, T& output, const std::string& name="data") { std::istringstream in_archive_stream(serialized); - boost::archive::binary_iarchive in_archive(in_archive_stream); - in_archive >> boost::serialization::make_nvp(name.c_str(), output); + deserializeBinary(in_archive_stream, output, name); } template @@ -148,8 +170,7 @@ bool serializeToBinaryFile(const T& input, const std::string& filename, const st std::ofstream out_archive_stream(filename.c_str()); if (!out_archive_stream.is_open()) return false; - boost::archive::binary_oarchive out_archive(out_archive_stream); - out_archive << boost::serialization::make_nvp(name.c_str(), input); + serializeBinary(input, out_archive_stream, name); out_archive_stream.close(); return true; } @@ -159,8 +180,7 @@ bool deserializeFromBinaryFile(const std::string& filename, T& output, const std std::ifstream in_archive_stream(filename.c_str()); if (!in_archive_stream.is_open()) return false; - boost::archive::binary_iarchive in_archive(in_archive_stream); - in_archive >> boost::serialization::make_nvp(name.c_str(), output); + deserializeBinary(in_archive_stream, output, name); in_archive_stream.close(); return true; } From a4737d47066c0ee0e533bea393f4da14347e9abf Mon Sep 17 00:00:00 2001 From: Gerry Chen Date: Mon, 22 Jun 2020 21:18:43 -0400 Subject: [PATCH 087/869] formatting to Google style --- gtsam/base/serialization.h | 78 +++++++++++++++++++------------------- 1 file changed, 40 insertions(+), 38 deletions(-) diff --git a/gtsam/base/serialization.h b/gtsam/base/serialization.h index 031ee3a3e..aaf06275c 100644 --- a/gtsam/base/serialization.h +++ b/gtsam/base/serialization.h @@ -43,46 +43,44 @@ namespace gtsam { // Serialization directly to strings in compressed format -template -void serialize(const T& input, std::ostream & out_archive_stream) { +template +void serialize(const T& input, std::ostream& out_archive_stream) { boost::archive::text_oarchive out_archive(out_archive_stream); out_archive << input; } -template -void deserialize(std::istream & in_archive_stream, T& output) { +template +void deserialize(std::istream& in_archive_stream, T& output) { boost::archive::text_iarchive in_archive(in_archive_stream); in_archive >> output; } -template +template std::string serialize(const T& input) { std::ostringstream out_archive_stream; serialize(input, out_archive_stream); return out_archive_stream.str(); } -template +template void deserialize(const std::string& serialized, T& output) { std::istringstream in_archive_stream(serialized); deserialize(in_archive_stream, output); } -template +template bool serializeToFile(const T& input, const std::string& filename) { std::ofstream out_archive_stream(filename.c_str()); - if (!out_archive_stream.is_open()) - return false; + if (!out_archive_stream.is_open()) return false; serialize(input, out_archive_stream); out_archive_stream.close(); return true; } -template +template bool deserializeFromFile(const std::string& filename, T& output) { std::ifstream in_archive_stream(filename.c_str()); - if (!in_archive_stream.is_open()) - return false; + if (!in_archive_stream.is_open()) return false; deserialize(in_archive_stream, output); in_archive_stream.close(); return true; @@ -103,34 +101,36 @@ void deserializeXML(std::istream& in_archive_stream, T& output, in_archive >> boost::serialization::make_nvp(name.c_str(), output); } -template -std::string serializeXML(const T& input, const std::string& name="data") { +template +std::string serializeXML(const T& input, + const std::string& name = "data") { std::ostringstream out_archive_stream; serializeXML(input, out_archive_stream, name); return out_archive_stream.str(); } -template -void deserializeXML(const std::string& serialized, T& output, const std::string& name="data") { +template +void deserializeXML(const std::string& serialized, T& output, + const std::string& name = "data") { std::istringstream in_archive_stream(serialized); deserializeXML(in_archive_stream, output, name); } -template -bool serializeToXMLFile(const T& input, const std::string& filename, const std::string& name="data") { +template +bool serializeToXMLFile(const T& input, const std::string& filename, + const std::string& name = "data") { std::ofstream out_archive_stream(filename.c_str()); - if (!out_archive_stream.is_open()) - return false; + if (!out_archive_stream.is_open()) return false; serializeXML(input, out_archive_stream, name); out_archive_stream.close(); return true; } -template -bool deserializeFromXMLFile(const std::string& filename, T& output, const std::string& name="data") { +template +bool deserializeFromXMLFile(const std::string& filename, T& output, + const std::string& name = "data") { std::ifstream in_archive_stream(filename.c_str()); - if (!in_archive_stream.is_open()) - return false; + if (!in_archive_stream.is_open()) return false; deserializeXML(in_archive_stream, output, name); in_archive_stream.close(); return true; @@ -139,7 +139,7 @@ bool deserializeFromXMLFile(const std::string& filename, T& output, const std::s // Serialization to binary format with named structures template void serializeBinary(const T& input, std::ostream& out_archive_stream, - const std::string& name = "data") { + const std::string& name = "data") { boost::archive::binary_oarchive out_archive(out_archive_stream); out_archive << boost::serialization::make_nvp(name.c_str(), input); } @@ -152,37 +152,39 @@ void deserializeBinary(std::istream& in_archive_stream, T& output, } // Serialization to binary format with named structures -template -std::string serializeBinary(const T& input, const std::string& name="data") { +template +std::string serializeBinary(const T& input, + const std::string& name = "data") { std::ostringstream out_archive_stream; serializeBinary(input, out_archive_stream, name); return out_archive_stream.str(); } -template -void deserializeBinary(const std::string& serialized, T& output, const std::string& name="data") { +template +void deserializeBinary(const std::string& serialized, T& output, + const std::string& name = "data") { std::istringstream in_archive_stream(serialized); deserializeBinary(in_archive_stream, output, name); } -template -bool serializeToBinaryFile(const T& input, const std::string& filename, const std::string& name="data") { +template +bool serializeToBinaryFile(const T& input, const std::string& filename, + const std::string& name = "data") { std::ofstream out_archive_stream(filename.c_str()); - if (!out_archive_stream.is_open()) - return false; + if (!out_archive_stream.is_open()) return false; serializeBinary(input, out_archive_stream, name); out_archive_stream.close(); return true; } -template -bool deserializeFromBinaryFile(const std::string& filename, T& output, const std::string& name="data") { +template +bool deserializeFromBinaryFile(const std::string& filename, T& output, + const std::string& name = "data") { std::ifstream in_archive_stream(filename.c_str()); - if (!in_archive_stream.is_open()) - return false; + if (!in_archive_stream.is_open()) return false; deserializeBinary(in_archive_stream, output, name); in_archive_stream.close(); return true; } -} // \namespace gtsam +} // namespace gtsam From ca46ebfda81d8b54b1098cce83a41f0c664ee8b8 Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Mon, 22 Jun 2020 20:20:50 -0500 Subject: [PATCH 088/869] added comments and removed unnecessary code --- cmake/GtsamCythonWrap.cmake | 8 ++++---- cython/CMakeLists.txt | 3 --- cython/scripts/install.sh | 10 +++++++++- 3 files changed, 13 insertions(+), 8 deletions(-) diff --git a/cmake/GtsamCythonWrap.cmake b/cmake/GtsamCythonWrap.cmake index 361038ce0..4cd061852 100644 --- a/cmake/GtsamCythonWrap.cmake +++ b/cmake/GtsamCythonWrap.cmake @@ -280,16 +280,16 @@ function(install_cython_files source_files dest_directory) endfunction() function(install_python_package install_path) -#TODO this will only work for Linux. Need to make it work on macOS and Windows as well -#TODO Running `sudo make install` makes this run in admin space causing Python 2.7 to be picked up. - # # go to cython directory and run setup.py - # install(CODE "execute_process(COMMAND sh \"-c\" \"cd ${package_path} && python setup.py install\")") + # Select the correct install script based on the OS if(CMAKE_SYSTEM_NAME STREQUAL "Windows") set(PYTHON_INSTALL_SCRIPT "install.bat") elseif(CMAKE_SYSTEM_NAME STREQUAL "Linux" OR CMAKE_SYSTEM_NAME STREQUAL "Darwin") set(PYTHON_INSTALL_SCRIPT "install.sh") endif() + # Configure the variables in the script configure_file(${PROJECT_SOURCE_DIR}/cython/scripts/${PYTHON_INSTALL_SCRIPT} ${PROJECT_BINARY_DIR}/cython/scripts/${PYTHON_INSTALL_SCRIPT}) + + # Add the new make target command add_custom_target(python-install "${PROJECT_BINARY_DIR}/cython/scripts/${PYTHON_INSTALL_SCRIPT}") endfunction() diff --git a/cython/CMakeLists.txt b/cython/CMakeLists.txt index 638bdfb2d..96503b82f 100644 --- a/cython/CMakeLists.txt +++ b/cython/CMakeLists.txt @@ -45,9 +45,6 @@ if (GTSAM_INSTALL_CYTHON_TOOLBOX) install_cython_scripts("${PROJECT_SOURCE_DIR}/cython/gtsam" "${GTSAM_CYTHON_INSTALL_PATH}" "*.py") install_cython_scripts("${PROJECT_SOURCE_DIR}/cython/gtsam_unstable" "${GTSAM_CYTHON_INSTALL_PATH}" "*.py") - # file(GLOB GTSAM_PYTHON_INSTALL_SCRIPTS "scripts/*") - # file(COPY ${GTSAM_PYTHON_INSTALL_SCRIPTS} DESTINATION ${PROJECT_BINARY_DIR}/cython/scripts) - install_python_package("${GTSAM_CYTHON_INSTALL_PATH}") endif () diff --git a/cython/scripts/install.sh b/cython/scripts/install.sh index 04759ca5e..8e409803d 100755 --- a/cython/scripts/install.sh +++ b/cython/scripts/install.sh @@ -1,15 +1,22 @@ #!/bin/sh + +# This script runs the installation flow for python wrapped GTSAM. +# It does so by first setting the correct ownership permissions on the package directory, +# and then running `python setup.py install` to install the wrapped package. + echo "Installing GTSAM Python Wrapper" +# Set the package path PACKAGE_PATH=${GTSAM_CYTHON_INSTALL_PATH}${GTSAM_BUILD_TAG} +# Check if package directory exists. If not, print warning and exit. if [ ! -d "$PACKAGE_PATH" ] then echo "Directory $PACKAGE_PATH DOES NOT exist. Please run 'make install' first."; exit 1; fi -# set cython directory permissions to user so we don't get permission denied +# Set cython directory permissions to user so we don't get permission denied if [ "$(whoami)" != "root" ] then sudo chown -R $(logname) ${GTSAM_CYTHON_INSTALL_PATH} @@ -17,5 +24,6 @@ else chown -R $(logname) ${GTSAM_CYTHON_INSTALL_PATH} fi +# Run setup.py install with full paths echo "Running setup.py in $PACKAGE_PATH" ${PYTHON_EXECUTABLE} $PACKAGE_PATH/setup.py install From 82db82bbf5d46bb64dc50ba52507b39ee7f061ed Mon Sep 17 00:00:00 2001 From: Gerry Chen Date: Mon, 22 Jun 2020 23:08:39 -0400 Subject: [PATCH 089/869] fixed unit test failure on `testSerializationBase` object `output` was getting reused, but should be re-loaded into a "blank" object each time. --- gtsam/base/serializationTestHelpers.h | 46 ++++++++++++--------------- 1 file changed, 20 insertions(+), 26 deletions(-) diff --git a/gtsam/base/serializationTestHelpers.h b/gtsam/base/serializationTestHelpers.h index 602fd68f6..bac166e5b 100644 --- a/gtsam/base/serializationTestHelpers.h +++ b/gtsam/base/serializationTestHelpers.h @@ -44,8 +44,8 @@ T create() { // Creates or empties a folder in the build folder and returns the relative path boost::filesystem::path resetFilesystem( boost::filesystem::path folder = "actual") { - boost::filesystem::remove_all(folder); - boost::filesystem::create_directory(folder); + // boost::filesystem::remove_all(folder); + // boost::filesystem::create_directory(folder); return folder; } @@ -71,11 +71,10 @@ void roundtripFile(const T& input, T& output) { // This version requires equality operator template bool equality(const T& input = T()) { - T output = create(); + T output = create(), outputf = create(); roundtrip(input,output); - if (input != output) return false; - roundtripFile(input,output); - return input==output; + roundtripFile(input,outputf); + return (input==output) && (input==outputf); } // This version requires Testable @@ -89,11 +88,10 @@ bool equalsObj(const T& input = T()) { // De-referenced version for pointers, requires equals method template bool equalsDereferenced(const T& input) { - T output = create(); + T output = create(), outputf = create(); roundtrip(input,output); - if (!input->equals(*output)) return false; - roundtripFile(input,output); - return input->equals(*output); + roundtripFile(input,outputf); + return (input->equals(*output)) && (input->equals(*outputf)); } // Templated round-trip serialization using XML @@ -122,11 +120,10 @@ void roundtripXMLFile(const T& input, T& output) { // This version requires equality operator template bool equalityXML(const T& input = T()) { - T output = create(); + T output = create(), outputf = create(); roundtripXML(input,output); - if (input != output) return false; - roundtripXMLFile(input,output); - return input==output; + roundtripXMLFile(input,outputf); + return (input==output) && (input==outputf); } // This version requires Testable @@ -140,11 +137,10 @@ bool equalsXML(const T& input = T()) { // This version is for pointers, requires equals method template bool equalsDereferencedXML(const T& input = T()) { - T output = create(); + T output = create(), outputf = create(); roundtripXML(input,output); - if (!input->equals(*output)) return false; - roundtripXMLFile(input, output); - return input->equals(*output); + roundtripXMLFile(input, outputf); + return (input->equals(*output)) && (input->equals(*outputf)); } // Templated round-trip serialization using XML @@ -171,11 +167,10 @@ void roundtripBinaryFile(const T& input, T& output) { // This version requires equality operator template bool equalityBinary(const T& input = T()) { - T output = create(); + T output = create(), outputf = create(); roundtripBinary(input,output); - if (input != output) return false; - roundtripBinaryFile(input,output); - return input==output; + roundtripBinaryFile(input,outputf); + return (input==output) && (input==outputf); } // This version requires Testable @@ -189,11 +184,10 @@ bool equalsBinary(const T& input = T()) { // This version is for pointers, requires equals method template bool equalsDereferencedBinary(const T& input = T()) { - T output = create(); + T output = create(), outputf = create(); roundtripBinary(input,output); - if (!input->equals(*output)) return false; - roundtripBinaryFile(input,output); - return input->equals(*output); + roundtripBinaryFile(input,outputf); + return (input->equals(*output)) && (input->equals(*outputf)); } } // \namespace serializationTestHelpers From a0a3b8f459df37349a7b4af7d6b52016142204cb Mon Sep 17 00:00:00 2001 From: Gerry Chen Date: Tue, 23 Jun 2020 09:52:29 -0400 Subject: [PATCH 090/869] reset filesystem - forgot to uncomment these after debugging --- gtsam/base/serializationTestHelpers.h | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/gtsam/base/serializationTestHelpers.h b/gtsam/base/serializationTestHelpers.h index bac166e5b..5d67b2687 100644 --- a/gtsam/base/serializationTestHelpers.h +++ b/gtsam/base/serializationTestHelpers.h @@ -44,8 +44,8 @@ T create() { // Creates or empties a folder in the build folder and returns the relative path boost::filesystem::path resetFilesystem( boost::filesystem::path folder = "actual") { - // boost::filesystem::remove_all(folder); - // boost::filesystem::create_directory(folder); + boost::filesystem::remove_all(folder); + boost::filesystem::create_directory(folder); return folder; } From 3ea9ff012005b1205b8c20f5ea2b676d4054ce76 Mon Sep 17 00:00:00 2001 From: akrishnan86 Date: Tue, 23 Jun 2020 07:58:38 -0700 Subject: [PATCH 091/869] optional initialization for LMParams --- gtsam/sfm/TranslationRecovery.h | 5 +++-- 1 file changed, 3 insertions(+), 2 deletions(-) diff --git a/gtsam/sfm/TranslationRecovery.h b/gtsam/sfm/TranslationRecovery.h index 5eea251cf..634825d29 100644 --- a/gtsam/sfm/TranslationRecovery.h +++ b/gtsam/sfm/TranslationRecovery.h @@ -61,8 +61,9 @@ class TranslationRecovery { * @param relativeTranslations the relative translations, in world coordinate * frames, indexed in a map by a pair of Pose keys. */ - TranslationRecovery(const TranslationEdges& relativeTranslations) - : relativeTranslations_(relativeTranslations) { + TranslationRecovery(const TranslationEdges& relativeTranslations, + const LevenbergMarquardtParams& lmParams = LevenbergMarquardtParams()) + : relativeTranslations_(relativeTranslations), params_(lmParams) { params_.setVerbosityLM("Summary"); } From 9daeb39267f80bef157c0d11e60f371e57a179bb Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Tue, 23 Jun 2020 16:08:44 -0500 Subject: [PATCH 092/869] Set minimum supported numpy version to 1.11.0 (#366) * add deadsnakes ppa to install python3.6 on Ubuntu Xenial * updated travis distro to Ubuntu 18.04 bionic * Revert "updated travis distro to Ubuntu 18.04 bionic" This reverts commit 323264a924e8554da49c27a374e9a6278c5a659e. * restrict numpy version to be less than 1.19.0 * use ubuntu packaged numpy as baseline version to test against * downgrade minimum required version of numpy to version supported by Ubuntu Xenial * undo explicit pip install --- .travis.yml | 3 ++- cython/requirements.txt | 2 +- 2 files changed, 3 insertions(+), 2 deletions(-) diff --git a/.travis.yml b/.travis.yml index ca6a426ea..d8094ef4d 100644 --- a/.travis.yml +++ b/.travis.yml @@ -14,7 +14,8 @@ addons: - clang-9 - build-essential pkg-config - cmake - - libpython-dev python-numpy + - python3-dev libpython-dev + - python3-numpy - libboost-all-dev # before_install: diff --git a/cython/requirements.txt b/cython/requirements.txt index cd77b097d..8d3c7aeb4 100644 --- a/cython/requirements.txt +++ b/cython/requirements.txt @@ -1,3 +1,3 @@ Cython>=0.25.2 backports_abc>=0.5 -numpy>=1.12.0 +numpy>=1.11.0 From b41809203f636878dbbc0aad718ac6f7343e82e6 Mon Sep 17 00:00:00 2001 From: Fan Jiang Date: Tue, 23 Jun 2020 18:37:12 -0400 Subject: [PATCH 093/869] Revise comments --- gtsam/base/types.h | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/gtsam/base/types.h b/gtsam/base/types.h index 3abbdfe81..93c475c40 100644 --- a/gtsam/base/types.h +++ b/gtsam/base/types.h @@ -235,7 +235,8 @@ namespace gtsam { /** * A trait to mark classes that need special alignment. - * Please refer to https://github.com/PointCloudLibrary/pcl/pull/3163 + * This is required to make boost::make_shared and etc respect alignment, which is essential for the Python + * wrappers to work properly. */ #if __cplusplus < 201703L template using void_t = void; From de7332fceac3224d4ea693a8f1631300b3345c74 Mon Sep 17 00:00:00 2001 From: Gerry Chen Date: Wed, 24 Jun 2020 02:39:44 -0400 Subject: [PATCH 094/869] remove file roundtrip test for pointers --- gtsam/base/serializationTestHelpers.h | 15 ++++++--------- 1 file changed, 6 insertions(+), 9 deletions(-) diff --git a/gtsam/base/serializationTestHelpers.h b/gtsam/base/serializationTestHelpers.h index 5d67b2687..78f9d6d10 100644 --- a/gtsam/base/serializationTestHelpers.h +++ b/gtsam/base/serializationTestHelpers.h @@ -88,10 +88,9 @@ bool equalsObj(const T& input = T()) { // De-referenced version for pointers, requires equals method template bool equalsDereferenced(const T& input) { - T output = create(), outputf = create(); + T output = create(); roundtrip(input,output); - roundtripFile(input,outputf); - return (input->equals(*output)) && (input->equals(*outputf)); + return input->equals(*output); } // Templated round-trip serialization using XML @@ -137,10 +136,9 @@ bool equalsXML(const T& input = T()) { // This version is for pointers, requires equals method template bool equalsDereferencedXML(const T& input = T()) { - T output = create(), outputf = create(); + T output = create(); roundtripXML(input,output); - roundtripXMLFile(input, outputf); - return (input->equals(*output)) && (input->equals(*outputf)); + return input->equals(*output); } // Templated round-trip serialization using XML @@ -184,10 +182,9 @@ bool equalsBinary(const T& input = T()) { // This version is for pointers, requires equals method template bool equalsDereferencedBinary(const T& input = T()) { - T output = create(), outputf = create(); + T output = create(); roundtripBinary(input,output); - roundtripBinaryFile(input,outputf); - return (input->equals(*output)) && (input->equals(*outputf)); + return input->equals(*output); } } // \namespace serializationTestHelpers From 6972a5c9a70e5ff8eaa3f8b5b0f9392c2829a195 Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Wed, 24 Jun 2020 11:06:01 -0500 Subject: [PATCH 095/869] updated comments in shell script --- cython/scripts/install.sh | 7 ++++--- 1 file changed, 4 insertions(+), 3 deletions(-) diff --git a/cython/scripts/install.sh b/cython/scripts/install.sh index 8e409803d..fdf86f130 100755 --- a/cython/scripts/install.sh +++ b/cython/scripts/install.sh @@ -11,12 +11,13 @@ PACKAGE_PATH=${GTSAM_CYTHON_INSTALL_PATH}${GTSAM_BUILD_TAG} # Check if package directory exists. If not, print warning and exit. if [ ! -d "$PACKAGE_PATH" ] -then +then echo "Directory $PACKAGE_PATH DOES NOT exist. Please run 'make install' first."; exit 1; fi -# Set cython directory permissions to user so we don't get permission denied +# Set cython directory permissions to user so we don't get permission denied. +# This also works inside Docker containers. if [ "$(whoami)" != "root" ] then sudo chown -R $(logname) ${GTSAM_CYTHON_INSTALL_PATH} @@ -24,6 +25,6 @@ else chown -R $(logname) ${GTSAM_CYTHON_INSTALL_PATH} fi -# Run setup.py install with full paths +# Run setup.py install with full paths. echo "Running setup.py in $PACKAGE_PATH" ${PYTHON_EXECUTABLE} $PACKAGE_PATH/setup.py install From 530016edf00e9a56cbdb4de27ce612580337a66a Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Wed, 24 Jun 2020 11:06:35 -0500 Subject: [PATCH 096/869] added Windows batch script to install python wrapped package --- cython/scripts/install.bat | 18 ++++++++++++++++++ 1 file changed, 18 insertions(+) diff --git a/cython/scripts/install.bat b/cython/scripts/install.bat index e69de29bb..4dbd2051f 100755 --- a/cython/scripts/install.bat +++ b/cython/scripts/install.bat @@ -0,0 +1,18 @@ +:: This script runs the installation flow for python wrapped GTSAM. +:: It does so by running `python setup.py install` to install the wrapped package. + +echo "Installing GTSAM Python Wrapper" + +:: Set the package path +PACKAGE_PATH=${GTSAM_CYTHON_INSTALL_PATH}${GTSAM_BUILD_TAG} + +:: Check if package directory exists. If not, print warning and exit. +if [ ! -d "$PACKAGE_PATH" ] +then + echo "Directory $PACKAGE_PATH DOES NOT exist. Please run 'make install' first."; + exit 1; +fi + +:: Run setup.py install with full paths. +echo "Running setup.py in $PACKAGE_PATH" +${PYTHON_EXECUTABLE} $PACKAGE_PATH/setup.py install From 7d7475b881ffc9f21ce2f49c3e4d3890e9e6d21f Mon Sep 17 00:00:00 2001 From: Fan Jiang Date: Wed, 24 Jun 2020 14:15:46 -0400 Subject: [PATCH 097/869] Style fixes as commented by @dellaert --- gtsam/base/make_shared.h | 22 +++++++++++++--------- gtsam/base/types.h | 19 ++++++++++--------- 2 files changed, 23 insertions(+), 18 deletions(-) diff --git a/gtsam/base/make_shared.h b/gtsam/base/make_shared.h index 966dd516d..c7d98cdee 100644 --- a/gtsam/base/make_shared.h +++ b/gtsam/base/make_shared.h @@ -25,27 +25,31 @@ #include -#if __cplusplus <= 201103L namespace gtsam { template using enable_if_t = typename std::enable_if::type; } -#endif namespace gtsam { - /// Add our own `make_shared` as a layer of wrapping on `boost::make_shared` + /** Add our own `make_shared` as a layer of wrapping on `boost::make_shared` + * This solves the problem with the stock `make_shared` that custom alignment is not respected, causing SEGFAULTs + * at runtime, which is notoriously hard to debug. + * + * @tparam T The type of object being constructed + * @tparam Args Type of the arguments of the constructor + * @param args Arguments of the constructor + * @return The object created as a boost::shared_ptr + */ template - gtsam::enable_if_t::value, boost::shared_ptr> make_shared(Args&&... args) - { - return boost::allocate_shared(Eigen::aligned_allocator(), std::forward (args)...); + gtsam::enable_if_t::value, boost::shared_ptr> make_shared(Args &&... args) { + return boost::allocate_shared(Eigen::aligned_allocator(), std::forward(args)...); } /// Fall back to the boost version if no need for alignment template - gtsam::enable_if_t::value, boost::shared_ptr> make_shared(Args&&... args) - { - return boost::make_shared(std::forward (args)...); + gtsam::enable_if_t::value, boost::shared_ptr> make_shared(Args &&... args) { + return boost::make_shared(std::forward(args)...); } } diff --git a/gtsam/base/types.h b/gtsam/base/types.h index 93c475c40..a4b2fb6ea 100644 --- a/gtsam/base/types.h +++ b/gtsam/base/types.h @@ -233,27 +233,28 @@ namespace std { namespace gtsam { + /// Convenience void_t as we assume C++11, it will not conflict the std one in C++17 as this is in `gtsam::` + template using void_t = void; + /** - * A trait to mark classes that need special alignment. + * A SFINAE trait to mark classes that need special alignment. * This is required to make boost::make_shared and etc respect alignment, which is essential for the Python * wrappers to work properly. */ -#if __cplusplus < 201703L - template using void_t = void; -#endif - template> - struct has_custom_allocator : std::false_type { + struct needs_eigen_aligned_allocator : std::false_type { }; template - struct has_custom_allocator> : std::true_type { + struct needs_eigen_aligned_allocator> : std::true_type { }; } /** - * This is necessary for the Cython wrapper to work properly, and possibly reduce future misalignment problems. + * This marks a GTSAM object to require alignment. With this macro an object will automatically be allocated in aligned + * memory when one uses `gtsam::make_shared`. It reduces future misalignment problems that is hard to debug. + * See https://eigen.tuxfamily.org/dox/group__DenseMatrixManipulation__Alignement.html for details */ #define GTSAM_MAKE_ALIGNED_OPERATOR_NEW \ EIGEN_MAKE_ALIGNED_OPERATOR_NEW \ - using _custom_allocator_type_trait = void; \ No newline at end of file + using _eigen_aligned_allocator_trait = void; From 6d75e992e896f54a1bd3956ff5f8cd1dddf5e814 Mon Sep 17 00:00:00 2001 From: Gerry Chen Date: Wed, 24 Jun 2020 14:16:00 -0400 Subject: [PATCH 098/869] serialization docstrings --- gtsam/base/serialization.h | 37 ++++++++++++++++++++++++--- gtsam/base/serializationTestHelpers.h | 17 +----------- 2 files changed, 34 insertions(+), 20 deletions(-) diff --git a/gtsam/base/serialization.h b/gtsam/base/serialization.h index aaf06275c..1a319ab17 100644 --- a/gtsam/base/serialization.h +++ b/gtsam/base/serialization.h @@ -42,19 +42,25 @@ namespace gtsam { -// Serialization directly to strings in compressed format +/** @name Standard serialization + * Serialization in default compressed format + */ +///@{ +/// serializes to a stream template void serialize(const T& input, std::ostream& out_archive_stream) { boost::archive::text_oarchive out_archive(out_archive_stream); out_archive << input; } +/// deserializes from a stream template void deserialize(std::istream& in_archive_stream, T& output) { boost::archive::text_iarchive in_archive(in_archive_stream); in_archive >> output; } +/// serializes to a string template std::string serialize(const T& input) { std::ostringstream out_archive_stream; @@ -62,12 +68,14 @@ std::string serialize(const T& input) { return out_archive_stream.str(); } +/// deserializes from a string template void deserialize(const std::string& serialized, T& output) { std::istringstream in_archive_stream(serialized); deserialize(in_archive_stream, output); } +/// serializes to a file template bool serializeToFile(const T& input, const std::string& filename) { std::ofstream out_archive_stream(filename.c_str()); @@ -77,6 +85,7 @@ bool serializeToFile(const T& input, const std::string& filename) { return true; } +/// deserializes from a file template bool deserializeFromFile(const std::string& filename, T& output) { std::ifstream in_archive_stream(filename.c_str()); @@ -85,8 +94,13 @@ bool deserializeFromFile(const std::string& filename, T& output) { in_archive_stream.close(); return true; } +///@} -// Serialization to XML format with named structures +/** @name XML Serialization + * Serialization to XML format with named structures + */ +///@{ +/// serializes to a stream in XML template void serializeXML(const T& input, std::ostream& out_archive_stream, const std::string& name = "data") { @@ -94,6 +108,7 @@ void serializeXML(const T& input, std::ostream& out_archive_stream, out_archive << boost::serialization::make_nvp(name.c_str(), input); } +/// deserializes from a stream in XML template void deserializeXML(std::istream& in_archive_stream, T& output, const std::string& name = "data") { @@ -101,6 +116,7 @@ void deserializeXML(std::istream& in_archive_stream, T& output, in_archive >> boost::serialization::make_nvp(name.c_str(), output); } +/// serializes to a string in XML template std::string serializeXML(const T& input, const std::string& name = "data") { @@ -109,6 +125,7 @@ std::string serializeXML(const T& input, return out_archive_stream.str(); } +/// deserializes from a string in XML template void deserializeXML(const std::string& serialized, T& output, const std::string& name = "data") { @@ -116,6 +133,7 @@ void deserializeXML(const std::string& serialized, T& output, deserializeXML(in_archive_stream, output, name); } +/// serializes to an XML file template bool serializeToXMLFile(const T& input, const std::string& filename, const std::string& name = "data") { @@ -126,6 +144,7 @@ bool serializeToXMLFile(const T& input, const std::string& filename, return true; } +/// deserializes from an XML file template bool deserializeFromXMLFile(const std::string& filename, T& output, const std::string& name = "data") { @@ -135,8 +154,13 @@ bool deserializeFromXMLFile(const std::string& filename, T& output, in_archive_stream.close(); return true; } +///@} -// Serialization to binary format with named structures +/** @name Binary Serialization + * Serialization to binary format with named structures + */ +///@{ +/// serializes to a stream in binary template void serializeBinary(const T& input, std::ostream& out_archive_stream, const std::string& name = "data") { @@ -144,6 +168,7 @@ void serializeBinary(const T& input, std::ostream& out_archive_stream, out_archive << boost::serialization::make_nvp(name.c_str(), input); } +/// deserializes from a stream in binary template void deserializeBinary(std::istream& in_archive_stream, T& output, const std::string& name = "data") { @@ -151,7 +176,7 @@ void deserializeBinary(std::istream& in_archive_stream, T& output, in_archive >> boost::serialization::make_nvp(name.c_str(), output); } -// Serialization to binary format with named structures +/// serializes to a string in binary template std::string serializeBinary(const T& input, const std::string& name = "data") { @@ -160,6 +185,7 @@ std::string serializeBinary(const T& input, return out_archive_stream.str(); } +/// deserializes from a string in binary template void deserializeBinary(const std::string& serialized, T& output, const std::string& name = "data") { @@ -167,6 +193,7 @@ void deserializeBinary(const std::string& serialized, T& output, deserializeBinary(in_archive_stream, output, name); } +/// serializes to a binary file template bool serializeToBinaryFile(const T& input, const std::string& filename, const std::string& name = "data") { @@ -177,6 +204,7 @@ bool serializeToBinaryFile(const T& input, const std::string& filename, return true; } +/// deserializes from a binary file template bool deserializeFromBinaryFile(const std::string& filename, T& output, const std::string& name = "data") { @@ -186,5 +214,6 @@ bool deserializeFromBinaryFile(const std::string& filename, T& output, in_archive_stream.close(); return true; } +///@} } // namespace gtsam diff --git a/gtsam/base/serializationTestHelpers.h b/gtsam/base/serializationTestHelpers.h index 78f9d6d10..5994a5e51 100644 --- a/gtsam/base/serializationTestHelpers.h +++ b/gtsam/base/serializationTestHelpers.h @@ -52,10 +52,8 @@ boost::filesystem::path resetFilesystem( // Templated round-trip serialization template void roundtrip(const T& input, T& output) { - // Serialize std::string serialized = serialize(input); if (verbose) std::cout << serialized << std::endl << std::endl; - deserialize(serialized, output); } @@ -63,12 +61,11 @@ void roundtrip(const T& input, T& output) { template void roundtripFile(const T& input, T& output) { boost::filesystem::path path = resetFilesystem()/"graph.dat"; - serializeToFile(input, path.string()); deserializeFromFile(path.string(), output); } -// This version requires equality operator +// This version requires equality operator and uses string and file round-trips template bool equality(const T& input = T()) { T output = create(), outputf = create(); @@ -96,11 +93,8 @@ bool equalsDereferenced(const T& input) { // Templated round-trip serialization using XML template void roundtripXML(const T& input, T& output) { - // Serialize std::string serialized = serializeXML(input); if (verbose) std::cout << serialized << std::endl << std::endl; - - // De-serialize deserializeXML(serialized, output); } @@ -108,11 +102,7 @@ void roundtripXML(const T& input, T& output) { template void roundtripXMLFile(const T& input, T& output) { boost::filesystem::path path = resetFilesystem()/"graph.xml"; - - // Serialize serializeToXMLFile(input, path.string()); - - // De-serialize deserializeFromXMLFile(path.string(), output); } @@ -144,11 +134,8 @@ bool equalsDereferencedXML(const T& input = T()) { // Templated round-trip serialization using XML template void roundtripBinary(const T& input, T& output) { - // Serialize std::string serialized = serializeBinary(input); if (verbose) std::cout << serialized << std::endl << std::endl; - - // De-serialize deserializeBinary(serialized, output); } @@ -156,9 +143,7 @@ void roundtripBinary(const T& input, T& output) { template void roundtripBinaryFile(const T& input, T& output) { boost::filesystem::path path = resetFilesystem()/"graph.bin"; - // Serialize serializeToBinaryFile(input, path.string()); - // De-serialize deserializeFromBinaryFile(path.string(), output); } From b37be7d640567be9b78c699d158c88035d4f789e Mon Sep 17 00:00:00 2001 From: Gerry Chen Date: Wed, 24 Jun 2020 14:33:08 -0400 Subject: [PATCH 099/869] rename serialization functions with less ambiguous names According to Varun's suggestion. Note: string functions should be automatically inlined by compiler to avoid passing big strings. --- gtsam/base/serialization.h | 88 +++++++++++++++++++++++++++----------- 1 file changed, 64 insertions(+), 24 deletions(-) diff --git a/gtsam/base/serialization.h b/gtsam/base/serialization.h index 1a319ab17..f589ecc5e 100644 --- a/gtsam/base/serialization.h +++ b/gtsam/base/serialization.h @@ -48,31 +48,31 @@ namespace gtsam { ///@{ /// serializes to a stream template -void serialize(const T& input, std::ostream& out_archive_stream) { +void serializeToStream(const T& input, std::ostream& out_archive_stream) { boost::archive::text_oarchive out_archive(out_archive_stream); out_archive << input; } /// deserializes from a stream template -void deserialize(std::istream& in_archive_stream, T& output) { +void deserializeFromStream(std::istream& in_archive_stream, T& output) { boost::archive::text_iarchive in_archive(in_archive_stream); in_archive >> output; } /// serializes to a string template -std::string serialize(const T& input) { +std::string serializeToString(const T& input) { std::ostringstream out_archive_stream; - serialize(input, out_archive_stream); + serializeToStream(input, out_archive_stream); return out_archive_stream.str(); } /// deserializes from a string template -void deserialize(const std::string& serialized, T& output) { +void deserializeFromString(const std::string& serialized, T& output) { std::istringstream in_archive_stream(serialized); - deserialize(in_archive_stream, output); + deserializeFromStream(in_archive_stream, output); } /// serializes to a file @@ -80,7 +80,7 @@ template bool serializeToFile(const T& input, const std::string& filename) { std::ofstream out_archive_stream(filename.c_str()); if (!out_archive_stream.is_open()) return false; - serialize(input, out_archive_stream); + serializeToStream(input, out_archive_stream); out_archive_stream.close(); return true; } @@ -90,10 +90,22 @@ template bool deserializeFromFile(const std::string& filename, T& output) { std::ifstream in_archive_stream(filename.c_str()); if (!in_archive_stream.is_open()) return false; - deserialize(in_archive_stream, output); + deserializeFromStream(in_archive_stream, output); in_archive_stream.close(); return true; } + +/// serializes to a string +template +std::string serialize(const T& input) { + return serializeToString(input); +} + +/// deserializes from a string +template +void deserialize(const std::string& serialized, T& output) { + deserializeFromString(serialized, output); +} ///@} /** @name XML Serialization @@ -102,7 +114,7 @@ bool deserializeFromFile(const std::string& filename, T& output) { ///@{ /// serializes to a stream in XML template -void serializeXML(const T& input, std::ostream& out_archive_stream, +void serializeToXMLStream(const T& input, std::ostream& out_archive_stream, const std::string& name = "data") { boost::archive::xml_oarchive out_archive(out_archive_stream); out_archive << boost::serialization::make_nvp(name.c_str(), input); @@ -110,7 +122,7 @@ void serializeXML(const T& input, std::ostream& out_archive_stream, /// deserializes from a stream in XML template -void deserializeXML(std::istream& in_archive_stream, T& output, +void deserializeFromXMLStream(std::istream& in_archive_stream, T& output, const std::string& name = "data") { boost::archive::xml_iarchive in_archive(in_archive_stream); in_archive >> boost::serialization::make_nvp(name.c_str(), output); @@ -118,19 +130,19 @@ void deserializeXML(std::istream& in_archive_stream, T& output, /// serializes to a string in XML template -std::string serializeXML(const T& input, +std::string serializeToXMLString(const T& input, const std::string& name = "data") { std::ostringstream out_archive_stream; - serializeXML(input, out_archive_stream, name); + serializeToXMLStream(input, out_archive_stream, name); return out_archive_stream.str(); } /// deserializes from a string in XML template -void deserializeXML(const std::string& serialized, T& output, +void deserializeFromXMLString(const std::string& serialized, T& output, const std::string& name = "data") { std::istringstream in_archive_stream(serialized); - deserializeXML(in_archive_stream, output, name); + deserializeFromXMLStream(in_archive_stream, output, name); } /// serializes to an XML file @@ -139,7 +151,7 @@ bool serializeToXMLFile(const T& input, const std::string& filename, const std::string& name = "data") { std::ofstream out_archive_stream(filename.c_str()); if (!out_archive_stream.is_open()) return false; - serializeXML(input, out_archive_stream, name); + serializeToXMLStream(input, out_archive_stream, name); out_archive_stream.close(); return true; } @@ -150,10 +162,24 @@ bool deserializeFromXMLFile(const std::string& filename, T& output, const std::string& name = "data") { std::ifstream in_archive_stream(filename.c_str()); if (!in_archive_stream.is_open()) return false; - deserializeXML(in_archive_stream, output, name); + deserializeFromXMLStream(in_archive_stream, output, name); in_archive_stream.close(); return true; } + +/// serializes to a string in XML +template +std::string serializeXML(const T& input, + const std::string& name = "data") { + return serializeToXMLString(input, name); +} + +/// deserializes from a string in XML +template +void deserializeXML(const std::string& serialized, T& output, + const std::string& name = "data") { + deserializeFromXMLString(serialized, output, name); +} ///@} /** @name Binary Serialization @@ -162,7 +188,7 @@ bool deserializeFromXMLFile(const std::string& filename, T& output, ///@{ /// serializes to a stream in binary template -void serializeBinary(const T& input, std::ostream& out_archive_stream, +void serializeToBinaryStream(const T& input, std::ostream& out_archive_stream, const std::string& name = "data") { boost::archive::binary_oarchive out_archive(out_archive_stream); out_archive << boost::serialization::make_nvp(name.c_str(), input); @@ -170,7 +196,7 @@ void serializeBinary(const T& input, std::ostream& out_archive_stream, /// deserializes from a stream in binary template -void deserializeBinary(std::istream& in_archive_stream, T& output, +void deserializeFromBinaryStream(std::istream& in_archive_stream, T& output, const std::string& name = "data") { boost::archive::binary_iarchive in_archive(in_archive_stream); in_archive >> boost::serialization::make_nvp(name.c_str(), output); @@ -178,19 +204,19 @@ void deserializeBinary(std::istream& in_archive_stream, T& output, /// serializes to a string in binary template -std::string serializeBinary(const T& input, +std::string serializeToBinaryString(const T& input, const std::string& name = "data") { std::ostringstream out_archive_stream; - serializeBinary(input, out_archive_stream, name); + serializeToBinaryStream(input, out_archive_stream, name); return out_archive_stream.str(); } /// deserializes from a string in binary template -void deserializeBinary(const std::string& serialized, T& output, +void deserializeFromBinaryString(const std::string& serialized, T& output, const std::string& name = "data") { std::istringstream in_archive_stream(serialized); - deserializeBinary(in_archive_stream, output, name); + deserializeFromBinaryStream(in_archive_stream, output, name); } /// serializes to a binary file @@ -199,7 +225,7 @@ bool serializeToBinaryFile(const T& input, const std::string& filename, const std::string& name = "data") { std::ofstream out_archive_stream(filename.c_str()); if (!out_archive_stream.is_open()) return false; - serializeBinary(input, out_archive_stream, name); + serializeToBinaryStream(input, out_archive_stream, name); out_archive_stream.close(); return true; } @@ -210,10 +236,24 @@ bool deserializeFromBinaryFile(const std::string& filename, T& output, const std::string& name = "data") { std::ifstream in_archive_stream(filename.c_str()); if (!in_archive_stream.is_open()) return false; - deserializeBinary(in_archive_stream, output, name); + deserializeFromBinaryStream(in_archive_stream, output, name); in_archive_stream.close(); return true; } + +/// serializes to a string in binary +template +std::string serializeBinary(const T& input, + const std::string& name = "data") { + return serializeToBinaryString(input, name); +} + +/// deserializes from a string in binary +template +void deserializeBinary(const std::string& serialized, T& output, + const std::string& name = "data") { + deserializeFromBinaryString(serialized, output, name); +} ///@} } // namespace gtsam From efde078b944e1865ea9e53e68726c48c5cf2d2e7 Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Wed, 24 Jun 2020 14:05:17 -0500 Subject: [PATCH 100/869] pure CMake script to install Python wrapper after compiling --- cmake/GtsamCythonWrap.cmake | 15 --------------- cython/CMakeLists.txt | 3 ++- cython/scripts/install.bat | 18 ------------------ cython/scripts/install.sh | 30 ------------------------------ 4 files changed, 2 insertions(+), 64 deletions(-) delete mode 100755 cython/scripts/install.bat delete mode 100755 cython/scripts/install.sh diff --git a/cmake/GtsamCythonWrap.cmake b/cmake/GtsamCythonWrap.cmake index 4cd061852..6331d1e95 100644 --- a/cmake/GtsamCythonWrap.cmake +++ b/cmake/GtsamCythonWrap.cmake @@ -278,18 +278,3 @@ function(install_cython_files source_files dest_directory) endif() endfunction() - -function(install_python_package install_path) - # Select the correct install script based on the OS - if(CMAKE_SYSTEM_NAME STREQUAL "Windows") - set(PYTHON_INSTALL_SCRIPT "install.bat") - elseif(CMAKE_SYSTEM_NAME STREQUAL "Linux" OR CMAKE_SYSTEM_NAME STREQUAL "Darwin") - set(PYTHON_INSTALL_SCRIPT "install.sh") - endif() - - # Configure the variables in the script - configure_file(${PROJECT_SOURCE_DIR}/cython/scripts/${PYTHON_INSTALL_SCRIPT} ${PROJECT_BINARY_DIR}/cython/scripts/${PYTHON_INSTALL_SCRIPT}) - - # Add the new make target command - add_custom_target(python-install "${PROJECT_BINARY_DIR}/cython/scripts/${PYTHON_INSTALL_SCRIPT}") -endfunction() diff --git a/cython/CMakeLists.txt b/cython/CMakeLists.txt index 96503b82f..bce9f2308 100644 --- a/cython/CMakeLists.txt +++ b/cython/CMakeLists.txt @@ -45,6 +45,7 @@ if (GTSAM_INSTALL_CYTHON_TOOLBOX) install_cython_scripts("${PROJECT_SOURCE_DIR}/cython/gtsam" "${GTSAM_CYTHON_INSTALL_PATH}" "*.py") install_cython_scripts("${PROJECT_SOURCE_DIR}/cython/gtsam_unstable" "${GTSAM_CYTHON_INSTALL_PATH}" "*.py") - install_python_package("${GTSAM_CYTHON_INSTALL_PATH}") + # Add the new make target command + add_custom_target(python-install COMMAND ${PYTHON_EXECUTABLE} ${GTSAM_CYTHON_INSTALL_PATH}${GTSAM_BUILD_TAG}/setup.py install) endif () diff --git a/cython/scripts/install.bat b/cython/scripts/install.bat deleted file mode 100755 index 4dbd2051f..000000000 --- a/cython/scripts/install.bat +++ /dev/null @@ -1,18 +0,0 @@ -:: This script runs the installation flow for python wrapped GTSAM. -:: It does so by running `python setup.py install` to install the wrapped package. - -echo "Installing GTSAM Python Wrapper" - -:: Set the package path -PACKAGE_PATH=${GTSAM_CYTHON_INSTALL_PATH}${GTSAM_BUILD_TAG} - -:: Check if package directory exists. If not, print warning and exit. -if [ ! -d "$PACKAGE_PATH" ] -then - echo "Directory $PACKAGE_PATH DOES NOT exist. Please run 'make install' first."; - exit 1; -fi - -:: Run setup.py install with full paths. -echo "Running setup.py in $PACKAGE_PATH" -${PYTHON_EXECUTABLE} $PACKAGE_PATH/setup.py install diff --git a/cython/scripts/install.sh b/cython/scripts/install.sh deleted file mode 100755 index fdf86f130..000000000 --- a/cython/scripts/install.sh +++ /dev/null @@ -1,30 +0,0 @@ -#!/bin/sh - -# This script runs the installation flow for python wrapped GTSAM. -# It does so by first setting the correct ownership permissions on the package directory, -# and then running `python setup.py install` to install the wrapped package. - -echo "Installing GTSAM Python Wrapper" - -# Set the package path -PACKAGE_PATH=${GTSAM_CYTHON_INSTALL_PATH}${GTSAM_BUILD_TAG} - -# Check if package directory exists. If not, print warning and exit. -if [ ! -d "$PACKAGE_PATH" ] -then - echo "Directory $PACKAGE_PATH DOES NOT exist. Please run 'make install' first."; - exit 1; -fi - -# Set cython directory permissions to user so we don't get permission denied. -# This also works inside Docker containers. -if [ "$(whoami)" != "root" ] -then - sudo chown -R $(logname) ${GTSAM_CYTHON_INSTALL_PATH} -else - chown -R $(logname) ${GTSAM_CYTHON_INSTALL_PATH} -fi - -# Run setup.py install with full paths. -echo "Running setup.py in $PACKAGE_PATH" -${PYTHON_EXECUTABLE} $PACKAGE_PATH/setup.py install From 9698b032537e9a74a6414ff46e09f9cdef196bab Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Wed, 24 Jun 2020 14:06:25 -0500 Subject: [PATCH 101/869] removed extra line --- cmake/GtsamCythonWrap.cmake | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/cmake/GtsamCythonWrap.cmake b/cmake/GtsamCythonWrap.cmake index 6331d1e95..b6c4c2856 100644 --- a/cmake/GtsamCythonWrap.cmake +++ b/cmake/GtsamCythonWrap.cmake @@ -277,4 +277,4 @@ function(install_cython_files source_files dest_directory) install(FILES "${source_files}" DESTINATION "${dest_directory}") endif() -endfunction() +endfunction() \ No newline at end of file From 5feaf6dd9da35b9a347dc5c0d006c72ab0a3f2d4 Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Wed, 24 Jun 2020 14:07:28 -0500 Subject: [PATCH 102/869] reset to previous version --- cmake/GtsamCythonWrap.cmake | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/cmake/GtsamCythonWrap.cmake b/cmake/GtsamCythonWrap.cmake index b6c4c2856..6331d1e95 100644 --- a/cmake/GtsamCythonWrap.cmake +++ b/cmake/GtsamCythonWrap.cmake @@ -277,4 +277,4 @@ function(install_cython_files source_files dest_directory) install(FILES "${source_files}" DESTINATION "${dest_directory}") endif() -endfunction() \ No newline at end of file +endfunction() From 6dbd7c243abc91489c010261bde27685c491acac Mon Sep 17 00:00:00 2001 From: Fan Jiang Date: Wed, 24 Jun 2020 16:25:46 -0400 Subject: [PATCH 103/869] Add comments --- gtsam/base/make_shared.h | 14 +++++++++++++- gtsam/base/types.h | 12 +++++++++++- 2 files changed, 24 insertions(+), 2 deletions(-) diff --git a/gtsam/base/make_shared.h b/gtsam/base/make_shared.h index c7d98cdee..5281eec6d 100644 --- a/gtsam/base/make_shared.h +++ b/gtsam/base/make_shared.h @@ -26,16 +26,28 @@ #include namespace gtsam { + /// An shorthand alias for accessing the ::type inside std::enable_if that can be used in a template directly template using enable_if_t = typename std::enable_if::type; } namespace gtsam { - /** Add our own `make_shared` as a layer of wrapping on `boost::make_shared` + /** + * Add our own `make_shared` as a layer of wrapping on `boost::make_shared` * This solves the problem with the stock `make_shared` that custom alignment is not respected, causing SEGFAULTs * at runtime, which is notoriously hard to debug. * + * Explanation + * =============== + * The template `needs_eigen_aligned_allocator::value` will evaluate to `std::true_type` if the type alias + * `_eigen_aligned_allocator_trait = void` is present in a class, which is automatically added by the + * `GTSAM_MAKE_ALIGNED_OPERATOR_NEW` macro. + * + * This function declaration will only be taken when the above condition is true, so if some object does not need to + * be aligned, `gtsam::make_shared` will fall back to the next definition, which is a simple wrapper for + * `boost::make_shared`. + * * @tparam T The type of object being constructed * @tparam Args Type of the arguments of the constructor * @param args Arguments of the constructor diff --git a/gtsam/base/types.h b/gtsam/base/types.h index a4b2fb6ea..b54cc2f2a 100644 --- a/gtsam/base/types.h +++ b/gtsam/base/types.h @@ -238,8 +238,18 @@ namespace gtsam { /** * A SFINAE trait to mark classes that need special alignment. + * * This is required to make boost::make_shared and etc respect alignment, which is essential for the Python * wrappers to work properly. + * + * Explanation + * ============= + * When a GTSAM type is not declared with the type alias `_eigen_aligned_allocator_trait = void`, the first template + * will be taken so `needs_eigen_aligned_allocator` will be resolved to `std::false_type`. + * + * Otherwise, it will resolve to the second template, which will be resolved to `std::true_type`. + * + * Please refer to `gtsam/base/make_shared.h` for an example. */ template> struct needs_eigen_aligned_allocator : std::false_type { @@ -253,7 +263,7 @@ namespace gtsam { /** * This marks a GTSAM object to require alignment. With this macro an object will automatically be allocated in aligned * memory when one uses `gtsam::make_shared`. It reduces future misalignment problems that is hard to debug. - * See https://eigen.tuxfamily.org/dox/group__DenseMatrixManipulation__Alignement.html for details + * See https://eigen.tuxfamily.org/dox/group__DenseMatrixManipulation__Alignement.html for detailed explanation. */ #define GTSAM_MAKE_ALIGNED_OPERATOR_NEW \ EIGEN_MAKE_ALIGNED_OPERATOR_NEW \ From fb21c553a05555ce4be3de305836d62fa1113bbe Mon Sep 17 00:00:00 2001 From: Fan Jiang Date: Wed, 24 Jun 2020 17:15:00 -0400 Subject: [PATCH 104/869] Switch to the new alignment marker type --- gtsam/base/GenericValue.h | 2 +- gtsam/base/Manifold.h | 2 +- gtsam/base/types.h | 9 +++++++++ gtsam/geometry/BearingRange.h | 2 +- gtsam/geometry/CameraSet.h | 2 +- gtsam/geometry/EssentialMatrix.h | 2 +- gtsam/geometry/PinholeCamera.h | 2 +- gtsam/geometry/PinholePose.h | 4 ++-- gtsam/geometry/Pose2.h | 2 +- gtsam/geometry/Pose3.h | 2 +- gtsam/geometry/Rot3.h | 2 +- gtsam/geometry/SOn.h | 2 +- gtsam/geometry/Unit3.h | 2 +- gtsam/geometry/triangulation.h | 2 +- gtsam/navigation/AttitudeFactor.h | 4 ++-- gtsam/navigation/CombinedImuFactor.h | 6 +++--- gtsam/navigation/ImuBias.h | 2 +- gtsam/navigation/PreintegratedRotation.h | 4 ++-- gtsam/navigation/PreintegrationBase.h | 2 +- gtsam/navigation/PreintegrationParams.h | 2 +- gtsam/navigation/TangentPreintegration.h | 2 +- gtsam/nonlinear/ExpressionFactor.h | 2 +- gtsam/nonlinear/NonlinearEquality.h | 6 +++--- gtsam/nonlinear/PriorFactor.h | 2 +- gtsam/nonlinear/internal/ExpressionNode.h | 2 +- gtsam/slam/BetweenFactor.h | 2 +- gtsam/slam/EssentialMatrixConstraint.h | 2 +- gtsam/slam/EssentialMatrixFactor.h | 6 +++--- gtsam/slam/ProjectionFactor.h | 2 +- gtsam/slam/RotateFactor.h | 2 +- gtsam/slam/SmartFactorBase.h | 2 +- 31 files changed, 48 insertions(+), 39 deletions(-) diff --git a/gtsam/base/GenericValue.h b/gtsam/base/GenericValue.h index e1cb3bc2c..2ac3eb80c 100644 --- a/gtsam/base/GenericValue.h +++ b/gtsam/base/GenericValue.h @@ -181,7 +181,7 @@ public: // Alignment, see https://eigen.tuxfamily.org/dox/group__TopicStructHavingEigenMembers.html enum { NeedsToAlign = (sizeof(T) % 16) == 0 }; public: - EIGEN_MAKE_ALIGNED_OPERATOR_NEW_IF(NeedsToAlign) + GTSAM_MAKE_ALIGNED_OPERATOR_NEW_IF(NeedsToAlign) }; /// use this macro instead of BOOST_CLASS_EXPORT for GenericValues diff --git a/gtsam/base/Manifold.h b/gtsam/base/Manifold.h index f3653f099..9feb2b451 100644 --- a/gtsam/base/Manifold.h +++ b/gtsam/base/Manifold.h @@ -214,7 +214,7 @@ public: enum { NeedsToAlign = (sizeof(M1) % 16) == 0 || (sizeof(M2) % 16) == 0 }; public: - EIGEN_MAKE_ALIGNED_OPERATOR_NEW_IF(NeedsToAlign) + GTSAM_MAKE_ALIGNED_OPERATOR_NEW_IF(NeedsToAlign) }; // Define any direct product group to be a model of the multiplicative Group concept diff --git a/gtsam/base/types.h b/gtsam/base/types.h index b54cc2f2a..924f339b3 100644 --- a/gtsam/base/types.h +++ b/gtsam/base/types.h @@ -268,3 +268,12 @@ namespace gtsam { #define GTSAM_MAKE_ALIGNED_OPERATOR_NEW \ EIGEN_MAKE_ALIGNED_OPERATOR_NEW \ using _eigen_aligned_allocator_trait = void; + +/** + * This marks a GTSAM object to require alignment. With this macro an object will automatically be allocated in aligned + * memory when one uses `gtsam::make_shared`. It reduces future misalignment problems that is hard to debug. + * See https://eigen.tuxfamily.org/dox/group__DenseMatrixManipulation__Alignement.html for detailed explanation. + */ +#define GTSAM_MAKE_ALIGNED_OPERATOR_NEW_IF(NeedsToAlign) \ + EIGEN_MAKE_ALIGNED_OPERATOR_NEW_IF(NeedsToAlign) \ + using _eigen_aligned_allocator_trait = void; \ No newline at end of file diff --git a/gtsam/geometry/BearingRange.h b/gtsam/geometry/BearingRange.h index 7c73f3cbd..8db7abffe 100644 --- a/gtsam/geometry/BearingRange.h +++ b/gtsam/geometry/BearingRange.h @@ -162,7 +162,7 @@ private: NeedsToAlign = (sizeof(B) % 16) == 0 || (sizeof(R) % 16) == 0 }; public: - EIGEN_MAKE_ALIGNED_OPERATOR_NEW_IF(NeedsToAlign) + GTSAM_MAKE_ALIGNED_OPERATOR_NEW_IF(NeedsToAlign) }; // Declare this to be both Testable and a Manifold diff --git a/gtsam/geometry/CameraSet.h b/gtsam/geometry/CameraSet.h index ecf9a572d..feab8e0fa 100644 --- a/gtsam/geometry/CameraSet.h +++ b/gtsam/geometry/CameraSet.h @@ -319,7 +319,7 @@ private: } public: - EIGEN_MAKE_ALIGNED_OPERATOR_NEW + GTSAM_MAKE_ALIGNED_OPERATOR_NEW }; template diff --git a/gtsam/geometry/EssentialMatrix.h b/gtsam/geometry/EssentialMatrix.h index 3235fdedd..ca719eb37 100644 --- a/gtsam/geometry/EssentialMatrix.h +++ b/gtsam/geometry/EssentialMatrix.h @@ -212,7 +212,7 @@ class EssentialMatrix { /// @} public: - EIGEN_MAKE_ALIGNED_OPERATOR_NEW + GTSAM_MAKE_ALIGNED_OPERATOR_NEW }; template<> diff --git a/gtsam/geometry/PinholeCamera.h b/gtsam/geometry/PinholeCamera.h index c52127a45..9a80b937b 100644 --- a/gtsam/geometry/PinholeCamera.h +++ b/gtsam/geometry/PinholeCamera.h @@ -325,7 +325,7 @@ private: } public: - EIGEN_MAKE_ALIGNED_OPERATOR_NEW + GTSAM_MAKE_ALIGNED_OPERATOR_NEW }; // manifold traits diff --git a/gtsam/geometry/PinholePose.h b/gtsam/geometry/PinholePose.h index 935962423..60088577c 100644 --- a/gtsam/geometry/PinholePose.h +++ b/gtsam/geometry/PinholePose.h @@ -222,7 +222,7 @@ private: } public: - EIGEN_MAKE_ALIGNED_OPERATOR_NEW + GTSAM_MAKE_ALIGNED_OPERATOR_NEW }; // end of class PinholeBaseK @@ -425,7 +425,7 @@ private: } public: - EIGEN_MAKE_ALIGNED_OPERATOR_NEW + GTSAM_MAKE_ALIGNED_OPERATOR_NEW }; // end of class PinholePose diff --git a/gtsam/geometry/Pose2.h b/gtsam/geometry/Pose2.h index 388318827..2a1f108ca 100644 --- a/gtsam/geometry/Pose2.h +++ b/gtsam/geometry/Pose2.h @@ -317,7 +317,7 @@ public: public: // Align for Point2, which is either derived from, or is typedef, of Vector2 - EIGEN_MAKE_ALIGNED_OPERATOR_NEW + GTSAM_MAKE_ALIGNED_OPERATOR_NEW }; // Pose2 /** specialization for pose2 wedge function (generic template in Lie.h) */ diff --git a/gtsam/geometry/Pose3.h b/gtsam/geometry/Pose3.h index fa55f98de..ced3b904b 100644 --- a/gtsam/geometry/Pose3.h +++ b/gtsam/geometry/Pose3.h @@ -355,7 +355,7 @@ public: #ifdef GTSAM_USE_QUATERNIONS // Align if we are using Quaternions public: - EIGEN_MAKE_ALIGNED_OPERATOR_NEW + GTSAM_MAKE_ALIGNED_OPERATOR_NEW #endif }; // Pose3 class diff --git a/gtsam/geometry/Rot3.h b/gtsam/geometry/Rot3.h index fc3a8b3f2..8f24f07c8 100644 --- a/gtsam/geometry/Rot3.h +++ b/gtsam/geometry/Rot3.h @@ -544,7 +544,7 @@ namespace gtsam { #ifdef GTSAM_USE_QUATERNIONS // only align if quaternion, Matrix3 has no alignment requirements public: - EIGEN_MAKE_ALIGNED_OPERATOR_NEW + GTSAM_MAKE_ALIGNED_OPERATOR_NEW #endif }; diff --git a/gtsam/geometry/SOn.h b/gtsam/geometry/SOn.h index 767b12020..a08f87783 100644 --- a/gtsam/geometry/SOn.h +++ b/gtsam/geometry/SOn.h @@ -54,7 +54,7 @@ class SO : public LieGroup, internal::DimensionSO(N)> { using VectorN2 = Eigen::Matrix; using MatrixDD = Eigen::Matrix; - GTSAM_MAKE_ALIGNED_OPERATOR_NEW + GTSAM_MAKE_ALIGNED_OPERATOR_NEW_IF(true) protected: MatrixNN matrix_; ///< Rotation matrix diff --git a/gtsam/geometry/Unit3.h b/gtsam/geometry/Unit3.h index f1a9c1a69..b80e6e4d8 100644 --- a/gtsam/geometry/Unit3.h +++ b/gtsam/geometry/Unit3.h @@ -214,7 +214,7 @@ private: /// @} public: - EIGEN_MAKE_ALIGNED_OPERATOR_NEW + GTSAM_MAKE_ALIGNED_OPERATOR_NEW }; // Define GTSAM traits diff --git a/gtsam/geometry/triangulation.h b/gtsam/geometry/triangulation.h index 586b7b165..8cdf0fdc0 100644 --- a/gtsam/geometry/triangulation.h +++ b/gtsam/geometry/triangulation.h @@ -215,7 +215,7 @@ struct CameraProjectionMatrix { private: const Matrix3 K_; public: - EIGEN_MAKE_ALIGNED_OPERATOR_NEW + GTSAM_MAKE_ALIGNED_OPERATOR_NEW }; /** diff --git a/gtsam/navigation/AttitudeFactor.h b/gtsam/navigation/AttitudeFactor.h index db588008e..5a0031caf 100644 --- a/gtsam/navigation/AttitudeFactor.h +++ b/gtsam/navigation/AttitudeFactor.h @@ -139,7 +139,7 @@ private: } public: - EIGEN_MAKE_ALIGNED_OPERATOR_NEW + GTSAM_MAKE_ALIGNED_OPERATOR_NEW }; /// traits @@ -219,7 +219,7 @@ private: } public: - EIGEN_MAKE_ALIGNED_OPERATOR_NEW + GTSAM_MAKE_ALIGNED_OPERATOR_NEW }; /// traits diff --git a/gtsam/navigation/CombinedImuFactor.h b/gtsam/navigation/CombinedImuFactor.h index ca9b2ca1a..6b3bf979a 100644 --- a/gtsam/navigation/CombinedImuFactor.h +++ b/gtsam/navigation/CombinedImuFactor.h @@ -100,7 +100,7 @@ private: } public: - EIGEN_MAKE_ALIGNED_OPERATOR_NEW + GTSAM_MAKE_ALIGNED_OPERATOR_NEW }; @@ -210,7 +210,7 @@ public: } public: - EIGEN_MAKE_ALIGNED_OPERATOR_NEW + GTSAM_MAKE_ALIGNED_OPERATOR_NEW }; /** @@ -332,7 +332,7 @@ private: } public: - EIGEN_MAKE_ALIGNED_OPERATOR_NEW + GTSAM_MAKE_ALIGNED_OPERATOR_NEW }; // class CombinedImuFactor diff --git a/gtsam/navigation/ImuBias.h b/gtsam/navigation/ImuBias.h index ff1a53025..d52b4eb29 100644 --- a/gtsam/navigation/ImuBias.h +++ b/gtsam/navigation/ImuBias.h @@ -171,7 +171,7 @@ private: public: - EIGEN_MAKE_ALIGNED_OPERATOR_NEW + GTSAM_MAKE_ALIGNED_OPERATOR_NEW /// @} }; // ConstantBias class diff --git a/gtsam/navigation/PreintegratedRotation.h b/gtsam/navigation/PreintegratedRotation.h index 71ef5d08f..12938a625 100644 --- a/gtsam/navigation/PreintegratedRotation.h +++ b/gtsam/navigation/PreintegratedRotation.h @@ -69,7 +69,7 @@ struct GTSAM_EXPORT PreintegratedRotationParams { #ifdef GTSAM_USE_QUATERNIONS // Align if we are using Quaternions public: - EIGEN_MAKE_ALIGNED_OPERATOR_NEW + GTSAM_MAKE_ALIGNED_OPERATOR_NEW #endif }; @@ -182,7 +182,7 @@ class GTSAM_EXPORT PreintegratedRotation { #ifdef GTSAM_USE_QUATERNIONS // Align if we are using Quaternions public: - EIGEN_MAKE_ALIGNED_OPERATOR_NEW + GTSAM_MAKE_ALIGNED_OPERATOR_NEW #endif }; diff --git a/gtsam/navigation/PreintegrationBase.h b/gtsam/navigation/PreintegrationBase.h index 9926d207a..eb30c1f13 100644 --- a/gtsam/navigation/PreintegrationBase.h +++ b/gtsam/navigation/PreintegrationBase.h @@ -214,7 +214,7 @@ class GTSAM_EXPORT PreintegrationBase { #endif public: - EIGEN_MAKE_ALIGNED_OPERATOR_NEW + GTSAM_MAKE_ALIGNED_OPERATOR_NEW }; } /// namespace gtsam diff --git a/gtsam/navigation/PreintegrationParams.h b/gtsam/navigation/PreintegrationParams.h index 962fef277..4bff625ca 100644 --- a/gtsam/navigation/PreintegrationParams.h +++ b/gtsam/navigation/PreintegrationParams.h @@ -84,7 +84,7 @@ protected: #ifdef GTSAM_USE_QUATERNIONS // Align if we are using Quaternions public: - EIGEN_MAKE_ALIGNED_OPERATOR_NEW + GTSAM_MAKE_ALIGNED_OPERATOR_NEW #endif }; diff --git a/gtsam/navigation/TangentPreintegration.h b/gtsam/navigation/TangentPreintegration.h index 11945e53a..edf76e562 100644 --- a/gtsam/navigation/TangentPreintegration.h +++ b/gtsam/navigation/TangentPreintegration.h @@ -141,7 +141,7 @@ private: } public: - EIGEN_MAKE_ALIGNED_OPERATOR_NEW + GTSAM_MAKE_ALIGNED_OPERATOR_NEW }; } /// namespace gtsam diff --git a/gtsam/nonlinear/ExpressionFactor.h b/gtsam/nonlinear/ExpressionFactor.h index 04d82fe9a..c42b2bdfc 100644 --- a/gtsam/nonlinear/ExpressionFactor.h +++ b/gtsam/nonlinear/ExpressionFactor.h @@ -209,7 +209,7 @@ private: // Alignment, see https://eigen.tuxfamily.org/dox/group__TopicStructHavingEigenMembers.html enum { NeedsToAlign = (sizeof(T) % 16) == 0 }; public: - EIGEN_MAKE_ALIGNED_OPERATOR_NEW_IF(NeedsToAlign) + GTSAM_MAKE_ALIGNED_OPERATOR_NEW_IF(NeedsToAlign) }; // ExpressionFactor diff --git a/gtsam/nonlinear/NonlinearEquality.h b/gtsam/nonlinear/NonlinearEquality.h index d4eb655c3..1bba57051 100644 --- a/gtsam/nonlinear/NonlinearEquality.h +++ b/gtsam/nonlinear/NonlinearEquality.h @@ -175,7 +175,7 @@ public: /// @} - EIGEN_MAKE_ALIGNED_OPERATOR_NEW + GTSAM_MAKE_ALIGNED_OPERATOR_NEW private: @@ -265,7 +265,7 @@ public: traits::Print(value_, "Value"); } - EIGEN_MAKE_ALIGNED_OPERATOR_NEW + GTSAM_MAKE_ALIGNED_OPERATOR_NEW private: @@ -331,7 +331,7 @@ public: return traits::Local(x1,x2); } - EIGEN_MAKE_ALIGNED_OPERATOR_NEW + GTSAM_MAKE_ALIGNED_OPERATOR_NEW private: diff --git a/gtsam/nonlinear/PriorFactor.h b/gtsam/nonlinear/PriorFactor.h index 8d8c67d5c..0afbaa588 100644 --- a/gtsam/nonlinear/PriorFactor.h +++ b/gtsam/nonlinear/PriorFactor.h @@ -114,7 +114,7 @@ namespace gtsam { // Alignment, see https://eigen.tuxfamily.org/dox/group__TopicStructHavingEigenMembers.html enum { NeedsToAlign = (sizeof(T) % 16) == 0 }; public: - EIGEN_MAKE_ALIGNED_OPERATOR_NEW_IF(NeedsToAlign) + GTSAM_MAKE_ALIGNED_OPERATOR_NEW_IF(NeedsToAlign) }; } /// namespace gtsam diff --git a/gtsam/nonlinear/internal/ExpressionNode.h b/gtsam/nonlinear/internal/ExpressionNode.h index 0011efb74..0ae37f130 100644 --- a/gtsam/nonlinear/internal/ExpressionNode.h +++ b/gtsam/nonlinear/internal/ExpressionNode.h @@ -150,7 +150,7 @@ public: return constant_; } - EIGEN_MAKE_ALIGNED_OPERATOR_NEW + GTSAM_MAKE_ALIGNED_OPERATOR_NEW }; //----------------------------------------------------------------------------- diff --git a/gtsam/slam/BetweenFactor.h b/gtsam/slam/BetweenFactor.h index 23138b9e6..b1d4904aa 100644 --- a/gtsam/slam/BetweenFactor.h +++ b/gtsam/slam/BetweenFactor.h @@ -126,7 +126,7 @@ namespace gtsam { // Alignment, see https://eigen.tuxfamily.org/dox/group__TopicStructHavingEigenMembers.html enum { NeedsToAlign = (sizeof(VALUE) % 16) == 0 }; public: - EIGEN_MAKE_ALIGNED_OPERATOR_NEW_IF(NeedsToAlign) + GTSAM_MAKE_ALIGNED_OPERATOR_NEW_IF(NeedsToAlign) }; // \class BetweenFactor /// traits diff --git a/gtsam/slam/EssentialMatrixConstraint.h b/gtsam/slam/EssentialMatrixConstraint.h index 179200fe1..e474ce5b3 100644 --- a/gtsam/slam/EssentialMatrixConstraint.h +++ b/gtsam/slam/EssentialMatrixConstraint.h @@ -105,7 +105,7 @@ private: } public: - EIGEN_MAKE_ALIGNED_OPERATOR_NEW + GTSAM_MAKE_ALIGNED_OPERATOR_NEW }; // \class EssentialMatrixConstraint diff --git a/gtsam/slam/EssentialMatrixFactor.h b/gtsam/slam/EssentialMatrixFactor.h index 8bd155a14..c214a2f48 100644 --- a/gtsam/slam/EssentialMatrixFactor.h +++ b/gtsam/slam/EssentialMatrixFactor.h @@ -81,7 +81,7 @@ public: } public: - EIGEN_MAKE_ALIGNED_OPERATOR_NEW + GTSAM_MAKE_ALIGNED_OPERATOR_NEW }; /** @@ -201,7 +201,7 @@ public: } public: - EIGEN_MAKE_ALIGNED_OPERATOR_NEW + GTSAM_MAKE_ALIGNED_OPERATOR_NEW }; // EssentialMatrixFactor2 @@ -286,7 +286,7 @@ public: } public: - EIGEN_MAKE_ALIGNED_OPERATOR_NEW + GTSAM_MAKE_ALIGNED_OPERATOR_NEW }; // EssentialMatrixFactor3 diff --git a/gtsam/slam/ProjectionFactor.h b/gtsam/slam/ProjectionFactor.h index 856913aae..0bed15fdc 100644 --- a/gtsam/slam/ProjectionFactor.h +++ b/gtsam/slam/ProjectionFactor.h @@ -189,7 +189,7 @@ namespace gtsam { } public: - EIGEN_MAKE_ALIGNED_OPERATOR_NEW + GTSAM_MAKE_ALIGNED_OPERATOR_NEW }; /// traits diff --git a/gtsam/slam/RotateFactor.h b/gtsam/slam/RotateFactor.h index b6ccc36a2..948fffe13 100644 --- a/gtsam/slam/RotateFactor.h +++ b/gtsam/slam/RotateFactor.h @@ -113,7 +113,7 @@ public: return error; } - EIGEN_MAKE_ALIGNED_OPERATOR_NEW + GTSAM_MAKE_ALIGNED_OPERATOR_NEW }; } // namespace gtsam diff --git a/gtsam/slam/SmartFactorBase.h b/gtsam/slam/SmartFactorBase.h index 34f9b9e9f..717a9c1f2 100644 --- a/gtsam/slam/SmartFactorBase.h +++ b/gtsam/slam/SmartFactorBase.h @@ -81,7 +81,7 @@ protected: mutable FBlocks Fs; public: - EIGEN_MAKE_ALIGNED_OPERATOR_NEW + GTSAM_MAKE_ALIGNED_OPERATOR_NEW /// shorthand for a smart pointer to a factor typedef boost::shared_ptr shared_ptr; From 2475e6c68c6581cce518f22c8d6683c857b0fc1b Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Wed, 24 Jun 2020 17:44:03 -0500 Subject: [PATCH 105/869] Load Cython requirements file instead of reading it in cmake --- cython/CMakeLists.txt | 3 +-- 1 file changed, 1 insertion(+), 2 deletions(-) diff --git a/cython/CMakeLists.txt b/cython/CMakeLists.txt index bce9f2308..0d2af6a33 100644 --- a/cython/CMakeLists.txt +++ b/cython/CMakeLists.txt @@ -32,8 +32,7 @@ if (GTSAM_INSTALL_CYTHON_TOOLBOX) ) endif() - file(READ "${PROJECT_SOURCE_DIR}/cython/requirements.txt" CYTHON_INSTALL_REQUIREMENTS) - file(READ "${PROJECT_SOURCE_DIR}/README.md" README_CONTENTS) + set(CYTHON_INSTALL_REQUIREMENTS_FILE "${PROJECT_SOURCE_DIR}/cython/requirements.txt") # Install the custom-generated __init__.py # This is to make the build/cython/gtsam folder a python package, so gtsam can be found while wrapping gtsam_unstable From 453d3a74164613375a083566eea9f8b16c782d74 Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Wed, 24 Jun 2020 18:11:24 -0500 Subject: [PATCH 106/869] Added cmake variable GTSAM_CYTHON_INSTALL_FULLPATH to include build tag directly --- CMakeLists.txt | 4 +++- cmake/GtsamCythonWrap.cmake | 2 +- cython/gtsam_eigency/CMakeLists.txt | 8 ++++---- 3 files changed, 8 insertions(+), 6 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index a810ac9df..2cbdbf00c 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -458,7 +458,9 @@ if (GTSAM_INSTALL_CYTHON_TOOLBOX) if(NOT GTSAM_CYTHON_INSTALL_PATH) set(GTSAM_CYTHON_INSTALL_PATH "${CMAKE_INSTALL_PREFIX}/cython") endif() - set(GTSAM_EIGENCY_INSTALL_PATH ${GTSAM_CYTHON_INSTALL_PATH}/gtsam_eigency) + # Cython install path appended with Build type (e.g. cython, cythonDebug, etc). + set(GTSAM_CYTHON_INSTALL_FULLPATH "${GTSAM_CYTHON_INSTALL_PATH}${GTSAM_BUILD_TAG}") + set(GTSAM_EIGENCY_INSTALL_PATH ${GTSAM_CYTHON_INSTALL_FULLPATH}/gtsam_eigency) add_subdirectory(cython) else() set(GTSAM_INSTALL_CYTHON_TOOLBOX 0) # This will go into config.h diff --git a/cmake/GtsamCythonWrap.cmake b/cmake/GtsamCythonWrap.cmake index 6331d1e95..851f53cfe 100644 --- a/cmake/GtsamCythonWrap.cmake +++ b/cmake/GtsamCythonWrap.cmake @@ -184,7 +184,7 @@ function(install_cython_wrapped_library interface_header generated_files_path in # Split up filename to strip trailing '/' in GTSAM_CYTHON_INSTALL_PATH/subdirectory if there is one get_filename_component(location "${install_path}" PATH) get_filename_component(name "${install_path}" NAME) - message(STATUS "Installing Cython Toolbox to ${location}${GTSAM_BUILD_TAG}/${name}") #${GTSAM_CYTHON_INSTALL_PATH}" + message(STATUS "Installing Cython Toolbox to ${location}${GTSAM_BUILD_TAG}/${name}") #${GTSAM_CYTHON_INSTALL_FULLPATH}" if(GTSAM_BUILD_TYPE_POSTFIXES) foreach(build_type ${CMAKE_CONFIGURATION_TYPES}) diff --git a/cython/gtsam_eigency/CMakeLists.txt b/cython/gtsam_eigency/CMakeLists.txt index 77bead834..da174d690 100644 --- a/cython/gtsam_eigency/CMakeLists.txt +++ b/cython/gtsam_eigency/CMakeLists.txt @@ -39,11 +39,11 @@ add_dependencies(cythonize_eigency cythonize_eigency_conversions cythonize_eigen # install install(DIRECTORY ${CMAKE_CURRENT_SOURCE_DIR} - DESTINATION "${GTSAM_CYTHON_INSTALL_PATH}${GTSAM_BUILD_TAG}" + DESTINATION "${GTSAM_CYTHON_INSTALL_FULLPATH}" PATTERN "CMakeLists.txt" EXCLUDE PATTERN "__init__.py.in" EXCLUDE) install(TARGETS cythonize_eigency_core cythonize_eigency_conversions - DESTINATION "${GTSAM_CYTHON_INSTALL_PATH}${GTSAM_BUILD_TAG}/gtsam_eigency") -install(FILES ${OUTPUT_DIR}/conversions_api.h DESTINATION ${GTSAM_CYTHON_INSTALL_PATH}${GTSAM_BUILD_TAG}/gtsam_eigency) + DESTINATION "${GTSAM_CYTHON_INSTALL_FULLPATH}/gtsam_eigency") +install(FILES ${OUTPUT_DIR}/conversions_api.h DESTINATION ${GTSAM_CYTHON_INSTALL_FULLPATH}/gtsam_eigency) configure_file(__init__.py.in ${OUTPUT_DIR}/__init__.py) -install(FILES ${OUTPUT_DIR}/__init__.py DESTINATION ${GTSAM_CYTHON_INSTALL_PATH}${GTSAM_BUILD_TAG}/gtsam_eigency) +install(FILES ${OUTPUT_DIR}/__init__.py DESTINATION ${GTSAM_CYTHON_INSTALL_FULLPATH}/gtsam_eigency) From 4f6f8216110a2db9d7a9be3fbdba65a967490793 Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Wed, 24 Jun 2020 18:39:49 -0500 Subject: [PATCH 107/869] Vastly improved setup.py template --- cython/setup.py.in | 27 +++++++++++++++++++-------- 1 file changed, 19 insertions(+), 8 deletions(-) diff --git a/cython/setup.py.in b/cython/setup.py.in index df92b564c..98a05c9f6 100644 --- a/cython/setup.py.in +++ b/cython/setup.py.in @@ -7,6 +7,22 @@ except ImportError: packages = find_packages() +package_data = { + package: + [f for f in os.listdir(package.replace('.', os.path.sep)) if os.path.splitext(f)[1] in ('.so', '.pyd')] + for package in packages +} + +cython_install_requirements = open("${CYTHON_INSTALL_REQUIREMENTS_FILE}").readlines() + +install_requires = [line.strip() \ + for line in cython_install_requirements \ + if len(line.strip()) > 0 and not line.strip().startswith('#') +] + +# Cleaner to read in the contents rather than copy them over. +readme_contents = open("${PROJECT_SOURCE_DIR}/README.md").read() + setup( name='gtsam', description='Georgia Tech Smoothing And Mapping library', @@ -16,7 +32,7 @@ setup( author_email='frank.dellaert@gtsam.org', license='Simplified BSD license', keywords='slam sam robotics localization mapping optimization', - long_description='''${README_CONTENTS}''', + long_description=readme_contents, long_description_content_type='text/markdown', python_requires='>=2.7', # https://pypi.org/pypi?%3Aaction=list_classifiers @@ -34,11 +50,6 @@ setup( ], packages=packages, - package_data={package: - [f for f in os.listdir(package.replace('.', os.path.sep)) if os.path.splitext(f)[1] in ('.so', '.pyd')] - for package in packages - }, - install_requires=[line.strip() for line in ''' -${CYTHON_INSTALL_REQUIREMENTS} -'''.splitlines() if len(line.strip()) > 0 and not line.strip().startswith('#')] + package_data=package_data, + install_requires=install_requires ) From 192184b3b7c1efacb5a7608a7da4205fbba3536f Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Wed, 24 Jun 2020 18:40:03 -0500 Subject: [PATCH 108/869] Specify working directory from where to call setup.py --- cython/CMakeLists.txt | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/cython/CMakeLists.txt b/cython/CMakeLists.txt index 0d2af6a33..01b6c06d4 100644 --- a/cython/CMakeLists.txt +++ b/cython/CMakeLists.txt @@ -45,6 +45,8 @@ if (GTSAM_INSTALL_CYTHON_TOOLBOX) install_cython_scripts("${PROJECT_SOURCE_DIR}/cython/gtsam_unstable" "${GTSAM_CYTHON_INSTALL_PATH}" "*.py") # Add the new make target command - add_custom_target(python-install COMMAND ${PYTHON_EXECUTABLE} ${GTSAM_CYTHON_INSTALL_PATH}${GTSAM_BUILD_TAG}/setup.py install) + add_custom_target(python-install + COMMAND ${PYTHON_EXECUTABLE} ${GTSAM_CYTHON_INSTALL_PATH}${GTSAM_BUILD_TAG}/setup.py install + WORKING_DIRECTORY ${GTSAM_CYTHON_INSTALL_FULLPATH}) endif () From a4ef531a32b6fa078a24cd30ef17cbdb9580688e Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Wed, 24 Jun 2020 19:23:37 -0500 Subject: [PATCH 109/869] print Eigen Unsupported status message correctly --- gtsam/3rdparty/CMakeLists.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/gtsam/3rdparty/CMakeLists.txt b/gtsam/3rdparty/CMakeLists.txt index 89149d964..c8fecc339 100644 --- a/gtsam/3rdparty/CMakeLists.txt +++ b/gtsam/3rdparty/CMakeLists.txt @@ -17,7 +17,7 @@ if(NOT GTSAM_USE_SYSTEM_EIGEN) endforeach(eigen_dir) if(GTSAM_WITH_EIGEN_UNSUPPORTED) - message("-- Installing Eigen Unsupported modules") + message(STATUS "Installing Eigen Unsupported modules") # do the same for the unsupported eigen folder file(GLOB_RECURSE unsupported_eigen_headers "${CMAKE_CURRENT_SOURCE_DIR}/Eigen/unsupported/Eigen/*.h") From 7f1384b0f26e89136237e538779c6f6b0972c6b4 Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Wed, 24 Jun 2020 19:25:56 -0500 Subject: [PATCH 110/869] wrap the biasHat function for PreintegratedMeasurement --- gtsam.h | 2 ++ 1 file changed, 2 insertions(+) diff --git a/gtsam.h b/gtsam.h index 614db91c7..bf4d7f4d1 100644 --- a/gtsam.h +++ b/gtsam.h @@ -2955,6 +2955,7 @@ class PreintegratedImuMeasurements { gtsam::Rot3 deltaRij() const; Vector deltaPij() const; Vector deltaVij() const; + gtsam::imuBias::ConstantBias biasHat() const; Vector biasHatVector() const; gtsam::NavState predict(const gtsam::NavState& state_i, const gtsam::imuBias::ConstantBias& bias) const; @@ -3016,6 +3017,7 @@ class PreintegratedCombinedMeasurements { gtsam::Rot3 deltaRij() const; Vector deltaPij() const; Vector deltaVij() const; + gtsam::imuBias::ConstantBias biasHat() const; Vector biasHatVector() const; gtsam::NavState predict(const gtsam::NavState& state_i, const gtsam::imuBias::ConstantBias& bias) const; From 350808d9dc7b6e2e31814e6b59ede8d59c9dfe8b Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Wed, 24 Jun 2020 19:27:45 -0500 Subject: [PATCH 111/869] added .gitignore for when building the sample cmake projects --- cmake/.gitignore | 1 + 1 file changed, 1 insertion(+) create mode 100644 cmake/.gitignore diff --git a/cmake/.gitignore b/cmake/.gitignore new file mode 100644 index 000000000..6f467448b --- /dev/null +++ b/cmake/.gitignore @@ -0,0 +1 @@ +**/build \ No newline at end of file From 17568e67793ad831b02ec701ef6734bbfe950f68 Mon Sep 17 00:00:00 2001 From: Fan Jiang Date: Thu, 25 Jun 2020 00:14:21 -0400 Subject: [PATCH 112/869] Add missing lf --- gtsam/base/types.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/gtsam/base/types.h b/gtsam/base/types.h index 924f339b3..c5dac9ab7 100644 --- a/gtsam/base/types.h +++ b/gtsam/base/types.h @@ -276,4 +276,4 @@ namespace gtsam { */ #define GTSAM_MAKE_ALIGNED_OPERATOR_NEW_IF(NeedsToAlign) \ EIGEN_MAKE_ALIGNED_OPERATOR_NEW_IF(NeedsToAlign) \ - using _eigen_aligned_allocator_trait = void; \ No newline at end of file + using _eigen_aligned_allocator_trait = void; From fee226a1de09c57c086ded40769a3cc024b2cdc5 Mon Sep 17 00:00:00 2001 From: akrishnan86 Date: Wed, 24 Jun 2020 22:43:55 -0700 Subject: [PATCH 113/869] fix SfmData naming --- tests/testTranslationRecovery.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/tests/testTranslationRecovery.cpp b/tests/testTranslationRecovery.cpp index 774a999e4..5a98c3bf5 100644 --- a/tests/testTranslationRecovery.cpp +++ b/tests/testTranslationRecovery.cpp @@ -33,7 +33,7 @@ using namespace gtsam; // sets up an optimization problem for the three unknown translations. TEST(TranslationRecovery, BAL) { const string filename = findExampleDataFile("dubrovnik-3-7-pre"); - SfM_data db; + SfmData db; bool success = readBAL(filename, db); if (!success) throw runtime_error("Could not access file!"); From c8583e921a2c370d244b7cf04e8f1a56a44d7f50 Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Thu, 25 Jun 2020 10:28:59 -0500 Subject: [PATCH 114/869] Revert "added .gitignore for when building the sample cmake projects" This reverts commit 350808d9dc7b6e2e31814e6b59ede8d59c9dfe8b. --- cmake/.gitignore | 1 - 1 file changed, 1 deletion(-) delete mode 100644 cmake/.gitignore diff --git a/cmake/.gitignore b/cmake/.gitignore deleted file mode 100644 index 6f467448b..000000000 --- a/cmake/.gitignore +++ /dev/null @@ -1 +0,0 @@ -**/build \ No newline at end of file From 9d9c30e5dc399fafc1726c949f24276b160244b4 Mon Sep 17 00:00:00 2001 From: akrishnan86 Date: Sun, 28 Jun 2020 11:03:38 -0700 Subject: [PATCH 115/869] review1 changes --- gtsam/sfm/TranslationFactor.h | 6 ++++-- gtsam/sfm/TranslationRecovery.cpp | 2 +- gtsam/sfm/TranslationRecovery.h | 5 +++++ gtsam/sfm/tests/testTranslationFactor.cpp | 20 +++++++++++++++++++- 4 files changed, 29 insertions(+), 4 deletions(-) diff --git a/gtsam/sfm/TranslationFactor.h b/gtsam/sfm/TranslationFactor.h index 584b1fa69..9a4bd68a7 100644 --- a/gtsam/sfm/TranslationFactor.h +++ b/gtsam/sfm/TranslationFactor.h @@ -51,8 +51,10 @@ class TranslationFactor : public NoiseModelFactor2 { : Base(noiseModel, a, b), measured_w_aZb_(w_aZb.point3()) {} /** - * @brief Caclulate error norm(p1-p2) - measured - * + * @brief Caclulate error: (norm(Tb - Ta) - measurement) + * where Tb and Ta are Point3 translations and measurement is + * the Unit3 translation direction from a to b. + * * @param Ta translation for key a * @param Tb translation for key b * @param H1 optional jacobian in Ta diff --git a/gtsam/sfm/TranslationRecovery.cpp b/gtsam/sfm/TranslationRecovery.cpp index a0f3eb6b6..aeeae688f 100644 --- a/gtsam/sfm/TranslationRecovery.cpp +++ b/gtsam/sfm/TranslationRecovery.cpp @@ -60,7 +60,7 @@ void TranslationRecovery::addPrior(const double scale, } Values TranslationRecovery::initalizeRandomly() const { - // Create a lambda expression that checks whether value exists and randomly + // Create a lambda expression that checks whether value exists and randomly // initializes if not. Values initial; auto insert = [&initial](Key j) { diff --git a/gtsam/sfm/TranslationRecovery.h b/gtsam/sfm/TranslationRecovery.h index 634825d29..bb3c3cdb1 100644 --- a/gtsam/sfm/TranslationRecovery.h +++ b/gtsam/sfm/TranslationRecovery.h @@ -60,6 +60,9 @@ class TranslationRecovery { * * @param relativeTranslations the relative translations, in world coordinate * frames, indexed in a map by a pair of Pose keys. + * @param lmParams (optional) gtsam::LavenbergMarquardtParams that can be + * used to modify the parameters for the LM optimizer. By default, uses the + * default LM parameters. */ TranslationRecovery(const TranslationEdges& relativeTranslations, const LevenbergMarquardtParams& lmParams = LevenbergMarquardtParams()) @@ -102,6 +105,8 @@ class TranslationRecovery { * * @param poses SE(3) ground truth poses stored as Values * @param edges pairs (a,b) for which a measurement w_aZb will be generated. + * @return TranslationEdges map from a KeyPair to the simulated Unit3 + * translation direction measurement between the cameras in KeyPair. */ static TranslationEdges SimulateMeasurements( const Values& poses, const std::vector& edges); diff --git a/gtsam/sfm/tests/testTranslationFactor.cpp b/gtsam/sfm/tests/testTranslationFactor.cpp index da284bfd6..37e8b6c0f 100644 --- a/gtsam/sfm/tests/testTranslationFactor.cpp +++ b/gtsam/sfm/tests/testTranslationFactor.cpp @@ -38,7 +38,7 @@ TEST(TranslationFactor, Constructor) { } /* ************************************************************************* */ -TEST(TranslationFactor, Error) { +TEST(TranslationFactor, ZeroError) { // Create a factor TranslationFactor factor(kKey1, kKey2, kMeasured, model); @@ -51,6 +51,24 @@ TEST(TranslationFactor, Error) { // Verify we get the expected error Vector expected = (Vector3() << 0, 0, 0).finished(); EXPECT(assert_equal(expected, actualError, 1e-9)); + + +} + +/* ************************************************************************* */ +TEST(TranslationFactor, NonZeroError) { + // create a factor + TranslationFactor factor(kKey1, kKey2, kMeasured, model); + + // set the linearization + Point3 T1(0, 1, 1), T2(0, 2, 2); + + // use the factor to calculate the error + Vector actualError(factor.evaluateError(T1, T2)); + + // verify we get the expected error + Vector expected = (Vector3() << -1, 1/sqrt(2), 1/sqrt(2)).finished(); + EXPECT(assert_equal(expected, actualError, 1e-9)); } /* ************************************************************************* */ From 17bf29d4b05b7baf777861719b6e5f5dd445d561 Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Sun, 28 Jun 2020 20:24:54 -0500 Subject: [PATCH 116/869] improved result printing and use of flags for ImuFactorExample.py --- cython/gtsam/examples/ImuFactorExample.py | 48 +++++++++++++---------- 1 file changed, 28 insertions(+), 20 deletions(-) diff --git a/cython/gtsam/examples/ImuFactorExample.py b/cython/gtsam/examples/ImuFactorExample.py index d323c1b17..bb0424c85 100644 --- a/cython/gtsam/examples/ImuFactorExample.py +++ b/cython/gtsam/examples/ImuFactorExample.py @@ -63,7 +63,7 @@ class ImuFactorExample(PreintegrationExample): graph.push_back(gtsam.PriorFactorVector( V(i), state.velocity(), self.velNoise)) - def run(self, T=12, verbose=True): + def run(self, T=12, compute_covariances=False, verbose=True): graph = gtsam.NonlinearFactorGraph() # initialize data structure for pre-integrated IMU measurements @@ -75,9 +75,9 @@ class ImuFactorExample(PreintegrationExample): # simulate the loop i = 0 # state index - actual_state_i = self.scenario.navState(0) - initial.insert(X(i), actual_state_i.pose()) - initial.insert(V(i), actual_state_i.velocity()) + initial_state_i = self.scenario.navState(0) + initial.insert(X(i), initial_state_i.pose()) + initial.insert(V(i), initial_state_i.velocity()) for k, t in enumerate(np.arange(0, T, self.dt)): # get measurements and add them to PIM @@ -111,17 +111,20 @@ class ImuFactorExample(PreintegrationExample): poseNoise = gtsam.Pose3(rotationNoise, translationNoise) actual_state_i = self.scenario.navState(t + self.dt) - actual_state_i = gtsam.NavState( + print("Actual state at {0}:\n{1}".format(t+self.dt, actual_state_i)) + + noisy_state_i = gtsam.NavState( actual_state_i.pose().compose(poseNoise), actual_state_i.velocity() + np.random.randn(3)*0.1) - initial.insert(X(i+1), actual_state_i.pose()) - initial.insert(V(i+1), actual_state_i.velocity()) + initial.insert(X(i+1), noisy_state_i.pose()) + initial.insert(V(i+1), noisy_state_i.velocity()) i += 1 - # add priors on beginning and end + # add prior on beginning self.addPrior(0, graph) - self.addPrior(num_poses - 1, graph) + # add prior on end + # self.addPrior(num_poses - 1, graph) # optimize using Levenberg-Marquardt optimization params = gtsam.LevenbergMarquardtParams() @@ -129,14 +132,17 @@ class ImuFactorExample(PreintegrationExample): optimizer = gtsam.LevenbergMarquardtOptimizer(graph, initial, params) result = optimizer.optimize() - # Calculate and print marginal covariances - marginals = gtsam.Marginals(graph, result) - print("Covariance on bias:\n", marginals.marginalCovariance(BIAS_KEY)) - for i in range(num_poses): - print("Covariance on pose {}:\n{}\n".format( - i, marginals.marginalCovariance(X(i)))) - print("Covariance on vel {}:\n{}\n".format( - i, marginals.marginalCovariance(V(i)))) + result.print_("") + + if compute_covariances: + # Calculate and print marginal covariances + marginals = gtsam.Marginals(graph, result) + print("Covariance on bias:\n", marginals.marginalCovariance(BIAS_KEY)) + for i in range(num_poses): + print("Covariance on pose {}:\n{}\n".format( + i, marginals.marginalCovariance(X(i)))) + print("Covariance on vel {}:\n{}\n".format( + i, marginals.marginalCovariance(V(i)))) # Plot resulting poses i = 0 @@ -148,7 +154,7 @@ class ImuFactorExample(PreintegrationExample): gtsam.utils.plot.set_axes_equal(POSES_FIG+1) - print(result.atimuBias_ConstantBias(BIAS_KEY)) + print("Bias Values", result.atimuBias_ConstantBias(BIAS_KEY)) plt.ioff() plt.show() @@ -159,8 +165,10 @@ if __name__ == '__main__': parser.add_argument("--twist_scenario", default="sick_twist", choices=("zero_twist", "forward_twist", "loop_twist", "sick_twist")) - parser.add_argument("--time", "-T", default=12, type=int, help="Total time in seconds") + parser.add_argument("--time", "-T", default=12, + type=int, help="Total time in seconds") + parser.add_argument("--compute_covariances", default=False, action='store_true') parser.add_argument("--verbose", default=False, action='store_true') args = parser.parse_args() - ImuFactorExample().run(args.time, args.verbose) + ImuFactorExample(args.twist_scenario).run(args.time, args.compute_covariances, args.verbose) From bfbb6cb28d81dd2fb18ded67ca4e805f0fbb291c Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Mon, 29 Jun 2020 16:32:46 -0500 Subject: [PATCH 117/869] renamed ImuFactorExample2 to ImuFactorISAM2Example --- ...orExample2.py => ImuFactorISAM2Example.py} | 122 +++++++++--------- 1 file changed, 60 insertions(+), 62 deletions(-) rename cython/gtsam/examples/{ImuFactorExample2.py => ImuFactorISAM2Example.py} (69%) diff --git a/cython/gtsam/examples/ImuFactorExample2.py b/cython/gtsam/examples/ImuFactorISAM2Example.py similarity index 69% rename from cython/gtsam/examples/ImuFactorExample2.py rename to cython/gtsam/examples/ImuFactorISAM2Example.py index 0d98f08fe..3d3138bf5 100644 --- a/cython/gtsam/examples/ImuFactorExample2.py +++ b/cython/gtsam/examples/ImuFactorISAM2Example.py @@ -1,6 +1,6 @@ """ iSAM2 example with ImuFactor. -Author: Robert Truax (C++), Frank Dellaert (Python) +Author: Frank Dellaert, Varun Agrawal """ # pylint: disable=invalid-name, E1101 @@ -8,10 +8,11 @@ from __future__ import print_function import math -import gtsam -import gtsam.utils.plot as gtsam_plot import matplotlib.pyplot as plt import numpy as np +from mpl_toolkits.mplot3d import Axes3D # pylint: disable=W0611 + +import gtsam from gtsam import (ISAM2, BetweenFactorConstantBias, Cal3_S2, ConstantTwistScenario, ImuFactor, NonlinearFactorGraph, PinholeCameraCal3_S2, Point3, Pose3, @@ -20,7 +21,7 @@ from gtsam import (ISAM2, BetweenFactorConstantBias, Cal3_S2, from gtsam import symbol_shorthand_B as B from gtsam import symbol_shorthand_V as V from gtsam import symbol_shorthand_X as X -from mpl_toolkits.mplot3d import Axes3D # pylint: disable=W0611 +from gtsam.utils import plot def vector3(x, y, z): @@ -28,46 +29,46 @@ def vector3(x, y, z): return np.array([x, y, z], dtype=np.float) -def ISAM2_plot(values, fignum=0): - """Plot poses.""" - fig = plt.figure(fignum) - axes = fig.gca(projection='3d') - plt.cla() - - i = 0 - min_bounds = 0, 0, 0 - max_bounds = 0, 0, 0 - while values.exists(X(i)): - pose_i = values.atPose3(X(i)) - gtsam_plot.plot_pose3(fignum, pose_i, 10) - position = pose_i.translation().vector() - min_bounds = [min(v1, v2) for (v1, v2) in zip(position, min_bounds)] - max_bounds = [max(v1, v2) for (v1, v2) in zip(position, max_bounds)] - # max_bounds = min(pose_i.x(), max_bounds[0]), 0, 0 - i += 1 - - # draw - axes.set_xlim3d(min_bounds[0]-1, max_bounds[0]+1) - axes.set_ylim3d(min_bounds[1]-1, max_bounds[1]+1) - axes.set_zlim3d(min_bounds[2]-1, max_bounds[2]+1) - plt.pause(1) - - -# IMU preintegration parameters -# Default Params for a Z-up navigation frame, such as ENU: gravity points along negative Z-axis g = 9.81 -n_gravity = vector3(0, 0, -g) -PARAMS = gtsam.PreintegrationParams.MakeSharedU(g) -I = np.eye(3) -PARAMS.setAccelerometerCovariance(I * 0.1) -PARAMS.setGyroscopeCovariance(I * 0.1) -PARAMS.setIntegrationCovariance(I * 0.1) -PARAMS.setUse2ndOrderCoriolis(False) -PARAMS.setOmegaCoriolis(vector3(0, 0, 0)) +kGravity = vector3(0, 0, -g) -BIAS_COVARIANCE = gtsam.noiseModel_Isotropic.Variance(6, 0.1) -DELTA = Pose3(Rot3.Rodrigues(0, 0, 0), - Point3(0.05, -0.10, 0.20)) + +def preintegration_parameters(): + # IMU preintegration parameters + # Default Params for a Z-up navigation frame, such as ENU: gravity points along negative Z-axis + PARAMS = gtsam.PreintegrationParams.MakeSharedU(g) + I = np.eye(3) + PARAMS.setAccelerometerCovariance(I * 0.1) + PARAMS.setGyroscopeCovariance(I * 0.1) + PARAMS.setIntegrationCovariance(I * 0.1) + PARAMS.setUse2ndOrderCoriolis(False) + PARAMS.setOmegaCoriolis(vector3(0, 0, 0)) + + BIAS_COVARIANCE = gtsam.noiseModel_Isotropic.Variance(6, 0.1) + DELTA = Pose3(Rot3.Rodrigues(0, 0, 0), + Point3(0.05, -0.10, 0.20)) + + return PARAMS, BIAS_COVARIANCE, DELTA + + +def get_camera(radius): + up = Point3(0, 0, 1) + target = Point3(0, 0, 0) + position = Point3(radius, 0, 0) + camera = PinholeCameraCal3_S2.Lookat(position, target, up, Cal3_S2()) + return camera + + +def get_scenario(radius, pose_0, angular_velocity, delta_t): + """Create the set of ground-truth landmarks and poses""" + + + angular_velocity_vector = vector3(0, -angular_velocity, 0) + linear_velocity_vector = vector3(radius * angular_velocity, 0, 0) + scenario = ConstantTwistScenario( + angular_velocity_vector, linear_velocity_vector, pose_0) + + return scenario def IMU_example(): @@ -75,23 +76,17 @@ def IMU_example(): # Start with a camera on x-axis looking at origin radius = 30 - up = Point3(0, 0, 1) - target = Point3(0, 0, 0) - position = Point3(radius, 0, 0) - camera = PinholeCameraCal3_S2.Lookat(position, target, up, Cal3_S2()) + camera = get_camera(radius) pose_0 = camera.pose() - # Create the set of ground-truth landmarks and poses - angular_velocity = math.radians(180) # rad/sec delta_t = 1.0/18 # makes for 10 degrees per step + angular_velocity = math.radians(180) # rad/sec + scenario = get_scenario(radius, pose_0, angular_velocity, delta_t) - angular_velocity_vector = vector3(0, -angular_velocity, 0) - linear_velocity_vector = vector3(radius * angular_velocity, 0, 0) - scenario = ConstantTwistScenario( - angular_velocity_vector, linear_velocity_vector, pose_0) + PARAMS, BIAS_COVARIANCE, DELTA = preintegration_parameters() # Create a factor graph - newgraph = NonlinearFactorGraph() + graph = NonlinearFactorGraph() # Create (incremental) ISAM2 solver isam = ISAM2() @@ -104,21 +99,21 @@ def IMU_example(): # 30cm std on x,y,z 0.1 rad on roll,pitch,yaw noise = gtsam.noiseModel_Diagonal.Sigmas( np.array([0.1, 0.1, 0.1, 0.3, 0.3, 0.3])) - newgraph.push_back(PriorFactorPose3(X(0), pose_0, noise)) + graph.push_back(PriorFactorPose3(X(0), pose_0, noise)) # Add imu priors biasKey = B(0) biasnoise = gtsam.noiseModel_Isotropic.Sigma(6, 0.1) biasprior = PriorFactorConstantBias(biasKey, gtsam.imuBias_ConstantBias(), biasnoise) - newgraph.push_back(biasprior) + graph.push_back(biasprior) initialEstimate.insert(biasKey, gtsam.imuBias_ConstantBias()) velnoise = gtsam.noiseModel_Isotropic.Sigma(3, 0.1) # Calculate with correct initial velocity n_velocity = vector3(0, angular_velocity * radius, 0) velprior = PriorFactorVector(V(0), n_velocity, velnoise) - newgraph.push_back(velprior) + graph.push_back(velprior) initialEstimate.insert(V(0), n_velocity) accum = gtsam.PreintegratedImuMeasurements(PARAMS) @@ -140,33 +135,36 @@ def IMU_example(): biasKey += 1 factor = BetweenFactorConstantBias( biasKey - 1, biasKey, gtsam.imuBias_ConstantBias(), BIAS_COVARIANCE) - newgraph.add(factor) + graph.add(factor) initialEstimate.insert(biasKey, gtsam.imuBias_ConstantBias()) # Predict acceleration and gyro measurements in (actual) body frame nRb = scenario.rotation(t).matrix() bRn = np.transpose(nRb) - measuredAcc = scenario.acceleration_b(t) - np.dot(bRn, n_gravity) + measuredAcc = scenario.acceleration_b(t) - np.dot(bRn, kGravity) measuredOmega = scenario.omega_b(t) accum.integrateMeasurement(measuredAcc, measuredOmega, delta_t) # Add Imu Factor imufac = ImuFactor(X(i - 1), V(i - 1), X(i), V(i), biasKey, accum) - newgraph.add(imufac) + graph.add(imufac) # insert new velocity, which is wrong initialEstimate.insert(V(i), n_velocity) accum.resetIntegration() # Incremental solution - isam.update(newgraph, initialEstimate) + isam.update(graph, initialEstimate) result = isam.calculateEstimate() - ISAM2_plot(result) + plot.plot_incremental_trajectory(0, result, + start=i, scale=3, time_interval=0.01) # reset - newgraph = NonlinearFactorGraph() + graph = NonlinearFactorGraph() initialEstimate.clear() + plt.show() + if __name__ == '__main__': IMU_example() From 89bdebf5ca96233b2d82d14741a1c1e58d53b1c3 Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Mon, 29 Jun 2020 16:33:09 -0500 Subject: [PATCH 118/869] added function to plot trajectory incrementally --- cython/gtsam/utils/plot.py | 41 +++++++++++++++++++++++++++++++++++++- 1 file changed, 40 insertions(+), 1 deletion(-) diff --git a/cython/gtsam/utils/plot.py b/cython/gtsam/utils/plot.py index b67444fc1..cbc7c227a 100644 --- a/cython/gtsam/utils/plot.py +++ b/cython/gtsam/utils/plot.py @@ -268,7 +268,8 @@ def plot_pose3(fignum, pose, axis_length=0.1, P=None): axis_length=axis_length) -def plot_trajectory(fignum, values, scale=1, marginals=None): +def plot_trajectory(fignum, values, scale=1, marginals=None, + animation_interval=0.0): """ Plot a complete 3D trajectory using poses in `values`. @@ -323,3 +324,41 @@ def plot_trajectory(fignum, values, scale=1, marginals=None): except: pass + + +def plot_incremental_trajectory(fignum, values, start=0, + scale=1, marginals=None, + time_interval=0.0): + """ + Incrementally plot a complete 3D trajectory using poses in `values`. + + Args: + fignum (int): Integer representing the figure number to use for plotting. + values (gtsam.Values): Values dict containing the poses. + start (int): Starting index to start plotting from. + scale (float): Value to scale the poses by. + marginals (gtsam.Marginals): Marginalized probability values of the estimation. + Used to plot uncertainty bounds. + time_interval (float): Time in seconds to pause between each rendering. + Used to create animation effect. + """ + fig = plt.figure(fignum) + axes = fig.gca(projection='3d') + + pose3Values = gtsam.utilities_allPose3s(values) + keys = gtsam.KeyVector(pose3Values.keys()) + + for i in range(start, keys.size()): + key = keys.at(i) + if values.exists(key): + pose_i = values.atPose3(keys.at(i)) + plot_pose3(fignum, pose_i, scale) + + # Update the plot space to encompass all plotted points + axes.autoscale() + + # Set the 3 axes equal + set_axes_equal(fignum) + + # Pause for a fixed amount of seconds + plt.pause(time_interval) From 6fdcddbaa7678620d46fbade21850f4e74e312bb Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Mon, 29 Jun 2020 16:33:28 -0500 Subject: [PATCH 119/869] improvements to ImuFactorExample --- cython/gtsam/examples/ImuFactorExample.py | 9 +++++---- cython/gtsam/examples/PreintegrationExample.py | 9 ++++----- 2 files changed, 9 insertions(+), 9 deletions(-) diff --git a/cython/gtsam/examples/ImuFactorExample.py b/cython/gtsam/examples/ImuFactorExample.py index bb0424c85..289a0ccec 100644 --- a/cython/gtsam/examples/ImuFactorExample.py +++ b/cython/gtsam/examples/ImuFactorExample.py @@ -69,7 +69,7 @@ class ImuFactorExample(PreintegrationExample): # initialize data structure for pre-integrated IMU measurements pim = gtsam.PreintegratedImuMeasurements(self.params, self.actualBias) - num_poses = T + 1 # assumes 1 factor per second + num_poses = T # assumes 1 factor per second initial = gtsam.Values() initial.insert(BIAS_KEY, self.actualBias) @@ -91,7 +91,7 @@ class ImuFactorExample(PreintegrationExample): if (k+1) % int(1 / self.dt) == 0: # Plot every second - self.plotGroundTruthPose(t) + self.plotGroundTruthPose(t, scale=1) plt.title("Ground Truth Trajectory") # create IMU factor every second @@ -107,7 +107,7 @@ class ImuFactorExample(PreintegrationExample): pim.resetIntegration() rotationNoise = gtsam.Rot3.Expmap(np.random.randn(3)*0.1) - translationNoise = gtsam.Point3(np.random.randn(3)*0.1) + translationNoise = gtsam.Point3(np.random.randn(3)*1) poseNoise = gtsam.Pose3(rotationNoise, translationNoise) actual_state_i = self.scenario.navState(t + self.dt) @@ -132,6 +132,7 @@ class ImuFactorExample(PreintegrationExample): optimizer = gtsam.LevenbergMarquardtOptimizer(graph, initial, params) result = optimizer.optimize() + initial.print_("Initial values:") result.print_("") if compute_covariances: @@ -148,7 +149,7 @@ class ImuFactorExample(PreintegrationExample): i = 0 while result.exists(X(i)): pose_i = result.atPose3(X(i)) - plot_pose3(POSES_FIG+1, pose_i, 0.1) + plot_pose3(POSES_FIG+1, pose_i, 1) i += 1 plt.title("Estimated Trajectory") diff --git a/cython/gtsam/examples/PreintegrationExample.py b/cython/gtsam/examples/PreintegrationExample.py index 68b1c8cc0..958221ac9 100644 --- a/cython/gtsam/examples/PreintegrationExample.py +++ b/cython/gtsam/examples/PreintegrationExample.py @@ -109,10 +109,10 @@ class PreintegrationExample(object): ax.scatter(t, measuredAcc[i], color=color, marker='.') ax.set_xlabel('specific force ' + label) - def plotGroundTruthPose(self, t): + def plotGroundTruthPose(self, t, scale=0.3, time_interval=0.01): # plot ground truth pose, as well as prediction from integrated IMU measurements actualPose = self.scenario.pose(t) - plot_pose3(POSES_FIG, actualPose, 0.3) + plot_pose3(POSES_FIG, actualPose, scale) t = actualPose.translation() self.maxDim = max([abs(t.x()), abs(t.y()), abs(t.z()), self.maxDim]) ax = plt.gca() @@ -120,11 +120,10 @@ class PreintegrationExample(object): ax.set_ylim3d(-self.maxDim, self.maxDim) ax.set_zlim3d(-self.maxDim, self.maxDim) - plt.pause(0.01) + plt.pause(time_interval) - def run(self): + def run(self, T=12): # simulate the loop - T = 12 for i, t in enumerate(np.arange(0, T, self.dt)): measuredOmega = self.runner.measuredAngularVelocity(t) measuredAcc = self.runner.measuredSpecificForce(t) From 561218ae822039fb48d1911c7344599208de3747 Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Mon, 29 Jun 2020 16:34:05 -0500 Subject: [PATCH 120/869] updated file docstring for ImuFactorExample2.cpp --- examples/ImuFactorExample2.cpp | 16 ++++++++++++++++ 1 file changed, 16 insertions(+) diff --git a/examples/ImuFactorExample2.cpp b/examples/ImuFactorExample2.cpp index cb3650421..0031acbe8 100644 --- a/examples/ImuFactorExample2.cpp +++ b/examples/ImuFactorExample2.cpp @@ -1,3 +1,19 @@ +/* ---------------------------------------------------------------------------- + + * GTSAM Copyright 2010, Georgia Tech Research Corporation, + * Atlanta, Georgia 30332-0415 + * All Rights Reserved + * Authors: Frank Dellaert, et al. (see THANKS for the full author list) + + * See LICENSE for the license information + + * -------------------------------------------------------------------------- */ + +/** + * @file ImuFactorExample2 + * @brief Test example for using GTSAM ImuFactor and ImuCombinedFactor with ISAM2. + * @author Robert Truax + */ #include #include From 54c29031839fe00d559e97e4b2014927667180d2 Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Mon, 29 Jun 2020 16:53:42 -0500 Subject: [PATCH 121/869] make python-install command depends on gtsam target --- cython/CMakeLists.txt | 1 + 1 file changed, 1 insertion(+) diff --git a/cython/CMakeLists.txt b/cython/CMakeLists.txt index 01b6c06d4..2bfa8ae7c 100644 --- a/cython/CMakeLists.txt +++ b/cython/CMakeLists.txt @@ -47,6 +47,7 @@ if (GTSAM_INSTALL_CYTHON_TOOLBOX) # Add the new make target command add_custom_target(python-install COMMAND ${PYTHON_EXECUTABLE} ${GTSAM_CYTHON_INSTALL_PATH}${GTSAM_BUILD_TAG}/setup.py install + DEPENDS gtsam WORKING_DIRECTORY ${GTSAM_CYTHON_INSTALL_FULLPATH}) endif () From 806e5b12a37462481f1d1e656835b0beab89a6f1 Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Mon, 29 Jun 2020 19:29:52 -0500 Subject: [PATCH 122/869] cleaner version of execution script which only needs 'make install' --- cython/CMakeLists.txt | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/cython/CMakeLists.txt b/cython/CMakeLists.txt index 2bfa8ae7c..75cbfea8a 100644 --- a/cython/CMakeLists.txt +++ b/cython/CMakeLists.txt @@ -45,9 +45,9 @@ if (GTSAM_INSTALL_CYTHON_TOOLBOX) install_cython_scripts("${PROJECT_SOURCE_DIR}/cython/gtsam_unstable" "${GTSAM_CYTHON_INSTALL_PATH}" "*.py") # Add the new make target command - add_custom_target(python-install - COMMAND ${PYTHON_EXECUTABLE} ${GTSAM_CYTHON_INSTALL_PATH}${GTSAM_BUILD_TAG}/setup.py install - DEPENDS gtsam - WORKING_DIRECTORY ${GTSAM_CYTHON_INSTALL_FULLPATH}) + install(CODE + "execute_process(COMMAND ${PYTHON_EXECUTABLE} setup.py install + WORKING_DIRECTORY ${GTSAM_CYTHON_INSTALL_FULLPATH})") + endif () From 16532bff37a5eb991f639d682ae733d2f27650b2 Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Mon, 29 Jun 2020 21:37:07 -0500 Subject: [PATCH 123/869] run setup.py after installing the gtsam_eigency module --- cython/CMakeLists.txt | 10 ++++++---- cython/gtsam_eigency/CMakeLists.txt | 22 ++++++++++++---------- 2 files changed, 18 insertions(+), 14 deletions(-) diff --git a/cython/CMakeLists.txt b/cython/CMakeLists.txt index 75cbfea8a..5569c0e47 100644 --- a/cython/CMakeLists.txt +++ b/cython/CMakeLists.txt @@ -44,10 +44,12 @@ if (GTSAM_INSTALL_CYTHON_TOOLBOX) install_cython_scripts("${PROJECT_SOURCE_DIR}/cython/gtsam" "${GTSAM_CYTHON_INSTALL_PATH}" "*.py") install_cython_scripts("${PROJECT_SOURCE_DIR}/cython/gtsam_unstable" "${GTSAM_CYTHON_INSTALL_PATH}" "*.py") - # Add the new make target command + # Adding custom function here so that gtsam_eigency is installed before + # the below execute_process runs. + install_gtsam_eigency(${PROJECT_BINARY_DIR}/cython/gtsam_eigency) + + # Automatically run the python installation via the setup.py install(CODE "execute_process(COMMAND ${PYTHON_EXECUTABLE} setup.py install - WORKING_DIRECTORY ${GTSAM_CYTHON_INSTALL_FULLPATH})") - - + WORKING_DIRECTORY ${GTSAM_CYTHON_INSTALL_FULLPATH})") endif () diff --git a/cython/gtsam_eigency/CMakeLists.txt b/cython/gtsam_eigency/CMakeLists.txt index da174d690..5ea1c337c 100644 --- a/cython/gtsam_eigency/CMakeLists.txt +++ b/cython/gtsam_eigency/CMakeLists.txt @@ -8,7 +8,7 @@ set(OUTPUT_DIR "${PROJECT_BINARY_DIR}/cython/gtsam_eigency") set(EIGENCY_INCLUDE_DIR ${OUTPUT_DIR}) # This is to make the build/cython/gtsam_eigency folder a python package -configure_file(__init__.py.in ${PROJECT_BINARY_DIR}/cython/gtsam_eigency/__init__.py) +configure_file(__init__.py.in ${OUTPUT_DIR}/__init__.py) # include eigency headers include_directories(${EIGENCY_INCLUDE_DIR}) @@ -38,12 +38,14 @@ add_custom_target(cythonize_eigency) add_dependencies(cythonize_eigency cythonize_eigency_conversions cythonize_eigency_core) # install -install(DIRECTORY ${CMAKE_CURRENT_SOURCE_DIR} - DESTINATION "${GTSAM_CYTHON_INSTALL_FULLPATH}" - PATTERN "CMakeLists.txt" EXCLUDE - PATTERN "__init__.py.in" EXCLUDE) -install(TARGETS cythonize_eigency_core cythonize_eigency_conversions - DESTINATION "${GTSAM_CYTHON_INSTALL_FULLPATH}/gtsam_eigency") -install(FILES ${OUTPUT_DIR}/conversions_api.h DESTINATION ${GTSAM_CYTHON_INSTALL_FULLPATH}/gtsam_eigency) -configure_file(__init__.py.in ${OUTPUT_DIR}/__init__.py) -install(FILES ${OUTPUT_DIR}/__init__.py DESTINATION ${GTSAM_CYTHON_INSTALL_FULLPATH}/gtsam_eigency) +function(install_gtsam_eigency source_directory) + install(DIRECTORY ${source_directory} + DESTINATION "${GTSAM_CYTHON_INSTALL_FULLPATH}" + PATTERN "CMakeLists.txt" EXCLUDE + PATTERN "__init__.py.in" EXCLUDE) + install(TARGETS cythonize_eigency_core cythonize_eigency_conversions + DESTINATION "${GTSAM_CYTHON_INSTALL_FULLPATH}/gtsam_eigency") + install(FILES ${source_directory}/conversions_api.h DESTINATION ${GTSAM_CYTHON_INSTALL_FULLPATH}/gtsam_eigency) + install(FILES ${source_directory}/__init__.py DESTINATION ${GTSAM_CYTHON_INSTALL_FULLPATH}/gtsam_eigency) + +endfunction() \ No newline at end of file From 83cbcd0bea250e5c314131d3cca832800c6b3899 Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Tue, 30 Jun 2020 13:13:04 -0500 Subject: [PATCH 124/869] capture stdout in python test [only for python3] --- cython/gtsam/tests/test_logging_optimizer.py | 12 +++++++++++- 1 file changed, 11 insertions(+), 1 deletion(-) diff --git a/cython/gtsam/tests/test_logging_optimizer.py b/cython/gtsam/tests/test_logging_optimizer.py index c857a6f7d..e7d9645b7 100644 --- a/cython/gtsam/tests/test_logging_optimizer.py +++ b/cython/gtsam/tests/test_logging_optimizer.py @@ -4,6 +4,8 @@ Author: Jing Wu and Frank Dellaert """ # pylint: disable=invalid-name +import io +import sys import unittest from datetime import datetime @@ -37,6 +39,14 @@ class TestOptimizeComet(GtsamTestCase): self.optimizer = gtsam.GaussNewtonOptimizer( graph, initial, self.params) + # setup output capture + self.capturedOutput = io.StringIO() + sys.stdout = self.capturedOutput + + def tearDown(self): + """Reset print capture.""" + sys.stdout = sys.__stdout__ + def test_simple_printing(self): """Test with a simple hook.""" @@ -76,4 +86,4 @@ class TestOptimizeComet(GtsamTestCase): self.gtsamAssertEquals(actual.atRot3(KEY), self.expected) if __name__ == "__main__": - unittest.main() \ No newline at end of file + unittest.main() From 192bf870af28156de5808074f6a45aa36e962410 Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Tue, 30 Jun 2020 13:16:09 -0500 Subject: [PATCH 125/869] newline added to end of CMake file --- cython/gtsam_eigency/CMakeLists.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/cython/gtsam_eigency/CMakeLists.txt b/cython/gtsam_eigency/CMakeLists.txt index 5ea1c337c..6cff534c5 100644 --- a/cython/gtsam_eigency/CMakeLists.txt +++ b/cython/gtsam_eigency/CMakeLists.txt @@ -48,4 +48,4 @@ function(install_gtsam_eigency source_directory) install(FILES ${source_directory}/conversions_api.h DESTINATION ${GTSAM_CYTHON_INSTALL_FULLPATH}/gtsam_eigency) install(FILES ${source_directory}/__init__.py DESTINATION ${GTSAM_CYTHON_INSTALL_FULLPATH}/gtsam_eigency) -endfunction() \ No newline at end of file +endfunction() From 9cbabb2cb6e8bf7407f67cfa8026cd227f069f5d Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Tue, 30 Jun 2020 20:45:55 -0500 Subject: [PATCH 126/869] Set high level Cython/Eigency variables to reduce duplication --- CMakeLists.txt | 13 +++++++------ 1 file changed, 7 insertions(+), 6 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index 2cbdbf00c..f8deebfcd 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -454,13 +454,14 @@ endif() if (GTSAM_INSTALL_CYTHON_TOOLBOX) set(GTSAM_INSTALL_CYTHON_TOOLBOX 1) # Set up cache options - set(GTSAM_CYTHON_INSTALL_PATH "" CACHE PATH "Cython toolbox destination, blank defaults to CMAKE_INSTALL_PREFIX/cython") - if(NOT GTSAM_CYTHON_INSTALL_PATH) - set(GTSAM_CYTHON_INSTALL_PATH "${CMAKE_INSTALL_PREFIX}/cython") - endif() + set(GTSAM_CYTHON_PATH "${PROJECT_BINARY_DIR}/cython" CACHE PATH "Cython source files directory path") # Cython install path appended with Build type (e.g. cython, cythonDebug, etc). - set(GTSAM_CYTHON_INSTALL_FULLPATH "${GTSAM_CYTHON_INSTALL_PATH}${GTSAM_BUILD_TAG}") - set(GTSAM_EIGENCY_INSTALL_PATH ${GTSAM_CYTHON_INSTALL_FULLPATH}/gtsam_eigency) + set(GTSAM_CYTHON_INSTALL_PATH "" CACHE PATH "Cython toolbox destination, blank defaults to PROJECT_BINARY_DIR/cython.build") + if(NOT GTSAM_CYTHON_INSTALL_PATH) + set(GTSAM_CYTHON_INSTALL_PATH "${PROJECT_BINARY_DIR}/cython.build${GTSAM_BUILD_TAG}") + endif() + set(GTSAM_EIGENCY_PATH ${GTSAM_CYTHON_PATH}/gtsam_eigency) + set(GTSAM_EIGENCY_INSTALL_PATH ${GTSAM_CYTHON_INSTALL_PATH}/gtsam_eigency) add_subdirectory(cython) else() set(GTSAM_INSTALL_CYTHON_TOOLBOX 0) # This will go into config.h From 06476c8ee745deca1b188730b4cf881d48a0f668 Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Tue, 30 Jun 2020 20:46:55 -0500 Subject: [PATCH 127/869] Create and use cython build directory --- cython/CMakeLists.txt | 14 +++++++++----- 1 file changed, 9 insertions(+), 5 deletions(-) diff --git a/cython/CMakeLists.txt b/cython/CMakeLists.txt index 5569c0e47..b0eb43c50 100644 --- a/cython/CMakeLists.txt +++ b/cython/CMakeLists.txt @@ -1,3 +1,6 @@ +# Create directory where cython build files will be placed +file(MAKE_DIRECTORY ${GTSAM_CYTHON_INSTALL_PATH}) + # Install cython components include(GtsamCythonWrap) @@ -5,7 +8,7 @@ include(GtsamCythonWrap) if (GTSAM_INSTALL_CYTHON_TOOLBOX) # build and include the eigency version of eigency add_subdirectory(gtsam_eigency) - include_directories(${PROJECT_BINARY_DIR}/cython/gtsam_eigency) + include_directories(${GTSAM_EIGENCY_PATH}) # Fix for error "C1128: number of sections exceeded object file format limit" if(MSVC) @@ -44,12 +47,13 @@ if (GTSAM_INSTALL_CYTHON_TOOLBOX) install_cython_scripts("${PROJECT_SOURCE_DIR}/cython/gtsam" "${GTSAM_CYTHON_INSTALL_PATH}" "*.py") install_cython_scripts("${PROJECT_SOURCE_DIR}/cython/gtsam_unstable" "${GTSAM_CYTHON_INSTALL_PATH}" "*.py") - # Adding custom function here so that gtsam_eigency is installed before - # the below execute_process runs. - install_gtsam_eigency(${PROJECT_BINARY_DIR}/cython/gtsam_eigency) + # Install gtsam_eigency. + # The paths are picked up directly from the parent CMakeLists.txt. + install_gtsam_eigency() # Automatically run the python installation via the setup.py install(CODE "execute_process(COMMAND ${PYTHON_EXECUTABLE} setup.py install - WORKING_DIRECTORY ${GTSAM_CYTHON_INSTALL_FULLPATH})") + WORKING_DIRECTORY ${GTSAM_CYTHON_INSTALL_PATH})") + endif () From c84060acea3321150f7fd5e652d0b8b8c5c90f53 Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Tue, 30 Jun 2020 20:47:32 -0500 Subject: [PATCH 128/869] Use the high level cython variables, improve install process --- cython/gtsam_eigency/CMakeLists.txt | 22 ++++++++++++---------- 1 file changed, 12 insertions(+), 10 deletions(-) diff --git a/cython/gtsam_eigency/CMakeLists.txt b/cython/gtsam_eigency/CMakeLists.txt index 6cff534c5..f64e45cdb 100644 --- a/cython/gtsam_eigency/CMakeLists.txt +++ b/cython/gtsam_eigency/CMakeLists.txt @@ -4,7 +4,7 @@ include(GtsamCythonWrap) # so that the cython-generated header "conversions_api.h" can be found when cythonizing eigency's core # and eigency's cython pxd headers can be found when cythonizing gtsam file(COPY "." DESTINATION ".") -set(OUTPUT_DIR "${PROJECT_BINARY_DIR}/cython/gtsam_eigency") +set(OUTPUT_DIR "${GTSAM_CYTHON_PATH}/gtsam_eigency") set(EIGENCY_INCLUDE_DIR ${OUTPUT_DIR}) # This is to make the build/cython/gtsam_eigency folder a python package @@ -16,8 +16,8 @@ include_directories(${EIGENCY_INCLUDE_DIR}) # Cythonize and build eigency message(STATUS "Cythonize and build eigency") # Important trick: use "../gtsam_eigency/conversions.pyx" to let cython know that the conversions module is -# a part of the gtsam_eigency package and generate the function call import_gtsam_igency__conversions() -# in conversions_api.h correctly!!! +# a part of the gtsam_eigency package and generate the function call import_gtsam_eigency__conversions() +# in conversions_api.h correctly! cythonize(cythonize_eigency_conversions "../gtsam_eigency/conversions.pyx" "conversions" "${OUTPUT_DIR}" "${EIGENCY_INCLUDE_DIR}" "" "" "") cythonize(cythonize_eigency_core "../gtsam_eigency/core.pyx" "core" @@ -38,14 +38,16 @@ add_custom_target(cythonize_eigency) add_dependencies(cythonize_eigency cythonize_eigency_conversions cythonize_eigency_core) # install -function(install_gtsam_eigency source_directory) - install(DIRECTORY ${source_directory} - DESTINATION "${GTSAM_CYTHON_INSTALL_FULLPATH}" +function(install_gtsam_eigency) + install(DIRECTORY ${GTSAM_EIGENCY_PATH} + DESTINATION "${GTSAM_CYTHON_INSTALL_PATH}" PATTERN "CMakeLists.txt" EXCLUDE - PATTERN "__init__.py.in" EXCLUDE) + PATTERN "__init__.py.in" EXCLUDE + PATTERN "*.dir" EXCLUDE + PATTERN "*.make" EXCLUDE) install(TARGETS cythonize_eigency_core cythonize_eigency_conversions - DESTINATION "${GTSAM_CYTHON_INSTALL_FULLPATH}/gtsam_eigency") - install(FILES ${source_directory}/conversions_api.h DESTINATION ${GTSAM_CYTHON_INSTALL_FULLPATH}/gtsam_eigency) - install(FILES ${source_directory}/__init__.py DESTINATION ${GTSAM_CYTHON_INSTALL_FULLPATH}/gtsam_eigency) + DESTINATION "${GTSAM_EIGENCY_INSTALL_PATH}") + install(FILES ${GTSAM_EIGENCY_PATH}/conversions_api.h DESTINATION ${GTSAM_EIGENCY_INSTALL_PATH}) + install(FILES ${GTSAM_EIGENCY_PATH}/__init__.py DESTINATION ${GTSAM_EIGENCY_INSTALL_PATH}) endfunction() From 7a725bf46af9fc069f4db772e4f191956a783e89 Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Tue, 30 Jun 2020 20:48:01 -0500 Subject: [PATCH 129/869] Remove redundant postfix checking since the postfix is already added at the top level --- cmake/GtsamCythonWrap.cmake | 75 ++++++------------------------------- 1 file changed, 12 insertions(+), 63 deletions(-) diff --git a/cmake/GtsamCythonWrap.cmake b/cmake/GtsamCythonWrap.cmake index 851f53cfe..3ce7f4454 100644 --- a/cmake/GtsamCythonWrap.cmake +++ b/cmake/GtsamCythonWrap.cmake @@ -184,35 +184,16 @@ function(install_cython_wrapped_library interface_header generated_files_path in # Split up filename to strip trailing '/' in GTSAM_CYTHON_INSTALL_PATH/subdirectory if there is one get_filename_component(location "${install_path}" PATH) get_filename_component(name "${install_path}" NAME) - message(STATUS "Installing Cython Toolbox to ${location}${GTSAM_BUILD_TAG}/${name}") #${GTSAM_CYTHON_INSTALL_FULLPATH}" + message(STATUS "Installing Cython Toolbox to ${location}/${name}") #${GTSAM_CYTHON_INSTALL_PATH}" - if(GTSAM_BUILD_TYPE_POSTFIXES) - foreach(build_type ${CMAKE_CONFIGURATION_TYPES}) - string(TOUPPER "${build_type}" build_type_upper) - if(${build_type_upper} STREQUAL "RELEASE") - set(build_type_tag "") # Don't create release mode tag on installed directory - else() - set(build_type_tag "${build_type}") - endif() - - install(DIRECTORY "${generated_files_path}/" DESTINATION "${location}${build_type_tag}/${name}" - CONFIGURATIONS "${build_type}" - PATTERN "build" EXCLUDE - PATTERN "CMakeFiles" EXCLUDE - PATTERN "Makefile" EXCLUDE - PATTERN "*.cmake" EXCLUDE - PATTERN "*.cpp" EXCLUDE - PATTERN "*.py" EXCLUDE) - endforeach() - else() - install(DIRECTORY "${generated_files_path}/" DESTINATION ${install_path} - PATTERN "build" EXCLUDE - PATTERN "CMakeFiles" EXCLUDE - PATTERN "Makefile" EXCLUDE - PATTERN "*.cmake" EXCLUDE - PATTERN "*.cpp" EXCLUDE - PATTERN "*.py" EXCLUDE) - endif() + install(DIRECTORY "${generated_files_path}/" DESTINATION ${install_path} + CONFIGURATIONS "${CMAKE_BUILD_TYPE}" + PATTERN "build" EXCLUDE + PATTERN "CMakeFiles" EXCLUDE + PATTERN "Makefile" EXCLUDE + PATTERN "*.cmake" EXCLUDE + PATTERN "*.cpp" EXCLUDE + PATTERN "*.py" EXCLUDE) endfunction() # Helper function to install Cython scripts and handle multiple build types where the scripts @@ -232,24 +213,9 @@ function(install_cython_scripts source_directory dest_directory patterns) foreach(pattern ${patterns}) list(APPEND patterns_args PATTERN "${pattern}") endforeach() - if(GTSAM_BUILD_TYPE_POSTFIXES) - foreach(build_type ${CMAKE_CONFIGURATION_TYPES}) - string(TOUPPER "${build_type}" build_type_upper) - if(${build_type_upper} STREQUAL "RELEASE") - set(build_type_tag "") # Don't create release mode tag on installed directory - else() - set(build_type_tag "${build_type}") - endif() - # Split up filename to strip trailing '/' in GTSAM_CYTHON_INSTALL_PATH if there is one - get_filename_component(location "${dest_directory}" PATH) - get_filename_component(name "${dest_directory}" NAME) - install(DIRECTORY "${source_directory}" DESTINATION "${location}/${name}${build_type_tag}" CONFIGURATIONS "${build_type}" - FILES_MATCHING ${patterns_args} PATTERN "${exclude_patterns}" EXCLUDE) - endforeach() - else() - install(DIRECTORY "${source_directory}" DESTINATION "${dest_directory}" FILES_MATCHING ${patterns_args} PATTERN "${exclude_patterns}" EXCLUDE) - endif() + install(DIRECTORY "${source_directory}" DESTINATION "${dest_directory}" CONFIGURATIONS "${CMAKE_BUILD_TYPE}" + FILES_MATCHING ${patterns_args} PATTERN "${exclude_patterns}" EXCLUDE) endfunction() # Helper function to install specific files and handle multiple build types where the scripts @@ -259,22 +225,5 @@ endfunction() # source_files: The source files to be installed. # dest_directory: The destination directory to install to. function(install_cython_files source_files dest_directory) - - if(GTSAM_BUILD_TYPE_POSTFIXES) - foreach(build_type ${CMAKE_CONFIGURATION_TYPES}) - string(TOUPPER "${build_type}" build_type_upper) - if(${build_type_upper} STREQUAL "RELEASE") - set(build_type_tag "") # Don't create release mode tag on installed directory - else() - set(build_type_tag "${build_type}") - endif() - # Split up filename to strip trailing '/' in GTSAM_CYTHON_INSTALL_PATH if there is one - get_filename_component(location "${dest_directory}" PATH) - get_filename_component(name "${dest_directory}" NAME) - install(FILES "${source_files}" DESTINATION "${location}/${name}${build_type_tag}" CONFIGURATIONS "${build_type}") - endforeach() - else() - install(FILES "${source_files}" DESTINATION "${dest_directory}") - endif() - + install(FILES "${source_files}" DESTINATION "${dest_directory}" CONFIGURATIONS "${CMAKE_BUILD_TYPE}") endfunction() From 54f2acd521b0531c9a727ee585cae7afcf5ef2bd Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Tue, 30 Jun 2020 20:57:31 -0500 Subject: [PATCH 130/869] updated cython wrapper README --- cython/README.md | 89 +++++++++++++++++++++--------------------------- 1 file changed, 38 insertions(+), 51 deletions(-) diff --git a/cython/README.md b/cython/README.md index bc6e346d9..0c59915a0 100644 --- a/cython/README.md +++ b/cython/README.md @@ -1,33 +1,36 @@ # Python Wrapper -This is the Cython/Python wrapper around the GTSAM C++ library. +This is the Python wrapper around the GTSAM C++ library. We use Cython to generate the bindings to the underlying C++ code. + +## Requirements + +- If you want to build the gtsam python library for a specific python version (eg 2.7), use the `-DGTSAM_PYTHON_VERSION=2.7` option when running `cmake` otherwise the default interpreter will be used. + - If the interpreter is inside an environment (such as an anaconda environment or virtualenv environment) then the environment should be active while building gtsam. +- This wrapper needs `Cython(>=0.25.2)`, `backports_abc(>=0.5)`, and `numpy(>=1.11.0)`. These can be installed as follows: + + ```bash + pip install -r /cython/requirements.txt + ``` + +- For compatibility with gtsam's Eigen version, it contains its own cloned version of [Eigency](https://github.com/wouterboomsma/eigency.git), +named `gtsam_eigency`, to interface between C++'s Eigen and Python's numpy. ## Install -- if you want to build the gtsam python library for a specific python version (eg 2.7), use the `-DGTSAM_PYTHON_VERSION=2.7` option when running `cmake` otherwise the default interpreter will be used. - - If the interpreter is inside an environment (such as an anaconda environment or virtualenv environment) then the environment should be active while building gtsam. -- This wrapper needs Cython(>=0.25.2), backports_abc>=0.5, and numpy. These can be installed as follows: - -```bash - pip install -r /cython/requirements.txt -``` - -- For compatibility with gtsam's Eigen version, it contains its own cloned version of [Eigency](https://github.com/wouterboomsma/eigency.git), -named **gtsam_eigency**, to interface between C++'s Eigen and Python's numpy. - -- Build and install gtsam using cmake with `GTSAM_INSTALL_CYTHON_TOOLBOX` enabled. -The wrapped module will be installed to `GTSAM_CYTHON_INSTALL_PATH`, which is -by default: `/cython` +- Run cmake with the `GTSAM_INSTALL_CYTHON_TOOLBOX` cmake flag enabled to configure building the wrapper. The wrapped module will be built and copied to the directory defined by `GTSAM_CYTHON_INSTALL_PATH`, which is by default: `/cython.build`. - To use the library without installing system-wide: modify your `PYTHONPATH` to include the `GTSAM_CYTHON_INSTALL_PATH`: -```bash -export PYTHONPATH=$PYTHONPATH: -``` -- To install system-wide: run `make install` then navigate to `GTSAM_CYTHON_INSTALL_PATH` and run `python setup.py install` - - (the same command can be used to install into a virtual environment if it is active) - - note: if you don't want gtsam to install to a system directory such as `/usr/local`, pass `-DCMAKE_INSTALL_PREFIX="./install"` to cmake to install gtsam to a subdirectory of the build directory. - - if you run `setup.py` from the build directory rather than the installation directory, the script will warn you with the message: `setup.py is being run from an unexpected location`. - Before `make install` is run, not all the components of the package have been copied across, so running `setup.py` from the build directory would result in an incomplete package. + + ```bash + export PYTHONPATH=$PYTHONPATH: + ``` + +- Build GTSAM and the wrapper with `make`. + +- To install system-wide, simply run `make install`. + - The same command can be used to install into a virtual environment if it is active. + - **NOTE**: if you don't want gtsam to install to a system directory such as `/usr/local`, pass `-DCMAKE_INSTALL_PREFIX="./install"` to cmake to install gtsam to a subdirectory of the build directory. + - If you run `setup.py` from the build directory rather than the installation directory, the script will warn you with the message: `setup.py is being run from an unexpected location`. ## Unit Tests @@ -47,48 +50,32 @@ See the tests for examples. - Vector/Matrix: + GTSAM expects double-precision floating point vectors and matrices. - Hence, you should pass numpy matrices with dtype=float, or 'float64'. + Hence, you should pass numpy matrices with `dtype=float`, or `float64`. + Also, GTSAM expects *column-major* matrices, unlike the default storage scheme in numpy. Hence, you should pass column-major matrices to gtsam using the flag order='F'. And you always get column-major matrices back. - For more details, see: https://github.com/wouterboomsma/eigency#storage-layout---why-arrays-are-sometimes-transposed - + Passing row-major matrices of different dtype, e.g. 'int', will also work + For more details, see [this link](https://github.com/wouterboomsma/eigency#storage-layout---why-arrays-are-sometimes-transposed). + + Passing row-major matrices of different dtype, e.g. `int`, will also work as the wrapper converts them to column-major and dtype float for you, using numpy.array.astype(float, order='F', copy=False). However, this will result a copy if your matrix is not in the expected type and storage order. - Inner namespace: Classes in inner namespace will be prefixed by _ in Python. -Examples: noiseModel_Gaussian, noiseModel_mEstimator_Tukey + + Examples: `noiseModel_Gaussian`, `noiseModel_mEstimator_Tukey` - Casting from a base class to a derive class must be done explicitly. -Examples: -```Python - noiseBase = factor.noiseModel() - noiseGaussian = dynamic_cast_noiseModel_Gaussian_noiseModel_Base(noiseBase) -``` -## Wrapping Your Own Project That Uses GTSAM + Examples: + ```python + noiseBase = factor.noiseModel() + noiseGaussian = dynamic_cast_noiseModel_Gaussian_noiseModel_Base(noiseBase) + ``` -- Set PYTHONPATH to include ${GTSAM_CYTHON_INSTALL_PATH} - + so that it can find gtsam Cython header: gtsam/gtsam.pxd +## Wrapping Custom GTSAM-based Project -- In your CMakeList.txt -```cmake -find_package(GTSAM REQUIRED) # Make sure gtsam's install folder is in your PATH -set(CMAKE_MODULE_PATH "${CMAKE_MODULE_PATH}" "${GTSAM_DIR}/../GTSAMCMakeTools") - -# Wrap -include(GtsamCythonWrap) -include_directories(${GTSAM_EIGENCY_INSTALL_PATH}) -wrap_and_install_library_cython("your_project_interface.h" - "from gtsam.gtsam cimport *" # extra import of gtsam/gtsam.pxd Cython header - "your_install_path" - "libraries_to_link_with_the_cython_module" - "dependencies_which_need_to_be_built_before_the_wrapper" - ) -#Optional: install_cython_scripts and install_cython_files. See GtsamCythonWrap.cmake. -``` +Please refer to the template project and the corresponding tutorial available [here](https://github.com/borglab/gtsam-project-python). ## KNOWN ISSUES From 8859b963a24db117fc51ea9532c310b6721c0fc1 Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Wed, 1 Jul 2020 12:13:53 -0500 Subject: [PATCH 131/869] In-place cython build Build everything inside the build/cython{BuildType} directory directly, so we can bypass the `make install` step and introduce the `make python-install` step which allows cmake to handle all dependencies. --- CMakeLists.txt | 8 ++--- cmake/GtsamCythonWrap.cmake | 6 ++-- cython/CMakeLists.txt | 51 ++++++++++++++--------------- cython/gtsam_eigency/CMakeLists.txt | 17 +--------- 4 files changed, 31 insertions(+), 51 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index f8deebfcd..a9966f5d3 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -454,15 +454,13 @@ endif() if (GTSAM_INSTALL_CYTHON_TOOLBOX) set(GTSAM_INSTALL_CYTHON_TOOLBOX 1) # Set up cache options - set(GTSAM_CYTHON_PATH "${PROJECT_BINARY_DIR}/cython" CACHE PATH "Cython source files directory path") # Cython install path appended with Build type (e.g. cython, cythonDebug, etc). - set(GTSAM_CYTHON_INSTALL_PATH "" CACHE PATH "Cython toolbox destination, blank defaults to PROJECT_BINARY_DIR/cython.build") + set(GTSAM_CYTHON_INSTALL_PATH "" CACHE PATH "Cython toolbox destination, blank defaults to PROJECT_BINARY_DIR/cython") if(NOT GTSAM_CYTHON_INSTALL_PATH) - set(GTSAM_CYTHON_INSTALL_PATH "${PROJECT_BINARY_DIR}/cython.build${GTSAM_BUILD_TAG}") + set(GTSAM_CYTHON_INSTALL_PATH "${PROJECT_BINARY_DIR}/cython${GTSAM_BUILD_TAG}" CACHE PATH "") endif() - set(GTSAM_EIGENCY_PATH ${GTSAM_CYTHON_PATH}/gtsam_eigency) set(GTSAM_EIGENCY_INSTALL_PATH ${GTSAM_CYTHON_INSTALL_PATH}/gtsam_eigency) - add_subdirectory(cython) + add_subdirectory(cython ${GTSAM_CYTHON_INSTALL_PATH}) else() set(GTSAM_INSTALL_CYTHON_TOOLBOX 0) # This will go into config.h endif() diff --git a/cmake/GtsamCythonWrap.cmake b/cmake/GtsamCythonWrap.cmake index 3ce7f4454..797745acf 100644 --- a/cmake/GtsamCythonWrap.cmake +++ b/cmake/GtsamCythonWrap.cmake @@ -41,9 +41,9 @@ execute_process(COMMAND "${PYTHON_EXECUTABLE}" "-c" function(wrap_and_install_library_cython interface_header extra_imports install_path libs dependencies) # Paths for generated files get_filename_component(module_name "${interface_header}" NAME_WE) - set(generated_files_path "${PROJECT_BINARY_DIR}/cython/${module_name}") + set(generated_files_path "${GTSAM_CYTHON_INSTALL_PATH}/${module_name}") wrap_library_cython("${interface_header}" "${generated_files_path}" "${extra_imports}" "${libs}" "${dependencies}") - install_cython_wrapped_library("${interface_header}" "${generated_files_path}" "${install_path}") + # install_cython_wrapped_library("${interface_header}" "${generated_files_path}" "${install_path}") endfunction() function(set_up_required_cython_packages) @@ -214,7 +214,7 @@ function(install_cython_scripts source_directory dest_directory patterns) list(APPEND patterns_args PATTERN "${pattern}") endforeach() - install(DIRECTORY "${source_directory}" DESTINATION "${dest_directory}" CONFIGURATIONS "${CMAKE_BUILD_TYPE}" + file(COPY "${source_directory}" DESTINATION "${dest_directory}" FILES_MATCHING ${patterns_args} PATTERN "${exclude_patterns}" EXCLUDE) endfunction() diff --git a/cython/CMakeLists.txt b/cython/CMakeLists.txt index b0eb43c50..74725c463 100644 --- a/cython/CMakeLists.txt +++ b/cython/CMakeLists.txt @@ -1,21 +1,37 @@ -# Create directory where cython build files will be placed -file(MAKE_DIRECTORY ${GTSAM_CYTHON_INSTALL_PATH}) - # Install cython components include(GtsamCythonWrap) # Create the cython toolbox for the gtsam library if (GTSAM_INSTALL_CYTHON_TOOLBOX) + # Add the new make target command + add_custom_target(python-install + COMMAND ${PYTHON_EXECUTABLE} ${GTSAM_CYTHON_INSTALL_PATH}/setup.py install + WORKING_DIRECTORY ${GTSAM_CYTHON_INSTALL_FULLPATH}) + # build and include the eigency version of eigency add_subdirectory(gtsam_eigency) - include_directories(${GTSAM_EIGENCY_PATH}) + include_directories(${GTSAM_EIGENCY_INSTALL_PATH}) # Fix for error "C1128: number of sections exceeded object file format limit" if(MSVC) add_compile_options(/bigobj) endif() - # wrap gtsam + # First set up all the package related files. + # This also ensures the below wrap operations work correctly. + set(CYTHON_INSTALL_REQUIREMENTS_FILE "${PROJECT_SOURCE_DIR}/cython/requirements.txt") + + # Install the custom-generated __init__.py + # This makes the cython (sub-)directories into python packages, so gtsam can be found while wrapping gtsam_unstable + configure_file(${PROJECT_SOURCE_DIR}/cython/gtsam/__init__.py ${GTSAM_CYTHON_INSTALL_PATH}/gtsam/__init__.py COPYONLY) + configure_file(${PROJECT_SOURCE_DIR}/cython/gtsam_unstable/__init__.py ${GTSAM_CYTHON_INSTALL_PATH}/gtsam_unstable/__init__.py COPYONLY) + configure_file(${PROJECT_SOURCE_DIR}/cython/setup.py.in ${GTSAM_CYTHON_INSTALL_PATH}/setup.py) + install_cython_files("${PROJECT_BINARY_DIR}/cython/setup.py" "${GTSAM_CYTHON_INSTALL_PATH}") + # install scripts and tests + install_cython_scripts("${PROJECT_SOURCE_DIR}/cython/gtsam" "${GTSAM_CYTHON_INSTALL_PATH}" "*.py") + install_cython_scripts("${PROJECT_SOURCE_DIR}/cython/gtsam_unstable" "${GTSAM_CYTHON_INSTALL_PATH}" "*.py") + + # Wrap gtsam add_custom_target(gtsam_header DEPENDS "../gtsam.h") wrap_and_install_library_cython("../gtsam.h" # interface_header "" # extra imports @@ -23,8 +39,9 @@ if (GTSAM_INSTALL_CYTHON_TOOLBOX) gtsam # library to link with "wrap;cythonize_eigency;gtsam;gtsam_header" # dependencies which need to be built before wrapping ) + add_dependencies(python-install gtsam gtsam_header) - # wrap gtsam_unstable + # Wrap gtsam_unstable if(GTSAM_BUILD_UNSTABLE) add_custom_target(gtsam_unstable_header DEPENDS "../gtsam_unstable/gtsam_unstable.h") wrap_and_install_library_cython("../gtsam_unstable/gtsam_unstable.h" # interface_header @@ -33,27 +50,7 @@ if (GTSAM_INSTALL_CYTHON_TOOLBOX) gtsam_unstable # library to link with "gtsam_unstable;gtsam_unstable_header;cythonize_gtsam" # dependencies to be built before wrapping ) + add_dependencies(python-install gtsam_unstable gtsam_unstable_header) endif() - set(CYTHON_INSTALL_REQUIREMENTS_FILE "${PROJECT_SOURCE_DIR}/cython/requirements.txt") - - # Install the custom-generated __init__.py - # This is to make the build/cython/gtsam folder a python package, so gtsam can be found while wrapping gtsam_unstable - configure_file(${PROJECT_SOURCE_DIR}/cython/gtsam/__init__.py ${PROJECT_BINARY_DIR}/cython/gtsam/__init__.py COPYONLY) - configure_file(${PROJECT_SOURCE_DIR}/cython/gtsam_unstable/__init__.py ${PROJECT_BINARY_DIR}/cython/gtsam_unstable/__init__.py COPYONLY) - configure_file(${PROJECT_SOURCE_DIR}/cython/setup.py.in ${PROJECT_BINARY_DIR}/cython/setup.py) - install_cython_files("${PROJECT_BINARY_DIR}/cython/setup.py" "${GTSAM_CYTHON_INSTALL_PATH}") - # install scripts and tests - install_cython_scripts("${PROJECT_SOURCE_DIR}/cython/gtsam" "${GTSAM_CYTHON_INSTALL_PATH}" "*.py") - install_cython_scripts("${PROJECT_SOURCE_DIR}/cython/gtsam_unstable" "${GTSAM_CYTHON_INSTALL_PATH}" "*.py") - - # Install gtsam_eigency. - # The paths are picked up directly from the parent CMakeLists.txt. - install_gtsam_eigency() - - # Automatically run the python installation via the setup.py - install(CODE - "execute_process(COMMAND ${PYTHON_EXECUTABLE} setup.py install - WORKING_DIRECTORY ${GTSAM_CYTHON_INSTALL_PATH})") - endif () diff --git a/cython/gtsam_eigency/CMakeLists.txt b/cython/gtsam_eigency/CMakeLists.txt index f64e45cdb..7c215e89c 100644 --- a/cython/gtsam_eigency/CMakeLists.txt +++ b/cython/gtsam_eigency/CMakeLists.txt @@ -4,7 +4,7 @@ include(GtsamCythonWrap) # so that the cython-generated header "conversions_api.h" can be found when cythonizing eigency's core # and eigency's cython pxd headers can be found when cythonizing gtsam file(COPY "." DESTINATION ".") -set(OUTPUT_DIR "${GTSAM_CYTHON_PATH}/gtsam_eigency") +set(OUTPUT_DIR "${GTSAM_CYTHON_INSTALL_PATH}/gtsam_eigency") set(EIGENCY_INCLUDE_DIR ${OUTPUT_DIR}) # This is to make the build/cython/gtsam_eigency folder a python package @@ -36,18 +36,3 @@ target_include_directories(cythonize_eigency_core PUBLIC add_dependencies(cythonize_eigency_core cythonize_eigency_conversions) add_custom_target(cythonize_eigency) add_dependencies(cythonize_eigency cythonize_eigency_conversions cythonize_eigency_core) - -# install -function(install_gtsam_eigency) - install(DIRECTORY ${GTSAM_EIGENCY_PATH} - DESTINATION "${GTSAM_CYTHON_INSTALL_PATH}" - PATTERN "CMakeLists.txt" EXCLUDE - PATTERN "__init__.py.in" EXCLUDE - PATTERN "*.dir" EXCLUDE - PATTERN "*.make" EXCLUDE) - install(TARGETS cythonize_eigency_core cythonize_eigency_conversions - DESTINATION "${GTSAM_EIGENCY_INSTALL_PATH}") - install(FILES ${GTSAM_EIGENCY_PATH}/conversions_api.h DESTINATION ${GTSAM_EIGENCY_INSTALL_PATH}) - install(FILES ${GTSAM_EIGENCY_PATH}/__init__.py DESTINATION ${GTSAM_EIGENCY_INSTALL_PATH}) - -endfunction() From 74591eece60b45342a865474fef452a7683430c7 Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Wed, 1 Jul 2020 14:36:16 -0500 Subject: [PATCH 132/869] fixed CYTHON_INSTALL_PATH cmake variable wrt cache --- CMakeLists.txt | 6 ++---- 1 file changed, 2 insertions(+), 4 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index a9966f5d3..f5b9c5e22 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -455,10 +455,8 @@ if (GTSAM_INSTALL_CYTHON_TOOLBOX) set(GTSAM_INSTALL_CYTHON_TOOLBOX 1) # Set up cache options # Cython install path appended with Build type (e.g. cython, cythonDebug, etc). - set(GTSAM_CYTHON_INSTALL_PATH "" CACHE PATH "Cython toolbox destination, blank defaults to PROJECT_BINARY_DIR/cython") - if(NOT GTSAM_CYTHON_INSTALL_PATH) - set(GTSAM_CYTHON_INSTALL_PATH "${PROJECT_BINARY_DIR}/cython${GTSAM_BUILD_TAG}" CACHE PATH "") - endif() + # This does not override custom values set from the command line + set(GTSAM_CYTHON_INSTALL_PATH "${PROJECT_BINARY_DIR}/cython${GTSAM_BUILD_TAG}" CACHE PATH "Cython toolbox destination, blank defaults to PROJECT_BINARY_DIR/cython") set(GTSAM_EIGENCY_INSTALL_PATH ${GTSAM_CYTHON_INSTALL_PATH}/gtsam_eigency) add_subdirectory(cython ${GTSAM_CYTHON_INSTALL_PATH}) else() From 59968fddc5d7e0ded0102a8ac310602b9dd5c4b9 Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Wed, 1 Jul 2020 14:36:57 -0500 Subject: [PATCH 133/869] Python Wrapper CMake update - Added python-install target variable for easy updating. - Fixed/Added all dependencies so that everything is built automatically. - Removed unnecessary install commands --- cmake/GtsamCythonWrap.cmake | 26 +++----------------------- cython/CMakeLists.txt | 14 ++++++++------ cython/gtsam_eigency/CMakeLists.txt | 2 ++ 3 files changed, 13 insertions(+), 29 deletions(-) diff --git a/cmake/GtsamCythonWrap.cmake b/cmake/GtsamCythonWrap.cmake index 797745acf..7597834c9 100644 --- a/cmake/GtsamCythonWrap.cmake +++ b/cmake/GtsamCythonWrap.cmake @@ -43,7 +43,6 @@ function(wrap_and_install_library_cython interface_header extra_imports install_ get_filename_component(module_name "${interface_header}" NAME_WE) set(generated_files_path "${GTSAM_CYTHON_INSTALL_PATH}/${module_name}") wrap_library_cython("${interface_header}" "${generated_files_path}" "${extra_imports}" "${libs}" "${dependencies}") - # install_cython_wrapped_library("${interface_header}" "${generated_files_path}" "${install_path}") endfunction() function(set_up_required_cython_packages) @@ -170,32 +169,13 @@ function(wrap_library_cython interface_header generated_files_path extra_imports cythonize(cythonize_${module_name} ${generated_pyx} ${module_name} ${generated_files_path} "${include_dirs}" "${libs}" ${interface_header} cython_wrap_${module_name}_pyx) + add_dependencies(${python_install_target} cython_wrap_${module_name}_pyx) + # distclean add_custom_target(wrap_${module_name}_cython_distclean COMMAND cmake -E remove_directory ${generated_files_path}) endfunction() -# Internal function that installs a wrap toolbox -function(install_cython_wrapped_library interface_header generated_files_path install_path) - get_filename_component(module_name "${interface_header}" NAME_WE) - - # NOTE: only installs .pxd and .pyx and binary files (not .cpp) - the trailing slash on the directory name - # here prevents creating the top-level module name directory in the destination. - # Split up filename to strip trailing '/' in GTSAM_CYTHON_INSTALL_PATH/subdirectory if there is one - get_filename_component(location "${install_path}" PATH) - get_filename_component(name "${install_path}" NAME) - message(STATUS "Installing Cython Toolbox to ${location}/${name}") #${GTSAM_CYTHON_INSTALL_PATH}" - - install(DIRECTORY "${generated_files_path}/" DESTINATION ${install_path} - CONFIGURATIONS "${CMAKE_BUILD_TYPE}" - PATTERN "build" EXCLUDE - PATTERN "CMakeFiles" EXCLUDE - PATTERN "Makefile" EXCLUDE - PATTERN "*.cmake" EXCLUDE - PATTERN "*.cpp" EXCLUDE - PATTERN "*.py" EXCLUDE) -endfunction() - # Helper function to install Cython scripts and handle multiple build types where the scripts # should be installed to all build type toolboxes # @@ -225,5 +205,5 @@ endfunction() # source_files: The source files to be installed. # dest_directory: The destination directory to install to. function(install_cython_files source_files dest_directory) - install(FILES "${source_files}" DESTINATION "${dest_directory}" CONFIGURATIONS "${CMAKE_BUILD_TYPE}") + file(COPY "${source_files}" DESTINATION "${dest_directory}") endfunction() diff --git a/cython/CMakeLists.txt b/cython/CMakeLists.txt index 74725c463..ce93120c2 100644 --- a/cython/CMakeLists.txt +++ b/cython/CMakeLists.txt @@ -4,7 +4,8 @@ include(GtsamCythonWrap) # Create the cython toolbox for the gtsam library if (GTSAM_INSTALL_CYTHON_TOOLBOX) # Add the new make target command - add_custom_target(python-install + set(python_install_target python-install) + add_custom_target(${python_install_target} COMMAND ${PYTHON_EXECUTABLE} ${GTSAM_CYTHON_INSTALL_PATH}/setup.py install WORKING_DIRECTORY ${GTSAM_CYTHON_INSTALL_FULLPATH}) @@ -27,9 +28,6 @@ if (GTSAM_INSTALL_CYTHON_TOOLBOX) configure_file(${PROJECT_SOURCE_DIR}/cython/gtsam_unstable/__init__.py ${GTSAM_CYTHON_INSTALL_PATH}/gtsam_unstable/__init__.py COPYONLY) configure_file(${PROJECT_SOURCE_DIR}/cython/setup.py.in ${GTSAM_CYTHON_INSTALL_PATH}/setup.py) install_cython_files("${PROJECT_BINARY_DIR}/cython/setup.py" "${GTSAM_CYTHON_INSTALL_PATH}") - # install scripts and tests - install_cython_scripts("${PROJECT_SOURCE_DIR}/cython/gtsam" "${GTSAM_CYTHON_INSTALL_PATH}" "*.py") - install_cython_scripts("${PROJECT_SOURCE_DIR}/cython/gtsam_unstable" "${GTSAM_CYTHON_INSTALL_PATH}" "*.py") # Wrap gtsam add_custom_target(gtsam_header DEPENDS "../gtsam.h") @@ -39,7 +37,7 @@ if (GTSAM_INSTALL_CYTHON_TOOLBOX) gtsam # library to link with "wrap;cythonize_eigency;gtsam;gtsam_header" # dependencies which need to be built before wrapping ) - add_dependencies(python-install gtsam gtsam_header) + add_dependencies(${python_install_target} gtsam gtsam_header) # Wrap gtsam_unstable if(GTSAM_BUILD_UNSTABLE) @@ -50,7 +48,11 @@ if (GTSAM_INSTALL_CYTHON_TOOLBOX) gtsam_unstable # library to link with "gtsam_unstable;gtsam_unstable_header;cythonize_gtsam" # dependencies to be built before wrapping ) - add_dependencies(python-install gtsam_unstable gtsam_unstable_header) + add_dependencies(${python_install_target} gtsam_unstable gtsam_unstable_header) endif() + # install scripts and tests + install_cython_scripts("${PROJECT_SOURCE_DIR}/cython/gtsam" "${GTSAM_CYTHON_INSTALL_PATH}" "*.py") + install_cython_scripts("${PROJECT_SOURCE_DIR}/cython/gtsam_unstable" "${GTSAM_CYTHON_INSTALL_PATH}" "*.py") + endif () diff --git a/cython/gtsam_eigency/CMakeLists.txt b/cython/gtsam_eigency/CMakeLists.txt index 7c215e89c..663ea0a32 100644 --- a/cython/gtsam_eigency/CMakeLists.txt +++ b/cython/gtsam_eigency/CMakeLists.txt @@ -36,3 +36,5 @@ target_include_directories(cythonize_eigency_core PUBLIC add_dependencies(cythonize_eigency_core cythonize_eigency_conversions) add_custom_target(cythonize_eigency) add_dependencies(cythonize_eigency cythonize_eigency_conversions cythonize_eigency_core) + +add_dependencies(${python_install_target} cythonize_eigency) From a6908cd1cb003ee184d0018a559075b319d65afe Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Wed, 1 Jul 2020 16:23:24 -0500 Subject: [PATCH 134/869] removed unneeded install commands and updated README --- cmake/GtsamCythonWrap.cmake | 10 ----- cython/CMakeLists.txt | 1 - cython/README.md | 83 ++++++++++++++++++++----------------- 3 files changed, 44 insertions(+), 50 deletions(-) diff --git a/cmake/GtsamCythonWrap.cmake b/cmake/GtsamCythonWrap.cmake index 7597834c9..c155cbbd8 100644 --- a/cmake/GtsamCythonWrap.cmake +++ b/cmake/GtsamCythonWrap.cmake @@ -197,13 +197,3 @@ function(install_cython_scripts source_directory dest_directory patterns) file(COPY "${source_directory}" DESTINATION "${dest_directory}" FILES_MATCHING ${patterns_args} PATTERN "${exclude_patterns}" EXCLUDE) endfunction() - -# Helper function to install specific files and handle multiple build types where the scripts -# should be installed to all build type toolboxes -# -# Arguments: -# source_files: The source files to be installed. -# dest_directory: The destination directory to install to. -function(install_cython_files source_files dest_directory) - file(COPY "${source_files}" DESTINATION "${dest_directory}") -endfunction() diff --git a/cython/CMakeLists.txt b/cython/CMakeLists.txt index ce93120c2..65a9e9c62 100644 --- a/cython/CMakeLists.txt +++ b/cython/CMakeLists.txt @@ -27,7 +27,6 @@ if (GTSAM_INSTALL_CYTHON_TOOLBOX) configure_file(${PROJECT_SOURCE_DIR}/cython/gtsam/__init__.py ${GTSAM_CYTHON_INSTALL_PATH}/gtsam/__init__.py COPYONLY) configure_file(${PROJECT_SOURCE_DIR}/cython/gtsam_unstable/__init__.py ${GTSAM_CYTHON_INSTALL_PATH}/gtsam_unstable/__init__.py COPYONLY) configure_file(${PROJECT_SOURCE_DIR}/cython/setup.py.in ${GTSAM_CYTHON_INSTALL_PATH}/setup.py) - install_cython_files("${PROJECT_BINARY_DIR}/cython/setup.py" "${GTSAM_CYTHON_INSTALL_PATH}") # Wrap gtsam add_custom_target(gtsam_header DEPENDS "../gtsam.h") diff --git a/cython/README.md b/cython/README.md index 0c59915a0..f69b7a5a6 100644 --- a/cython/README.md +++ b/cython/README.md @@ -4,43 +4,48 @@ This is the Python wrapper around the GTSAM C++ library. We use Cython to genera ## Requirements -- If you want to build the gtsam python library for a specific python version (eg 2.7), use the `-DGTSAM_PYTHON_VERSION=2.7` option when running `cmake` otherwise the default interpreter will be used. - - If the interpreter is inside an environment (such as an anaconda environment or virtualenv environment) then the environment should be active while building gtsam. +- If you want to build the GTSAM python library for a specific python version (eg 3.6), + use the `-DGTSAM_PYTHON_VERSION=3.6` option when running `cmake` otherwise the default interpreter will be used. +- If the interpreter is inside an environment (such as an anaconda environment or virtualenv environment), + then the environment should be active while building GTSAM. - This wrapper needs `Cython(>=0.25.2)`, `backports_abc(>=0.5)`, and `numpy(>=1.11.0)`. These can be installed as follows: ```bash pip install -r /cython/requirements.txt ``` -- For compatibility with gtsam's Eigen version, it contains its own cloned version of [Eigency](https://github.com/wouterboomsma/eigency.git), -named `gtsam_eigency`, to interface between C++'s Eigen and Python's numpy. +- For compatibility with GTSAM's Eigen version, it contains its own cloned version of [Eigency](https://github.com/wouterboomsma/eigency.git), + named `gtsam_eigency`, to interface between C++'s Eigen and Python's numpy. ## Install -- Run cmake with the `GTSAM_INSTALL_CYTHON_TOOLBOX` cmake flag enabled to configure building the wrapper. The wrapped module will be built and copied to the directory defined by `GTSAM_CYTHON_INSTALL_PATH`, which is by default: `/cython.build`. - -- To use the library without installing system-wide: modify your `PYTHONPATH` to include the `GTSAM_CYTHON_INSTALL_PATH`: - - ```bash - export PYTHONPATH=$PYTHONPATH: - ``` +- Run cmake with the `GTSAM_INSTALL_CYTHON_TOOLBOX` cmake flag enabled to configure building the wrapper. The wrapped module will be built and copied to the directory defined by `GTSAM_CYTHON_INSTALL_PATH`, which is by default `/cython` in Release mode and `/cython` for other modes. - Build GTSAM and the wrapper with `make`. -- To install system-wide, simply run `make install`. - - The same command can be used to install into a virtual environment if it is active. - - **NOTE**: if you don't want gtsam to install to a system directory such as `/usr/local`, pass `-DCMAKE_INSTALL_PREFIX="./install"` to cmake to install gtsam to a subdirectory of the build directory. - - If you run `setup.py` from the build directory rather than the installation directory, the script will warn you with the message: `setup.py is being run from an unexpected location`. +- To install, simply run `make python-install`. + - The same command can be used to install into a virtual environment if it is active. + - **NOTE**: if you don't want GTSAM to install to a system directory such as `/usr/local`, pass `-DCMAKE_INSTALL_PREFIX="./install"` to cmake to install GTSAM to a subdirectory of the build directory. + +- You can also directly run `make python-install` without running `make`, and it will compile all the dependencies accordingly. ## Unit Tests The Cython toolbox also has a small set of unit tests located in the test directory. To run them: -```bash - cd - python -m unittest discover -``` + ```bash + cd + python -m unittest discover + ``` + +## Utils + +TODO + +## Examples + +TODO ## Writing Your Own Scripts @@ -49,25 +54,27 @@ See the tests for examples. ### Some Important Notes: - Vector/Matrix: - + GTSAM expects double-precision floating point vectors and matrices. + + - GTSAM expects double-precision floating point vectors and matrices. Hence, you should pass numpy matrices with `dtype=float`, or `float64`. - + Also, GTSAM expects *column-major* matrices, unlike the default storage - scheme in numpy. Hence, you should pass column-major matrices to gtsam using + - Also, GTSAM expects _column-major_ matrices, unlike the default storage + scheme in numpy. Hence, you should pass column-major matrices to GTSAM using the flag order='F'. And you always get column-major matrices back. For more details, see [this link](https://github.com/wouterboomsma/eigency#storage-layout---why-arrays-are-sometimes-transposed). - + Passing row-major matrices of different dtype, e.g. `int`, will also work + - Passing row-major matrices of different dtype, e.g. `int`, will also work as the wrapper converts them to column-major and dtype float for you, using numpy.array.astype(float, order='F', copy=False). However, this will result a copy if your matrix is not in the expected type and storage order. -- Inner namespace: Classes in inner namespace will be prefixed by _ in Python. +- Inner namespace: Classes in inner namespace will be prefixed by \_ in Python. Examples: `noiseModel_Gaussian`, `noiseModel_mEstimator_Tukey` - Casting from a base class to a derive class must be done explicitly. Examples: + ```python noiseBase = factor.noiseModel() noiseGaussian = dynamic_cast_noiseModel_Gaussian_noiseModel_Base(noiseBase) @@ -75,37 +82,35 @@ See the tests for examples. ## Wrapping Custom GTSAM-based Project -Please refer to the template project and the corresponding tutorial available [here](https://github.com/borglab/gtsam-project-python). +Please refer to the template project and the corresponding tutorial available [here](https://github.com/borglab/GTSAM-project-python). ## KNOWN ISSUES - - Doesn't work with python3 installed from homebrew - - size-related issue: can only wrap up to a certain number of classes: up to mEstimator! - - Guess: 64 vs 32b? disutils Compiler flags? - - Bug with Cython 0.24: instantiated factor classes return FastVector for keys(), which can't be casted to FastVector - - Upgrading to 0.25 solves the problem - - Need default constructor and default copy constructor for almost every classes... :( - - support these constructors by default and declare "delete" for special classes? - +- Doesn't work with python3 installed from homebrew + - size-related issue: can only wrap up to a certain number of classes: up to mEstimator! + - Guess: 64 vs 32b? disutils Compiler flags? +- Bug with Cython 0.24: instantiated factor classes return FastVector for keys(), which can't be casted to FastVector + - Upgrading to 0.25 solves the problem +- Need default constructor and default copy constructor for almost every classes... :( + - support these constructors by default and declare "delete" for special classes? ### TODO - [ ] allow duplication of parent' functions in child classes. Not allowed for now due to conflicts in Cython. -- [ ] a common header for boost shared_ptr? (Or wait until everything is switched to std::shared_ptr in gtsam?) +- [ ] a common header for boost shared_ptr? (Or wait until everything is switched to std::shared_ptr in GTSAM?) - [ ] inner namespaces ==> inner packages? - [ ] Wrap fixed-size Matrices/Vectors? - ### Completed/Cancelled: -- [x] Fix Python tests: don't use " import * ": Bad style!!! (18-03-17 19:50) +- [x] Fix Python tests: don't use " import \* ": Bad style!!! (18-03-17 19:50) - [x] Unit tests for cython wrappers @done (18-03-17 18:45) -- simply compare generated files - [x] Wrap unstable @done (18-03-17 15:30) -- [x] Unify cython/gtsam.h and the original gtsam.h @done (18-03-17 15:30) +- [x] Unify cython/GTSAM.h and the original GTSAM.h @done (18-03-17 15:30) - [x] 18-03-17: manage to unify the two versions by removing std container stubs from the matlab version,and keeping KeyList/KeyVector/KeySet as in the matlab version. Probably Cython 0.25 fixes the casting problem. - [x] 06-03-17: manage to remove the requirements for default and copy constructors - [ ] 25-11-16: Try to unify but failed. Main reasons are: Key/size_t, std containers, KeyVector/KeyList/KeySet. Matlab doesn't need to know about Key, but I can't make Cython to ignore Key as it couldn't cast KeyVector, i.e. FastVector, to FastVector. -- [ ] Marginal and JointMarginal: revert changes @failed (17-03-17 11:00) -- Cython does need a default constructor! It produces cpp code like this: ```gtsam::JointMarginal __pyx_t_1;``` Users don't have to wrap this constructor, however. +- [ ] Marginal and JointMarginal: revert changes @failed (17-03-17 11:00) -- Cython does need a default constructor! It produces cpp code like this: `GTSAM::JointMarginal __pyx_t_1;` Users don't have to wrap this constructor, however. - [x] Convert input numpy Matrix/Vector to float dtype and storage order 'F' automatically, cannot crash! @done (15-03-17 13:00) - [x] Remove requirements.txt - Frank: don't bother with only 2 packages and a special case for eigency! @done (08-03-17 10:30) - [x] CMake install script @done (25-11-16 02:30) @@ -119,7 +124,7 @@ Please refer to the template project and the corresponding tutorial available [h - [x] Casting from parent and grandparents @done (16-11-16 17:00) - [x] Allow overloading constructors. The current solution is annoying!!! @done (16-11-16 17:00) - [x] Support "print obj" @done (16-11-16 17:00) -- [x] methods for FastVector: at, [], ... @done (16-11-16 17:00) +- [x] methods for FastVector: at, [], ... @done (16-11-16 17:00) - [x] Cython: Key and size_t: traits doesn't exist @done (16-09-12 18:34) - [x] KeyVector, KeyList, KeySet... @done (16-09-13 17:19) - [x] [Nice to have] parse typedef @done (16-09-13 17:19) From d2f69eeab41044219f4a40314eaf98d62254d183 Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Wed, 1 Jul 2020 17:07:31 -0500 Subject: [PATCH 135/869] Add python-install dependency for gtsam_unstable as well --- cmake/GtsamCythonWrap.cmake | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/cmake/GtsamCythonWrap.cmake b/cmake/GtsamCythonWrap.cmake index c155cbbd8..2f5582513 100644 --- a/cmake/GtsamCythonWrap.cmake +++ b/cmake/GtsamCythonWrap.cmake @@ -137,6 +137,8 @@ function(cythonize target pyx_file output_lib_we output_dir include_dirs libs in target_link_libraries(${target} "${libs}") endif() add_dependencies(${target} ${target}_pyx2cpp) + + add_dependencies(${python_install_target} ${target}) endfunction() # Internal function that wraps a library and compiles the wrapper @@ -169,8 +171,6 @@ function(wrap_library_cython interface_header generated_files_path extra_imports cythonize(cythonize_${module_name} ${generated_pyx} ${module_name} ${generated_files_path} "${include_dirs}" "${libs}" ${interface_header} cython_wrap_${module_name}_pyx) - add_dependencies(${python_install_target} cython_wrap_${module_name}_pyx) - # distclean add_custom_target(wrap_${module_name}_cython_distclean COMMAND cmake -E remove_directory ${generated_files_path}) From 52da4580fb58b79a2aca51c65fa4d1046f6a6f1d Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Wed, 1 Jul 2020 18:52:02 -0500 Subject: [PATCH 136/869] make utils and test code python2 compliant --- cython/gtsam/tests/test_logging_optimizer.py | 12 ++++++++---- cython/gtsam/utils/logging_optimizer.py | 10 +++------- 2 files changed, 11 insertions(+), 11 deletions(-) diff --git a/cython/gtsam/tests/test_logging_optimizer.py b/cython/gtsam/tests/test_logging_optimizer.py index e7d9645b7..69665db65 100644 --- a/cython/gtsam/tests/test_logging_optimizer.py +++ b/cython/gtsam/tests/test_logging_optimizer.py @@ -4,8 +4,12 @@ Author: Jing Wu and Frank Dellaert """ # pylint: disable=invalid-name -import io import sys +if sys.version_info.major >= 3: + from io import StringIO +else: + from cStringIO import StringIO + import unittest from datetime import datetime @@ -40,7 +44,7 @@ class TestOptimizeComet(GtsamTestCase): graph, initial, self.params) # setup output capture - self.capturedOutput = io.StringIO() + self.capturedOutput = StringIO() sys.stdout = self.capturedOutput def tearDown(self): @@ -51,7 +55,7 @@ class TestOptimizeComet(GtsamTestCase): """Test with a simple hook.""" # Provide a hook that just prints - def hook(_, error: float): + def hook(_, error): print(error) # Only thing we require from optimizer is an iterate method @@ -75,7 +79,7 @@ class TestOptimizeComet(GtsamTestCase): + str(time.hour)+":"+str(time.minute)+":"+str(time.second)) # I want to do some comet thing here - def hook(optimizer, error: float): + def hook(optimizer, error): comet.log_metric("Karcher error", error, optimizer.iterations()) diff --git a/cython/gtsam/utils/logging_optimizer.py b/cython/gtsam/utils/logging_optimizer.py index b201bb8aa..939453927 100644 --- a/cython/gtsam/utils/logging_optimizer.py +++ b/cython/gtsam/utils/logging_optimizer.py @@ -4,15 +4,11 @@ Author: Jing Wu and Frank Dellaert """ # pylint: disable=invalid-name -from typing import TypeVar - from gtsam import NonlinearOptimizer, NonlinearOptimizerParams import gtsam -T = TypeVar('T') - -def optimize(optimizer: T, check_convergence, hook): +def optimize(optimizer, check_convergence, hook): """ Given an optimizer and a convergence check, iterate until convergence. After each iteration, hook(optimizer, error) is called. After the function, use values and errors to get the result. @@ -36,8 +32,8 @@ def optimize(optimizer: T, check_convergence, hook): current_error = new_error -def gtsam_optimize(optimizer: NonlinearOptimizer, - params: NonlinearOptimizerParams, +def gtsam_optimize(optimizer, + params, hook): """ Given an optimizer and params, iterate until convergence. After each iteration, hook(optimizer) is called. From ebd4db2380ce9d9c14e8ce3ccbbc08e37657fcc2 Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Thu, 2 Jul 2020 13:03:17 -0500 Subject: [PATCH 137/869] small improvements to the ImuFactorExample.py --- cython/gtsam/examples/ImuFactorExample.py | 10 ++++++---- 1 file changed, 6 insertions(+), 4 deletions(-) diff --git a/cython/gtsam/examples/ImuFactorExample.py b/cython/gtsam/examples/ImuFactorExample.py index 289a0ccec..06742fcd1 100644 --- a/cython/gtsam/examples/ImuFactorExample.py +++ b/cython/gtsam/examples/ImuFactorExample.py @@ -79,6 +79,9 @@ class ImuFactorExample(PreintegrationExample): initial.insert(X(i), initial_state_i.pose()) initial.insert(V(i), initial_state_i.velocity()) + # add prior on beginning + self.addPrior(0, graph) + for k, t in enumerate(np.arange(0, T, self.dt)): # get measurements and add them to PIM measuredOmega = self.runner.measuredAngularVelocity(t) @@ -121,19 +124,18 @@ class ImuFactorExample(PreintegrationExample): initial.insert(V(i+1), noisy_state_i.velocity()) i += 1 - # add prior on beginning - self.addPrior(0, graph) # add prior on end # self.addPrior(num_poses - 1, graph) + initial.print_("Initial values:") + # optimize using Levenberg-Marquardt optimization params = gtsam.LevenbergMarquardtParams() params.setVerbosityLM("SUMMARY") optimizer = gtsam.LevenbergMarquardtOptimizer(graph, initial, params) result = optimizer.optimize() - initial.print_("Initial values:") - result.print_("") + result.print_("Optimized values:") if compute_covariances: # Calculate and print marginal covariances From ab047d6962cd93414d695344cb7fd3360a4febae Mon Sep 17 00:00:00 2001 From: akrishnan86 Date: Thu, 2 Jul 2020 23:35:34 -0700 Subject: [PATCH 138/869] forking code for mfas from 1dsfm --- gtsam/sfm/mfas.cc | 138 ++++++++++++++++++++++++++++++++++++++++++++++ gtsam/sfm/mfas.h | 25 +++++++++ 2 files changed, 163 insertions(+) create mode 100644 gtsam/sfm/mfas.cc create mode 100644 gtsam/sfm/mfas.h diff --git a/gtsam/sfm/mfas.cc b/gtsam/sfm/mfas.cc new file mode 100644 index 000000000..4bc8f21a6 --- /dev/null +++ b/gtsam/sfm/mfas.cc @@ -0,0 +1,138 @@ +#include "mfas.h" + +#include +#include +#include + +using std::map; +using std::pair; +using std::set; +using std::vector; + +void reindex_problem(vector &edges, map &reindexing_key) { + // get the unique set of notes + set nodes; + for (int i = 0; i < edges.size(); ++i) { + nodes.insert(edges[i].first); + nodes.insert(edges[i].second); + } + + // iterator through them and assign a new name to each vertex + std::set::const_iterator it; + reindexing_key.clear(); + int i = 0; + for (it = nodes.begin(); it != nodes.end(); ++it) { + reindexing_key[*it] = i; + ++i; + } + + // now renumber the edges + for (int i = 0; i < edges.size(); ++i) { + edges[i].first = reindexing_key[edges[i].first]; + edges[i].second = reindexing_key[edges[i].second]; + } +} + +void flip_neg_edges(vector &edges, vector &weights) { + // now renumber the edges + for (int i = 0; i < edges.size(); ++i) { + if (weights[i] < 0.0) { + double tmp = edges[i].second; + edges[i].second = edges[i].first; + edges[i].first = tmp; + weights[i] *= -1; + } + } +} + +void mfas_ratio(const std::vector &edges, + const std::vector &weights, std::vector &order) { + // find the number of nodes in this problem + int n = -1; + int m = edges.size(); + for (int i = 0; i < m; ++i) { + n = (edges[i].first > n) ? edges[i].first : n; + n = (edges[i].second > n) ? edges[i].second : n; + } + n += 1; // 0 indexed + + // initialize data structures + vector win_deg(n, 0.0); + vector wout_deg(n, 0.0); + vector unchosen(n, 1); + vector > > inbrs(n); + vector > > onbrs(n); + + // stuff data structures + for (int ii = 0; ii < m; ++ii) { + int i = edges[ii].first; + int j = edges[ii].second; + double w = weights[ii]; + + win_deg[j] += w; + wout_deg[i] += w; + inbrs[j].push_back(pair(i, w)); + onbrs[i].push_back(pair(j, w)); + } + + while (order.size() < n) { + // choose an unchosen node + int choice = -1; + double max_score = 0.0; + for (int i = 0; i < n; ++i) { + if (unchosen[i]) { + // is this a source + if (win_deg[i] < 1e-8) { + choice = i; + break; + } else { + double score = (wout_deg[i] + 1) / (win_deg[i] + 1); + if (score > max_score) { + max_score = score; + choice = i; + } + } + } + } + + // find its inbrs, adjust their wout_deg + vector >::iterator it; + for (it = inbrs[choice].begin(); it != inbrs[choice].end(); ++it) + wout_deg[it->first] -= it->second; + // find its onbrs, adjust their win_deg + for (it = onbrs[choice].begin(); it != onbrs[choice].end(); ++it) + win_deg[it->first] -= it->second; + + order.push_back(choice); + unchosen[choice] = 0; + } +} + +void broken_weight(const std::vector &edges, + const std::vector &weight, + const std::vector &order, std::vector &broken) { + // clear the output vector + int m = edges.size(); + broken.resize(m); + broken.assign(broken.size(), 0.0); + + // find the number of nodes in this problem + int n = -1; + for (int i = 0; i < m; ++i) { + n = (edges[i].first > n) ? edges[i].first : n; + n = (edges[i].second > n) ? edges[i].second : n; + } + n += 1; // 0 indexed + + // invert the permutation + std::vector inv_perm(n, 0.0); + for (int i = 0; i < n; ++i) inv_perm[order[i]] = i; + + // find the broken edges + for (int i = 0; i < m; ++i) { + int x0 = inv_perm[edges[i].first]; + int x1 = inv_perm[edges[i].second]; + if ((x1 - x0) * weight[i] < 0) + broken[i] += weight[i] > 0 ? weight[i] : -weight[i]; + } +} diff --git a/gtsam/sfm/mfas.h b/gtsam/sfm/mfas.h new file mode 100644 index 000000000..57f69a756 --- /dev/null +++ b/gtsam/sfm/mfas.h @@ -0,0 +1,25 @@ +/* + This file contains the code to solve a Minimum feedback arc set (MFAS) problem + Copyright (c) 2014, Kyle Wilson + All rights reserved. +*/ +#ifndef __MFAS_H__ +#define __MFAS_H__ + +#include +#include +typedef std::pair Edge; + +void mfas_ratio(const std::vector &edges, + const std::vector &weight, std::vector &order); + +void reindex_problem(std::vector &edges, + std::map &reindexing_key); + +void flip_neg_edges(std::vector &edges, std::vector &weights); + +void broken_weight(const std::vector &edges, + const std::vector &weight, + const std::vector &order, std::vector &broken); + +#endif // __MFAS_H__ From cb151dd9ee9426f60c371c4a49c043726f7a4afa Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Sat, 4 Jul 2020 20:42:15 -0400 Subject: [PATCH 139/869] update python build location in travis script --- .travis.python.sh | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/.travis.python.sh b/.travis.python.sh index 1ef5799aa..772311f38 100644 --- a/.travis.python.sh +++ b/.travis.python.sh @@ -34,7 +34,7 @@ cmake $CURRDIR -DCMAKE_BUILD_TYPE=Release \ make -j$(nproc) install -cd $CURRDIR/../gtsam_install/cython +cd cython sudo $PYTHON setup.py install From 564d2c58730e9710385b4009e7e676117076ccb2 Mon Sep 17 00:00:00 2001 From: Fan Jiang Date: Sun, 5 Jul 2020 10:19:05 -0400 Subject: [PATCH 140/869] Fix memory leak in Expressions --- gtsam/nonlinear/internal/ExecutionTrace.h | 6 ++++++ gtsam/nonlinear/tests/testExecutionTrace.cpp | 1 + 2 files changed, 7 insertions(+) diff --git a/gtsam/nonlinear/internal/ExecutionTrace.h b/gtsam/nonlinear/internal/ExecutionTrace.h index ace0aaea8..2943b5e68 100644 --- a/gtsam/nonlinear/internal/ExecutionTrace.h +++ b/gtsam/nonlinear/internal/ExecutionTrace.h @@ -169,6 +169,12 @@ class ExecutionTrace { content.ptr->reverseAD2(dTdA, jacobians); } + ~ExecutionTrace() { + if (kind == Function) { + content.ptr->~CallRecord(); + } + } + /// Define type so we can apply it as a meta-function typedef ExecutionTrace type; }; diff --git a/gtsam/nonlinear/tests/testExecutionTrace.cpp b/gtsam/nonlinear/tests/testExecutionTrace.cpp index c2b245780..58f76089a 100644 --- a/gtsam/nonlinear/tests/testExecutionTrace.cpp +++ b/gtsam/nonlinear/tests/testExecutionTrace.cpp @@ -16,6 +16,7 @@ * @brief unit tests for Expression internals */ +#include #include #include From 258d05c9efd5223c29a80441bb7ebdb3aeada224 Mon Sep 17 00:00:00 2001 From: Fan Jiang Date: Sat, 4 Jul 2020 20:31:04 -0400 Subject: [PATCH 141/869] Fix TranslationFactor with Vector3 as Point3 --- gtsam/sfm/TranslationFactor.h | 3 +-- 1 file changed, 1 insertion(+), 2 deletions(-) diff --git a/gtsam/sfm/TranslationFactor.h b/gtsam/sfm/TranslationFactor.h index 9a4bd68a7..d63633d7e 100644 --- a/gtsam/sfm/TranslationFactor.h +++ b/gtsam/sfm/TranslationFactor.h @@ -67,8 +67,7 @@ class TranslationFactor : public NoiseModelFactor2 { boost::optional H2 = boost::none) const override { const Point3 dir = Tb - Ta; Matrix33 H_predicted_dir; - const Point3 predicted = - dir.normalized(H1 || H2 ? &H_predicted_dir : nullptr); + const Point3 predicted = normalize(dir, H1 || H2 ? &H_predicted_dir : nullptr); if (H1) *H1 = -H_predicted_dir; if (H2) *H2 = H_predicted_dir; return predicted - measured_w_aZb_; From df687e5abf4da44933f00b121356817f1c85bd6c Mon Sep 17 00:00:00 2001 From: Fan Jiang Date: Fri, 19 Jun 2020 10:40:07 -0400 Subject: [PATCH 142/869] Fix MSVC build --- gtsam/base/types.h | 1 + 1 file changed, 1 insertion(+) diff --git a/gtsam/base/types.h b/gtsam/base/types.h index c5dac9ab7..857de00c9 100644 --- a/gtsam/base/types.h +++ b/gtsam/base/types.h @@ -28,6 +28,7 @@ #include #include +#include #ifdef GTSAM_USE_TBB #include From e08e39202074fed0b0a40fdb821e5f0726ec4799 Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Sun, 5 Jul 2020 21:57:18 -0500 Subject: [PATCH 143/869] Improved paths and added checks --- cmake/GtsamCythonWrap.cmake | 13 +++++++++---- cython/gtsam_eigency/CMakeLists.txt | 4 +++- 2 files changed, 12 insertions(+), 5 deletions(-) diff --git a/cmake/GtsamCythonWrap.cmake b/cmake/GtsamCythonWrap.cmake index 2f5582513..c8f876895 100644 --- a/cmake/GtsamCythonWrap.cmake +++ b/cmake/GtsamCythonWrap.cmake @@ -41,7 +41,7 @@ execute_process(COMMAND "${PYTHON_EXECUTABLE}" "-c" function(wrap_and_install_library_cython interface_header extra_imports install_path libs dependencies) # Paths for generated files get_filename_component(module_name "${interface_header}" NAME_WE) - set(generated_files_path "${GTSAM_CYTHON_INSTALL_PATH}/${module_name}") + set(generated_files_path "${install_path}") wrap_library_cython("${interface_header}" "${generated_files_path}" "${extra_imports}" "${libs}" "${dependencies}") endfunction() @@ -138,7 +138,9 @@ function(cythonize target pyx_file output_lib_we output_dir include_dirs libs in endif() add_dependencies(${target} ${target}_pyx2cpp) - add_dependencies(${python_install_target} ${target}) + if(TARGET ${python_install_target}) + add_dependencies(${python_install_target} ${target}) + endif() endfunction() # Internal function that wraps a library and compiles the wrapper @@ -151,9 +153,12 @@ function(wrap_library_cython interface_header generated_files_path extra_imports get_filename_component(module_name "${interface_header}" NAME_WE) # Wrap module to Cython pyx - message(STATUS "Cython wrapper generating ${module_name}.pyx") + message(STATUS "Cython wrapper generating ${generated_files_path}/${module_name}.pyx") set(generated_pyx "${generated_files_path}/${module_name}.pyx") - file(MAKE_DIRECTORY "${generated_files_path}") + if(NOT EXISTS ${generated_files_path}) + file(MAKE_DIRECTORY "${generated_files_path}") + endif() + add_custom_command( OUTPUT ${generated_pyx} DEPENDS ${interface_header} wrap diff --git a/cython/gtsam_eigency/CMakeLists.txt b/cython/gtsam_eigency/CMakeLists.txt index 663ea0a32..a0cf0fbde 100644 --- a/cython/gtsam_eigency/CMakeLists.txt +++ b/cython/gtsam_eigency/CMakeLists.txt @@ -37,4 +37,6 @@ add_dependencies(cythonize_eigency_core cythonize_eigency_conversions) add_custom_target(cythonize_eigency) add_dependencies(cythonize_eigency cythonize_eigency_conversions cythonize_eigency_core) -add_dependencies(${python_install_target} cythonize_eigency) +if(TARGET ${python_install_target}) + add_dependencies(${python_install_target} cythonize_eigency) +endif() From 636178f3bd8a8b850cde23fadebe12e3970f7b4a Mon Sep 17 00:00:00 2001 From: akrishnan86 Date: Mon, 6 Jul 2020 00:43:25 -0700 Subject: [PATCH 144/869] changing mfas to use gtsam keys --- gtsam/sfm/mfas.cc | 110 ++++++++++++++-------------------------------- gtsam/sfm/mfas.h | 33 ++++++++++---- 2 files changed, 57 insertions(+), 86 deletions(-) diff --git a/gtsam/sfm/mfas.cc b/gtsam/sfm/mfas.cc index 4bc8f21a6..f2244bdfc 100644 --- a/gtsam/sfm/mfas.cc +++ b/gtsam/sfm/mfas.cc @@ -9,35 +9,14 @@ using std::pair; using std::set; using std::vector; -void reindex_problem(vector &edges, map &reindexing_key) { - // get the unique set of notes - set nodes; - for (int i = 0; i < edges.size(); ++i) { - nodes.insert(edges[i].first); - nodes.insert(edges[i].second); - } +namespace gtsam { +namespace mfas { - // iterator through them and assign a new name to each vertex - std::set::const_iterator it; - reindexing_key.clear(); - int i = 0; - for (it = nodes.begin(); it != nodes.end(); ++it) { - reindexing_key[*it] = i; - ++i; - } - - // now renumber the edges - for (int i = 0; i < edges.size(); ++i) { - edges[i].first = reindexing_key[edges[i].first]; - edges[i].second = reindexing_key[edges[i].second]; - } -} - -void flip_neg_edges(vector &edges, vector &weights) { +void flipNegEdges(vector &edges, vector &weights) { // now renumber the edges for (int i = 0; i < edges.size(); ++i) { if (weights[i] < 0.0) { - double tmp = edges[i].second; + Key tmp = edges[i].second; edges[i].second = edges[i].first; edges[i].first = tmp; weights[i] *= -1; @@ -45,26 +24,17 @@ void flip_neg_edges(vector &edges, vector &weights) { } } -void mfas_ratio(const std::vector &edges, - const std::vector &weights, std::vector &order) { - // find the number of nodes in this problem - int n = -1; - int m = edges.size(); - for (int i = 0; i < m; ++i) { - n = (edges[i].first > n) ? edges[i].first : n; - n = (edges[i].second > n) ? edges[i].second : n; - } - n += 1; // 0 indexed - +void mfasRatio(const std::vector &edges, + const std::vector &weights, const KeyVector &nodes, + FastMap &ordered_positions) { // initialize data structures - vector win_deg(n, 0.0); - vector wout_deg(n, 0.0); - vector unchosen(n, 1); - vector > > inbrs(n); - vector > > onbrs(n); + FastMap win_deg; + FastMap wout_deg; + FastMap > > inbrs; + FastMap > > onbrs; // stuff data structures - for (int ii = 0; ii < m; ++ii) { + for (int ii = 0; ii < edges.size(); ++ii) { int i = edges[ii].first; int j = edges[ii].second; double w = weights[ii]; @@ -75,64 +45,50 @@ void mfas_ratio(const std::vector &edges, onbrs[i].push_back(pair(j, w)); } - while (order.size() < n) { + int ordered_count = 0; + while (ordered_count < nodes.size()) { // choose an unchosen node - int choice = -1; + Key choice; double max_score = 0.0; - for (int i = 0; i < n; ++i) { - if (unchosen[i]) { + for (auto node : nodes) { + if (ordered_positions.find(node) != ordered_positions.end()) { // is this a source - if (win_deg[i] < 1e-8) { - choice = i; + if (win_deg[node] < 1e-8) { + choice = node; break; } else { - double score = (wout_deg[i] + 1) / (win_deg[i] + 1); + double score = (wout_deg[node] + 1) / (win_deg[node] + 1); if (score > max_score) { max_score = score; - choice = i; + choice = node; } } } } // find its inbrs, adjust their wout_deg - vector >::iterator it; - for (it = inbrs[choice].begin(); it != inbrs[choice].end(); ++it) + for (auto it = inbrs[choice].begin(); it != inbrs[choice].end(); ++it) wout_deg[it->first] -= it->second; // find its onbrs, adjust their win_deg - for (it = onbrs[choice].begin(); it != onbrs[choice].end(); ++it) + for (auto it = onbrs[choice].begin(); it != onbrs[choice].end(); ++it) win_deg[it->first] -= it->second; - order.push_back(choice); - unchosen[choice] = 0; + ordered_positions[choice] = ordered_count++; } } -void broken_weight(const std::vector &edges, +void brokenWeights(const std::vector &edges, const std::vector &weight, - const std::vector &order, std::vector &broken) { - // clear the output vector - int m = edges.size(); - broken.resize(m); - broken.assign(broken.size(), 0.0); - - // find the number of nodes in this problem - int n = -1; - for (int i = 0; i < m; ++i) { - n = (edges[i].first > n) ? edges[i].first : n; - n = (edges[i].second > n) ? edges[i].second : n; - } - n += 1; // 0 indexed - - // invert the permutation - std::vector inv_perm(n, 0.0); - for (int i = 0; i < n; ++i) inv_perm[order[i]] = i; - + const FastMap &ordered_positions, + FastMap &broken) { // find the broken edges - for (int i = 0; i < m; ++i) { - int x0 = inv_perm[edges[i].first]; - int x1 = inv_perm[edges[i].second]; + for (int i = 0; i < edges.size(); ++i) { + int x0 = ordered_positions.at(edges[i].first); + int x1 = ordered_positions.at(edges[i].second); if ((x1 - x0) * weight[i] < 0) broken[i] += weight[i] > 0 ? weight[i] : -weight[i]; } } + +} // namespace mfas +} // namespace gtsam \ No newline at end of file diff --git a/gtsam/sfm/mfas.h b/gtsam/sfm/mfas.h index 57f69a756..b76064ed6 100644 --- a/gtsam/sfm/mfas.h +++ b/gtsam/sfm/mfas.h @@ -1,25 +1,40 @@ /* - This file contains the code to solve a Minimum feedback arc set (MFAS) problem + This file defines functions used to solve a Minimum feedback arc set (MFAS) + problem. This code was forked and modified from Kyle Wilson's repository at + https://github.com/wilsonkl/SfM_Init. Copyright (c) 2014, Kyle Wilson All rights reserved. + + Given a weighted directed graph, the objective in a Minimum feedback arc set + problem is to obtain a graph that does not contain any cycles by removing + edges such that the total weight of removed edges is minimum. */ #ifndef __MFAS_H__ #define __MFAS_H__ +#include +#include + #include #include -typedef std::pair Edge; -void mfas_ratio(const std::vector &edges, - const std::vector &weight, std::vector &order); +namespace gtsam { -void reindex_problem(std::vector &edges, - std::map &reindexing_key); +using KeyPair = std::pair; -void flip_neg_edges(std::vector &edges, std::vector &weights); +namespace mfas { -void broken_weight(const std::vector &edges, +void flipNegEdges(std::vector &edges, std::vector &weights); + +void mfasRatio(const std::vector &edges, + const std::vector &weights, const KeyVector &nodes, + FastMap &ordered_positions); + +void brokenWeights(const std::vector &edges, const std::vector &weight, - const std::vector &order, std::vector &broken); + const FastMap &ordered_positions, + FastMap &broken); +} // namespace mfas +} // namespace gtsam #endif // __MFAS_H__ From 3c5f8711caabe0a1db5a7b293b2bed05f74004d2 Mon Sep 17 00:00:00 2001 From: Jose Luis Blanco-Claraco Date: Mon, 6 Jul 2020 20:07:18 +0200 Subject: [PATCH 145/869] Fix missing DLL exported symbol --- gtsam/base/types.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/gtsam/base/types.h b/gtsam/base/types.h index 857de00c9..aaada3cee 100644 --- a/gtsam/base/types.h +++ b/gtsam/base/types.h @@ -55,7 +55,7 @@ namespace gtsam { /// Function to demangle type name of variable, e.g. demangle(typeid(x).name()) - std::string demangle(const char* name); + std::string GTSAM_EXPORT demangle(const char* name); /// Integer nonlinear key type typedef std::uint64_t Key; From 7d0e440293fe87b2f5ff6e142bf10588d9c051ee Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Mon, 6 Jul 2020 17:38:34 -0400 Subject: [PATCH 146/869] new definition for FunctorizedFactor to allow for using std::function and lambdas --- gtsam/nonlinear/FunctorizedFactor.h | 73 +++++++-------- .../nonlinear/tests/testFunctorizedFactor.cpp | 89 ++++++++++++++----- 2 files changed, 97 insertions(+), 65 deletions(-) diff --git a/gtsam/nonlinear/FunctorizedFactor.h b/gtsam/nonlinear/FunctorizedFactor.h index 82d2f822e..c88579587 100644 --- a/gtsam/nonlinear/FunctorizedFactor.h +++ b/gtsam/nonlinear/FunctorizedFactor.h @@ -27,14 +27,11 @@ namespace gtsam { /** * Factor which evaluates functor and uses the result to compute * error on provided measurement. - * The provided FUNCTOR should provide two type aliases: `argument_type` which - * corresponds to the type of input it accepts and `return_type` which indicates - * the type of the return value. This factor uses those type values to construct - * the functor. * * Template parameters are - * @param FUNCTOR: A class which operates as a functor. - * + * @param R: The return type of the functor after evaluation. + * @param T: The argument type for the functor. + * * Example: * Key key = Symbol('X', 0); * auto model = noiseModel::Isotropic::Sigma(9, 1); @@ -48,58 +45,53 @@ namespace gtsam { * MultiplyFunctor(double m) : m_(m) {} * Matrix operator()(const Matrix &X, * OptionalJacobian<-1, -1> H = boost::none) const { - * if (H) *H = m_ * Matrix::Identity(X.rows()*X.cols(), X.rows()*X.cols()); - * return m_ * X; + * if (H) *H = m_ * Matrix::Identity(X.rows()*X.cols(), + * X.rows()*X.cols()); return m_ * X; * } * }; * * Matrix measurement = Matrix::Identity(3, 3); * double multiplier = 2.0; - * FunctorizedFactor factor(keyX, measurement, model, multiplier); + * + * FunctorizedFactor factor(keyX, measurement, model, + * MultiplyFunctor(multiplier)); */ -template -class GTSAM_EXPORT FunctorizedFactor - : public NoiseModelFactor1 { -private: - using T = typename FUNCTOR::argument_type; +template +class GTSAM_EXPORT FunctorizedFactor : public NoiseModelFactor1 { + private: using Base = NoiseModelFactor1; - typename FUNCTOR::return_type - measured_; ///< value that is compared with functor return value - SharedNoiseModel noiseModel_; ///< noise model - FUNCTOR func_; ///< functor instance + R measured_; ///< value that is compared with functor return value + SharedNoiseModel noiseModel_; ///< noise model + std::function)> func_; ///< functor instance -public: + public: /** default constructor - only use for serialization */ FunctorizedFactor() {} /** Construct with given x and the parameters of the basis - * - * @param Args: Variadic template parameter for functor arguments. * * @param key: Factor key - * @param z: Measurement object of type FUNCTOR::return_type + * @param z: Measurement object of type R * @param model: Noise model - * @param args: Variable number of arguments used to instantiate functor + * @param func: The instance of the functor object */ - template - FunctorizedFactor(Key key, const typename FUNCTOR::return_type &z, - const SharedNoiseModel &model, Args &&... args) - : Base(model, key), measured_(z), noiseModel_(model), - func_(std::forward(args)...) {} + FunctorizedFactor(Key key, const R &z, const SharedNoiseModel &model, + const std::function)> func) + : Base(model, key), measured_(z), noiseModel_(model), func_(func) {} virtual ~FunctorizedFactor() {} /// @return a deep copy of this factor virtual NonlinearFactor::shared_ptr clone() const { return boost::static_pointer_cast( - NonlinearFactor::shared_ptr(new FunctorizedFactor(*this))); + NonlinearFactor::shared_ptr(new FunctorizedFactor(*this))); } Vector evaluateError(const T ¶ms, boost::optional H = boost::none) const { - typename FUNCTOR::return_type x = func_(params, H); - Vector error = traits::Local(measured_, x); + R x = func_(params, H); + Vector error = traits::Local(measured_, x); return error; } @@ -110,22 +102,21 @@ public: Base::print(s, keyFormatter); std::cout << s << (s != "" ? " " : "") << "FunctorizedFactor(" << keyFormatter(this->key()) << ")" << std::endl; - traits::Print(measured_, " measurement: "); + traits::Print(measured_, " measurement: "); std::cout << " noise model sigmas: " << noiseModel_->sigmas().transpose() << std::endl; } virtual bool equals(const NonlinearFactor &other, double tol = 1e-9) const { - const FunctorizedFactor *e = - dynamic_cast *>(&other); + const FunctorizedFactor *e = + dynamic_cast *>(&other); const bool base = Base::equals(*e, tol); return e && Base::equals(other, tol) && - traits::Equals(this->measured_, e->measured_, - tol); + traits::Equals(this->measured_, e->measured_, tol); } /// @} -private: + private: /** Serialization function */ friend class boost::serialization::access; template @@ -138,8 +129,8 @@ private: }; /// traits -template -struct traits> - : public Testable> {}; +template +struct traits> + : public Testable> {}; -} // namespace gtsam +} // namespace gtsam diff --git a/gtsam/nonlinear/tests/testFunctorizedFactor.cpp b/gtsam/nonlinear/tests/testFunctorizedFactor.cpp index 9393a4410..9ff6b8e24 100644 --- a/gtsam/nonlinear/tests/testFunctorizedFactor.cpp +++ b/gtsam/nonlinear/tests/testFunctorizedFactor.cpp @@ -17,13 +17,12 @@ * @brief unit tests for FunctorizedFactor class */ +#include #include #include #include #include -#include - using namespace std; using namespace gtsam; @@ -32,9 +31,9 @@ auto model = noiseModel::Isotropic::Sigma(9, 1); /// Functor that takes a matrix and multiplies every element by m class MultiplyFunctor { - double m_; ///< simple multiplier + double m_; ///< simple multiplier -public: + public: using argument_type = Matrix; using return_type = Matrix; @@ -42,32 +41,33 @@ public: Matrix operator()(const Matrix &X, OptionalJacobian<-1, -1> H = boost::none) const { - if (H) - *H = m_ * Matrix::Identity(X.rows() * X.cols(), X.rows() * X.cols()); + if (H) *H = m_ * Matrix::Identity(X.rows() * X.cols(), X.rows() * X.cols()); return m_ * X; } }; +/* ************************************************************************* */ TEST(FunctorizedFactor, Identity) { - Matrix X = Matrix::Identity(3, 3), measurement = Matrix::Identity(3, 3); double multiplier = 1.0; - FunctorizedFactor factor(key, measurement, model, - multiplier); + FunctorizedFactor factor(key, measurement, model, + MultiplyFunctor(multiplier)); Vector error = factor.evaluateError(X); EXPECT(assert_equal(Vector::Zero(9), error, 1e-9)); } +/* ************************************************************************* */ TEST(FunctorizedFactor, Multiply2) { double multiplier = 2.0; Matrix X = Matrix::Identity(3, 3); Matrix measurement = multiplier * Matrix::Identity(3, 3); - FunctorizedFactor factor(key, measurement, model, multiplier); + FunctorizedFactor factor(key, measurement, model, + MultiplyFunctor(multiplier)); Vector error = factor.evaluateError(X); @@ -79,10 +79,10 @@ TEST(FunctorizedFactor, Equality) { double multiplier = 2.0; - FunctorizedFactor factor1(key, measurement, model, - multiplier); - FunctorizedFactor factor2(key, measurement, model, - multiplier); + FunctorizedFactor factor1(key, measurement, model, + MultiplyFunctor(multiplier)); + FunctorizedFactor factor2(key, measurement, model, + MultiplyFunctor(multiplier)); EXPECT(factor1.equals(factor2)); } @@ -94,7 +94,8 @@ TEST(FunctorizedFactor, Jacobians) { double multiplier = 2.0; - FunctorizedFactor factor(key, X, model, multiplier); + FunctorizedFactor factor(key, X, model, + MultiplyFunctor(multiplier)); Values values; values.insert(key, X); @@ -103,12 +104,14 @@ TEST(FunctorizedFactor, Jacobians) { EXPECT_CORRECT_FACTOR_JACOBIANS(factor, values, 1e-7, 1e-5); } +/* ************************************************************************* */ TEST(FunctorizedFactor, Print) { Matrix X = Matrix::Identity(2, 2); double multiplier = 2.0; - FunctorizedFactor factor(key, X, model, multiplier); + FunctorizedFactor factor(key, X, model, + MultiplyFunctor(multiplier)); // redirect output to buffer so we can compare stringstream buffer; @@ -120,18 +123,56 @@ TEST(FunctorizedFactor, Print) { string actual = buffer.str(); cout.rdbuf(old); - string expected = " keys = { X0 }\n" - " noise model: unit (9) \n" - "FunctorizedFactor(X0)\n" - " measurement: [\n" - " 1, 0;\n" - " 0, 1\n" - "]\n" - " noise model sigmas: 1 1 1 1 1 1 1 1 1\n"; + string expected = + " keys = { X0 }\n" + " noise model: unit (9) \n" + "FunctorizedFactor(X0)\n" + " measurement: [\n" + " 1, 0;\n" + " 0, 1\n" + "]\n" + " noise model sigmas: 1 1 1 1 1 1 1 1 1\n"; CHECK_EQUAL(expected, actual); } +/* ************************************************************************* */ +// Test factor using a std::function type. +TEST(FunctorizedFactor, Functional) { + double multiplier = 2.0; + Matrix X = Matrix::Identity(3, 3); + Matrix measurement = multiplier * Matrix::Identity(3, 3); + + std::function)> functional = + MultiplyFunctor(multiplier); + FunctorizedFactor factor(key, measurement, model, functional); + + Vector error = factor.evaluateError(X); + + EXPECT(assert_equal(Vector::Zero(9), error, 1e-9)); +} + +/* ************************************************************************* */ +TEST(FunctorizedFactor, Lambda) { + double multiplier = 2.0; + Matrix X = Matrix::Identity(3, 3); + Matrix measurement = multiplier * Matrix::Identity(3, 3); + + auto lambda = [multiplier](const Matrix &X, + OptionalJacobian<-1, -1> H = boost::none) { + if (H) + *H = multiplier * + Matrix::Identity(X.rows() * X.cols(), X.rows() * X.cols()); + return multiplier * X; + }; + // FunctorizedFactor factor(key, measurement, model, lambda); + auto factor = FunctorizedFactor(key, measurement, model, lambda); + + Vector error = factor.evaluateError(X); + + EXPECT(assert_equal(Vector::Zero(9), error, 1e-9)); +} + /* ************************************************************************* */ int main() { From 30ffcdd1371985b5415e7b22918c65ecbc42789e Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Mon, 6 Jul 2020 21:48:51 -0400 Subject: [PATCH 147/869] Simplified FunctorizedFactor By adding the helper function MakeFunctorizedFactor, we now only need to provide the argument type in the template parameter list. This considerably simplifies the factor declaration, while removing the need for argument type and return type in the functor definition. Also added tests for std::function and lambda functions. --- gtsam/nonlinear/FunctorizedFactor.h | 38 ++++++++++----- .../nonlinear/tests/testFunctorizedFactor.cpp | 47 ++++++++++--------- 2 files changed, 50 insertions(+), 35 deletions(-) diff --git a/gtsam/nonlinear/FunctorizedFactor.h b/gtsam/nonlinear/FunctorizedFactor.h index c88579587..a83198967 100644 --- a/gtsam/nonlinear/FunctorizedFactor.h +++ b/gtsam/nonlinear/FunctorizedFactor.h @@ -25,8 +25,8 @@ namespace gtsam { /** - * Factor which evaluates functor and uses the result to compute - * error on provided measurement. + * Factor which evaluates provided unary functor and uses the result to compute + * error with respect to the provided measurement. * * Template parameters are * @param R: The return type of the functor after evaluation. @@ -40,13 +40,12 @@ namespace gtsam { * class MultiplyFunctor { * double m_; ///< simple multiplier * public: - * using argument_type = Matrix; - * using return_type = Matrix; * MultiplyFunctor(double m) : m_(m) {} * Matrix operator()(const Matrix &X, * OptionalJacobian<-1, -1> H = boost::none) const { - * if (H) *H = m_ * Matrix::Identity(X.rows()*X.cols(), - * X.rows()*X.cols()); return m_ * X; + * if (H) + * *H = m_ * Matrix::Identity(X.rows()*X.cols(), X.rows()*X.cols()); + * return m_ * X; * } * }; * @@ -72,7 +71,7 @@ class GTSAM_EXPORT FunctorizedFactor : public NoiseModelFactor1 { /** Construct with given x and the parameters of the basis * * @param key: Factor key - * @param z: Measurement object of type R + * @param z: Measurement object of same type as that returned by functor * @param model: Noise model * @param func: The instance of the functor object */ @@ -85,7 +84,7 @@ class GTSAM_EXPORT FunctorizedFactor : public NoiseModelFactor1 { /// @return a deep copy of this factor virtual NonlinearFactor::shared_ptr clone() const { return boost::static_pointer_cast( - NonlinearFactor::shared_ptr(new FunctorizedFactor(*this))); + NonlinearFactor::shared_ptr(new FunctorizedFactor(*this))); } Vector evaluateError(const T ¶ms, @@ -108,8 +107,8 @@ class GTSAM_EXPORT FunctorizedFactor : public NoiseModelFactor1 { } virtual bool equals(const NonlinearFactor &other, double tol = 1e-9) const { - const FunctorizedFactor *e = - dynamic_cast *>(&other); + const FunctorizedFactor *e = + dynamic_cast *>(&other); const bool base = Base::equals(*e, tol); return e && Base::equals(other, tol) && traits::Equals(this->measured_, e->measured_, tol); @@ -129,8 +128,21 @@ class GTSAM_EXPORT FunctorizedFactor : public NoiseModelFactor1 { }; /// traits -template -struct traits> - : public Testable> {}; +template +struct traits> + : public Testable> {}; + +/** + * Helper function to create a functorized factor. + * + * Uses function template deduction to identify return type and functor type, so + * template list only needs the functor argument type. + */ +template +FunctorizedFactor MakeFunctorizedFactor(Key key, const R &z, + const SharedNoiseModel &model, + const FUNC func) { + return FunctorizedFactor(key, z, model, func); +} } // namespace gtsam diff --git a/gtsam/nonlinear/tests/testFunctorizedFactor.cpp b/gtsam/nonlinear/tests/testFunctorizedFactor.cpp index 9ff6b8e24..12dd6b91c 100644 --- a/gtsam/nonlinear/tests/testFunctorizedFactor.cpp +++ b/gtsam/nonlinear/tests/testFunctorizedFactor.cpp @@ -34,9 +34,6 @@ class MultiplyFunctor { double m_; ///< simple multiplier public: - using argument_type = Matrix; - using return_type = Matrix; - MultiplyFunctor(double m) : m_(m) {} Matrix operator()(const Matrix &X, @@ -47,13 +44,13 @@ class MultiplyFunctor { }; /* ************************************************************************* */ +// Test identity operation for FunctorizedFactor. TEST(FunctorizedFactor, Identity) { Matrix X = Matrix::Identity(3, 3), measurement = Matrix::Identity(3, 3); double multiplier = 1.0; - - FunctorizedFactor factor(key, measurement, model, - MultiplyFunctor(multiplier)); + auto functor = MultiplyFunctor(multiplier); + auto factor = MakeFunctorizedFactor(key, measurement, model, functor); Vector error = factor.evaluateError(X); @@ -61,41 +58,45 @@ TEST(FunctorizedFactor, Identity) { } /* ************************************************************************* */ +// Test FunctorizedFactor with multiplier value of 2. TEST(FunctorizedFactor, Multiply2) { double multiplier = 2.0; Matrix X = Matrix::Identity(3, 3); Matrix measurement = multiplier * Matrix::Identity(3, 3); - FunctorizedFactor factor(key, measurement, model, - MultiplyFunctor(multiplier)); + auto factor = MakeFunctorizedFactor(key, measurement, model, + MultiplyFunctor(multiplier)); Vector error = factor.evaluateError(X); EXPECT(assert_equal(Vector::Zero(9), error, 1e-9)); } +/* ************************************************************************* */ +// Test equality function for FunctorizedFactor. TEST(FunctorizedFactor, Equality) { Matrix measurement = Matrix::Identity(2, 2); double multiplier = 2.0; - FunctorizedFactor factor1(key, measurement, model, - MultiplyFunctor(multiplier)); - FunctorizedFactor factor2(key, measurement, model, - MultiplyFunctor(multiplier)); + auto factor1 = MakeFunctorizedFactor(key, measurement, model, + MultiplyFunctor(multiplier)); + auto factor2 = MakeFunctorizedFactor(key, measurement, model, + MultiplyFunctor(multiplier)); EXPECT(factor1.equals(factor2)); } -//****************************************************************************** +/* *************************************************************************** */ +// Test Jacobians of FunctorizedFactor. TEST(FunctorizedFactor, Jacobians) { Matrix X = Matrix::Identity(3, 3); Matrix actualH; double multiplier = 2.0; - FunctorizedFactor factor(key, X, model, - MultiplyFunctor(multiplier)); + auto factor = + MakeFunctorizedFactor(key, X, model, MultiplyFunctor(multiplier)); Values values; values.insert(key, X); @@ -105,13 +106,14 @@ TEST(FunctorizedFactor, Jacobians) { } /* ************************************************************************* */ +// Test print result of FunctorizedFactor. TEST(FunctorizedFactor, Print) { Matrix X = Matrix::Identity(2, 2); double multiplier = 2.0; - FunctorizedFactor factor(key, X, model, - MultiplyFunctor(multiplier)); + auto factor = + MakeFunctorizedFactor(key, X, model, MultiplyFunctor(multiplier)); // redirect output to buffer so we can compare stringstream buffer; @@ -137,7 +139,7 @@ TEST(FunctorizedFactor, Print) { } /* ************************************************************************* */ -// Test factor using a std::function type. +// Test FunctorizedFactor using a std::function type. TEST(FunctorizedFactor, Functional) { double multiplier = 2.0; Matrix X = Matrix::Identity(3, 3); @@ -145,7 +147,8 @@ TEST(FunctorizedFactor, Functional) { std::function)> functional = MultiplyFunctor(multiplier); - FunctorizedFactor factor(key, measurement, model, functional); + auto factor = + MakeFunctorizedFactor(key, measurement, model, functional); Vector error = factor.evaluateError(X); @@ -153,6 +156,7 @@ TEST(FunctorizedFactor, Functional) { } /* ************************************************************************* */ +// Test FunctorizedFactor with a lambda function. TEST(FunctorizedFactor, Lambda) { double multiplier = 2.0; Matrix X = Matrix::Identity(3, 3); @@ -166,15 +170,14 @@ TEST(FunctorizedFactor, Lambda) { return multiplier * X; }; // FunctorizedFactor factor(key, measurement, model, lambda); - auto factor = FunctorizedFactor(key, measurement, model, lambda); + auto factor = MakeFunctorizedFactor(key, measurement, model, lambda); Vector error = factor.evaluateError(X); EXPECT(assert_equal(Vector::Zero(9), error, 1e-9)); } -/* ************************************************************************* - */ +/* ************************************************************************* */ int main() { TestResult tr; return TestRegistry::runAllTests(tr); From 683e37f14889701b5acd40797d6a5a0648c2e601 Mon Sep 17 00:00:00 2001 From: Fan Jiang Date: Mon, 6 Jul 2020 23:36:17 -0400 Subject: [PATCH 148/869] Fix FrobeniusWormholeFactor Python test --- cython/gtsam/tests/test_FrobeniusFactor.py | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/cython/gtsam/tests/test_FrobeniusFactor.py b/cython/gtsam/tests/test_FrobeniusFactor.py index 82d1fb410..f3f5354bb 100644 --- a/cython/gtsam/tests/test_FrobeniusFactor.py +++ b/cython/gtsam/tests/test_FrobeniusFactor.py @@ -12,7 +12,7 @@ Author: Frank Dellaert import unittest import numpy as np -from gtsam import (SO3, SO4, FrobeniusBetweenFactorSO4, FrobeniusFactorSO4, +from gtsam import (Rot3, SO3, SO4, FrobeniusBetweenFactorSO4, FrobeniusFactorSO4, FrobeniusWormholeFactor, SOn) id = SO4() @@ -43,7 +43,7 @@ class TestFrobeniusFactorSO4(unittest.TestCase): """Test creation of a factor that calculates Shonan error.""" R1 = SO3.Expmap(v1[3:]) R2 = SO3.Expmap(v2[3:]) - factor = FrobeniusWormholeFactor(1, 2, R1.between(R2), p=4) + factor = FrobeniusWormholeFactor(1, 2, Rot3(R1.between(R2).matrix()), p=4) I4 = SOn(4) Q1 = I4.retract(v1) Q2 = I4.retract(v2) From 66570469c5f890af0245ec0b1334c9a9c1294782 Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Tue, 7 Jul 2020 17:38:27 -0400 Subject: [PATCH 149/869] fix working directory for python install target --- cython/CMakeLists.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/cython/CMakeLists.txt b/cython/CMakeLists.txt index 65a9e9c62..221025575 100644 --- a/cython/CMakeLists.txt +++ b/cython/CMakeLists.txt @@ -7,7 +7,7 @@ if (GTSAM_INSTALL_CYTHON_TOOLBOX) set(python_install_target python-install) add_custom_target(${python_install_target} COMMAND ${PYTHON_EXECUTABLE} ${GTSAM_CYTHON_INSTALL_PATH}/setup.py install - WORKING_DIRECTORY ${GTSAM_CYTHON_INSTALL_FULLPATH}) + WORKING_DIRECTORY ${GTSAM_CYTHON_INSTALL_PATH}) # build and include the eigency version of eigency add_subdirectory(gtsam_eigency) From 73007fe0483c81f72b05220b8d0a45b8eb18a363 Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Tue, 7 Jul 2020 19:24:38 -0400 Subject: [PATCH 150/869] test SmartFactor when body_P_sensor is passed in --- gtsam/slam/SmartFactorBase.h | 7 ++-- gtsam/slam/tests/testSmartFactorBase.cpp | 42 +++++++++++++++++++++--- 2 files changed, 41 insertions(+), 8 deletions(-) diff --git a/gtsam/slam/SmartFactorBase.h b/gtsam/slam/SmartFactorBase.h index 717a9c1f2..3bedf599f 100644 --- a/gtsam/slam/SmartFactorBase.h +++ b/gtsam/slam/SmartFactorBase.h @@ -206,11 +206,12 @@ protected: boost::optional E = boost::none) const { Vector ue = cameras.reprojectionError(point, measured_, Fs, E); if (body_P_sensor_ && Fs) { - const Pose3 sensor_P_body = body_P_sensor_->inverse(); + const Pose3 sensor_T_body = body_P_sensor_->inverse(); for (size_t i = 0; i < Fs->size(); i++) { - const Pose3 w_Pose_body = cameras[i].pose() * sensor_P_body; + const Pose3 world_T_body = cameras[i].pose() * sensor_T_body; Matrix J(6, 6); - const Pose3 world_P_body = w_Pose_body.compose(*body_P_sensor_, J); + // Call compose to compute Jacobian + world_T_body.compose(*body_P_sensor_, J); Fs->at(i) = Fs->at(i) * J; } } diff --git a/gtsam/slam/tests/testSmartFactorBase.cpp b/gtsam/slam/tests/testSmartFactorBase.cpp index f69f4c113..bb04ad56d 100644 --- a/gtsam/slam/tests/testSmartFactorBase.cpp +++ b/gtsam/slam/tests/testSmartFactorBase.cpp @@ -37,11 +37,11 @@ class PinholeFactor: public SmartFactorBase > { public: typedef SmartFactorBase > Base; PinholeFactor() {} - PinholeFactor(const SharedNoiseModel& sharedNoiseModel): Base(sharedNoiseModel) { - } - virtual double error(const Values& values) const { - return 0.0; - } + PinholeFactor(const SharedNoiseModel& sharedNoiseModel, + boost::optional body_P_sensor = boost::none, + size_t expectedNumberCameras = 10) + : Base(sharedNoiseModel, body_P_sensor, expectedNumberCameras) {} + virtual double error(const Values& values) const { return 0.0; } virtual boost::shared_ptr linearize( const Values& values) const { return boost::shared_ptr(new JacobianFactor()); @@ -60,6 +60,38 @@ TEST(SmartFactorBase, Pinhole) { EXPECT_LONGS_EQUAL(2 * 2, f.dim()); } +TEST(SmartFactorBase, PinholeWithSensor) { + Pose3 body_P_sensor(Rot3(), Point3(1, 0, 0)); + PinholeFactor f = PinholeFactor(unit2, body_P_sensor); + EXPECT(assert_equal(f.body_P_sensor(), body_P_sensor)); + + PinholeFactor::Cameras cameras; + // Assume body at origin. + Pose3 world_T_body = Pose3(); + // Camera coordinates in world frame. + Pose3 wTc = world_T_body * body_P_sensor; + cameras.push_back(PinholeCamera(wTc)); + + // Simple point to project slightly off image center + Point3 p(0, 0, 10); + Point2 measurement = cameras[0].project(p); + f.add(measurement, 1); + + PinholeFactor::Cameras::FBlocks Fs; + Matrix E; + Vector error = f.unwhitenedError(cameras, p, Fs, E); + + Vector expectedError = Vector::Zero(2); + Matrix29 expectedFs; + expectedFs << -0.001, -1.00001, 0, -0.1, 0, -0.01, 0, 0, 0, 1, 0, 0, 0, -0.1, 0, 0, 0, 0; + Matrix23 expectedE; + expectedE << 0.1, 0, 0.01, 0, 0.1, 0; + + EXPECT(assert_equal(error, expectedError)); + EXPECT(assert_equal(expectedFs, Fs[0])); // We only have the jacobian for the 1 camera + EXPECT(assert_equal(expectedE, E)); +} + /* ************************************************************************* */ #include From e3712772cbdfa2f0e851e80241d46236c901c7b9 Mon Sep 17 00:00:00 2001 From: Thomas Jespersen Date: Wed, 8 Jul 2020 00:05:38 +0800 Subject: [PATCH 151/869] ISAM2 Kitti example: Addressed review comments --- examples/IMUKittiExampleGPS.cpp | 380 ++++++++++++++++++-------------- 1 file changed, 220 insertions(+), 160 deletions(-) diff --git a/examples/IMUKittiExampleGPS.cpp b/examples/IMUKittiExampleGPS.cpp index 9f302ab2f..7cfccbc11 100644 --- a/examples/IMUKittiExampleGPS.cpp +++ b/examples/IMUKittiExampleGPS.cpp @@ -24,241 +24,301 @@ #include #include #include -#include #include #include + #include #include #include -using namespace gtsam; using namespace std; +using namespace gtsam; -using symbol_shorthand::X; // Pose3 (x,y,z,r,p,y) -using symbol_shorthand::V; // Vel (xdot,ydot,zdot) -using symbol_shorthand::B; // Bias (ax,ay,az,gx,gy,gz) +using symbol_shorthand::X; // Pose3 (x,y,z,r,p,y) +using symbol_shorthand::V; // Vel (xdot,ydot,zdot) +using symbol_shorthand::B; // Bias (ax,ay,az,gx,gy,gz) -typedef struct { - double Time; +struct KittiCalibration { + double body_ptx; + double body_pty; + double body_ptz; + double body_prx; + double body_pry; + double body_prz; + double accelerometer_sigma; + double gyroscope_sigma; + double integration_sigma; + double accelerometer_bias_sigma; + double gyroscope_bias_sigma; + double average_delta_t; +}; + +struct ImuMeasurement { + double time; double dt; - Vector3 Accelerometer; - Vector3 Gyroscope; // omega -} imuMeasurement_t; + Vector3 accelerometer; + Vector3 gyroscope; // omega +}; -typedef struct { - double Time; - Vector3 Position; // x,y,z -} gpsMeasurement_t; +struct GpsMeasurement { + double time; + Vector3 position; // x,y,z +}; -const string output_filename = "IMUKittyExampleGPSResults.csv"; +const string output_filename = "IMUKittiExampleGPSResults.csv"; -int main(int argc, char* argv[]) -{ +void loadKittiData(KittiCalibration& kitti_calibration, + vector& imu_measurements, + vector& gps_measurements) { string line; // Read IMU metadata and compute relative sensor pose transforms - // BodyPtx BodyPty BodyPtz BodyPrx BodyPry BodyPrz AccelerometerSigma GyroscopeSigma IntegrationSigma AccelerometerBiasSigma GyroscopeBiasSigma AverageDeltaT - // 0 0 0 0 0 0 0.01 0.000175 0 0.000167 2.91e-006 0.0100395199348279 - string IMU_metadata_file = findExampleDataFile("KittiEquivBiasedImu_metadata.txt"); - ifstream IMU_metadata(IMU_metadata_file.c_str()); + // BodyPtx BodyPty BodyPtz BodyPrx BodyPry BodyPrz AccelerometerSigma GyroscopeSigma IntegrationSigma + // AccelerometerBiasSigma GyroscopeBiasSigma AverageDeltaT + string imu_metadata_file = findExampleDataFile("KittiEquivBiasedImu_metadata.txt"); + ifstream imu_metadata(imu_metadata_file.c_str()); printf("-- Reading sensor metadata\n"); - getline(IMU_metadata, line, '\n'); // ignore the first line + getline(imu_metadata, line, '\n'); // ignore the first line - double BodyPtx, BodyPty, BodyPtz, BodyPrx, BodyPry, BodyPrz, AccelerometerSigma, GyroscopeSigma, IntegrationSigma, AccelerometerBiasSigma, GyroscopeBiasSigma, AverageDeltaT; - getline(IMU_metadata, line, '\n'); - sscanf(line.c_str(), "%lf %lf %lf %lf %lf %lf %lf %lf %lf %lf %lf %lf", &BodyPtx, &BodyPty, &BodyPtz, &BodyPrx, &BodyPry, &BodyPrz, &AccelerometerSigma, &GyroscopeSigma, &IntegrationSigma, &AccelerometerBiasSigma, &GyroscopeBiasSigma, &AverageDeltaT); - printf("IMU metadata: %lf %lf %lf %lf %lf %lf %lf %lf %lf %lf %lf %lf\n", BodyPtx, BodyPty, BodyPtz, BodyPrx, BodyPry, BodyPrz, AccelerometerSigma, GyroscopeSigma, IntegrationSigma, AccelerometerBiasSigma, GyroscopeBiasSigma, AverageDeltaT); + // Load Kitti calibration + getline(imu_metadata, line, '\n'); + sscanf(line.c_str(), "%lf %lf %lf %lf %lf %lf %lf %lf %lf %lf %lf %lf", + &kitti_calibration.body_ptx, + &kitti_calibration.body_pty, + &kitti_calibration.body_ptz, + &kitti_calibration.body_prx, + &kitti_calibration.body_pry, + &kitti_calibration.body_prz, + &kitti_calibration.accelerometer_sigma, + &kitti_calibration.gyroscope_sigma, + &kitti_calibration.integration_sigma, + &kitti_calibration.accelerometer_bias_sigma, + &kitti_calibration.gyroscope_bias_sigma, + &kitti_calibration.average_delta_t); + printf("IMU metadata: %lf %lf %lf %lf %lf %lf %lf %lf %lf %lf %lf %lf\n", + kitti_calibration.body_ptx, + kitti_calibration.body_pty, + kitti_calibration.body_ptz, + kitti_calibration.body_prx, + kitti_calibration.body_pry, + kitti_calibration.body_prz, + kitti_calibration.accelerometer_sigma, + kitti_calibration.gyroscope_sigma, + kitti_calibration.integration_sigma, + kitti_calibration.accelerometer_bias_sigma, + kitti_calibration.gyroscope_bias_sigma, + kitti_calibration.average_delta_t); - Vector6 BodyP = (Vector(6) << BodyPtx, BodyPty, BodyPtz, BodyPrx, BodyPry, BodyPrz).finished(); + // Read IMU data + // Time dt accelX accelY accelZ omegaX omegaY omegaZ + string imu_data_file = findExampleDataFile("KittiEquivBiasedImu.txt"); + printf("-- Reading IMU measurements from file\n"); + { + ifstream imu_data(imu_data_file.c_str()); + getline(imu_data, line, '\n'); // ignore the first line + + double time = 0, dt = 0, acc_x = 0, acc_y = 0, acc_z = 0, gyro_x = 0, gyro_y = 0, gyro_z = 0; + while (!imu_data.eof()) { + getline(imu_data, line, '\n'); + sscanf(line.c_str(), "%lf %lf %lf %lf %lf %lf %lf %lf", + &time, &dt, + &acc_x, &acc_y, &acc_z, + &gyro_x, &gyro_y, &gyro_z); + + ImuMeasurement measurement; + measurement.time = time; + measurement.dt = dt; + measurement.accelerometer = Vector3(acc_x, acc_y, acc_z); + measurement.gyroscope = Vector3(gyro_x, gyro_y, gyro_z); + imu_measurements.push_back(measurement); + } + } + + // Read GPS data + // Time,X,Y,Z + string gps_data_file = findExampleDataFile("KittiGps_converted.txt"); + printf("-- Reading GPS measurements from file\n"); + { + ifstream gps_data(gps_data_file.c_str()); + getline(gps_data, line, '\n'); // ignore the first line + + double time = 0, gps_x = 0, gps_y = 0, gps_z = 0; + while (!gps_data.eof()) { + getline(gps_data, line, '\n'); + sscanf(line.c_str(), "%lf,%lf,%lf,%lf", &time, &gps_x, &gps_y, &gps_z); + + GpsMeasurement measurement; + measurement.time = time; + measurement.position = Vector3(gps_x, gps_y, gps_z); + gps_measurements.push_back(measurement); + } + } +} + +int main(int argc, char* argv[]) { + KittiCalibration kitti_calibration; + vector imu_measurements; + vector gps_measurements; + loadKittiData(kitti_calibration, imu_measurements, gps_measurements); + + Vector6 BodyP = (Vector(6) << kitti_calibration.body_ptx, kitti_calibration.body_pty, kitti_calibration.body_ptz, + kitti_calibration.body_prx, kitti_calibration.body_pry, kitti_calibration.body_prz) + .finished(); auto body_T_imu = Pose3::Expmap(BodyP); if (!body_T_imu.equals(Pose3(), 1e-5)) { printf("Currently only support IMUinBody is identity, i.e. IMU and body frame are the same"); exit(-1); } - // Read IMU data - // Time dt accelX accelY accelZ omegaX omegaY omegaZ - // 46534.47837579 46534.47837579 1.7114864219577 0.1717911743144 9.80533438749 -0.0032006241515747 0.031231284764596 -0.0063569265706488 - vector IMU_measurements; - string IMU_data_file = findExampleDataFile("KittiEquivBiasedImu.txt"); - - printf("-- Reading IMU measurements from file\n"); - { - ifstream IMU_data(IMU_data_file.c_str()); - getline(IMU_data, line, '\n'); // ignore the first line - - double time = 0, dt = 0, acc_x = 0, acc_y = 0, acc_z = 0, gyro_x = 0, gyro_y = 0, gyro_z = 0; - while (!IMU_data.eof()) { - getline(IMU_data, line, '\n'); - sscanf(line.c_str(), "%lf %lf %lf %lf %lf %lf %lf %lf", &time, &dt, &acc_x, &acc_y, &acc_z, &gyro_x, - &gyro_y, &gyro_z); - - imuMeasurement_t measurement; - measurement.Time = time; - measurement.dt = dt; - measurement.Accelerometer = Vector3(acc_x, acc_y, acc_z); - measurement.Gyroscope = Vector3(gyro_x, gyro_y, gyro_z); - IMU_measurements.push_back(measurement); - } - } - - // Read GPS data - // Time,X,Y,Z - // 46534.478375790000428,-6.8269361350059405424,-11.868164241239471224,0.040306091310000624617 - vector GPS_measurements; - string GPS_data_file = findExampleDataFile("KittiGps_converted.txt"); - - printf("-- Reading GPS measurements from file\n"); - { - ifstream GPS_data(GPS_data_file.c_str()); - getline(GPS_data, line, '\n'); // ignore the first line - - double time = 0, gps_x = 0, gps_y = 0, gps_z = 0; - while (!GPS_data.eof()) { - getline(GPS_data, line, '\n'); - sscanf(line.c_str(), "%lf,%lf,%lf,%lf", &time, &gps_x, &gps_y, &gps_z); - - gpsMeasurement_t measurement; - measurement.Time = time; - measurement.Position = Vector3(gps_x, gps_y, gps_z); - GPS_measurements.push_back(measurement); - } - } - // Configure different variables - double tOffset = GPS_measurements[0].Time; - size_t firstGPSPose = 1; - size_t GPSskip = 10; // Skip this many GPS measurements each time + double t_offset = gps_measurements[0].time; + size_t first_gps_pose = 1; + size_t gps_skip = 10; // Skip this many GPS measurements each time double g = 9.8; - auto w_coriolis = Vector3(); // zero vector + auto w_coriolis = Vector3(); // zero vector // Configure noise models - noiseModel::Diagonal::shared_ptr noiseModelGPS = noiseModel::Diagonal::Precisions((Vector(6) << Vector3::Constant(0), Vector3::Constant(1.0/0.07)).finished()); + auto noise_model_gps = noiseModel::Diagonal::Precisions((Vector(6) << Vector3::Constant(0), + Vector3::Constant(1.0/0.07)) + .finished()); // Set initial conditions for the estimated trajectory - auto currentPoseGlobal = Pose3(Rot3(), GPS_measurements[firstGPSPose].Position); // initial pose is the reference frame (navigation frame) - auto currentVelocityGlobal = Vector3(); // the vehicle is stationary at the beginning at position 0,0,0 - auto currentBias = imuBias::ConstantBias(); // init with zero bias + // initial pose is the reference frame (navigation frame) + auto current_pose_global = Pose3(Rot3(), gps_measurements[first_gps_pose].position); + auto current_velocity_global = Vector3(); // the vehicle is stationary at the beginning at position 0,0,0 + auto current_bias = imuBias::ConstantBias(); // init with zero bias - noiseModel::Diagonal::shared_ptr sigma_init_x = noiseModel::Isotropic::Precisions((Vector(6) << Vector3::Constant(0), Vector3::Constant(1.0)).finished()); - noiseModel::Diagonal::shared_ptr sigma_init_v = noiseModel::Isotropic::Sigma(3, 1000.0); - noiseModel::Diagonal::shared_ptr sigma_init_b = noiseModel::Isotropic::Sigmas((Vector(6) << Vector3::Constant(0.100), Vector3::Constant(5.00e-05)).finished()); + auto sigma_init_x = noiseModel::Diagonal::Precisions((Vector(6) << Vector3::Constant(0), + Vector3::Constant(1.0)) + .finished()); + auto sigma_init_v = noiseModel::Diagonal::Sigmas(Vector3::Constant(1000.0)); + auto sigma_init_b = noiseModel::Diagonal::Sigmas((Vector(6) << Vector3::Constant(0.100), + Vector3::Constant(5.00e-05)) + .finished()); // Set IMU preintegration parameters - Matrix33 measured_acc_cov = Matrix33::Identity(3,3) * pow(AccelerometerSigma,2); - Matrix33 measured_omega_cov = Matrix33::Identity(3,3) * pow(GyroscopeSigma,2); - Matrix33 integration_error_cov = Matrix33::Identity(3,3) * pow(IntegrationSigma,2); // error committed in integrating position from velocities + Matrix33 measured_acc_cov = I_3x3 * pow(kitti_calibration.accelerometer_sigma, 2); + Matrix33 measured_omega_cov = I_3x3 * pow(kitti_calibration.gyroscope_sigma, 2); + // error committed in integrating position from velocities + Matrix33 integration_error_cov = I_3x3 * pow(kitti_calibration.integration_sigma, 2); - boost::shared_ptr IMU_params = PreintegratedImuMeasurements::Params::MakeSharedU(g); - IMU_params->accelerometerCovariance = measured_acc_cov; // acc white noise in continuous - IMU_params->integrationCovariance = integration_error_cov; // integration uncertainty continuous - IMU_params->gyroscopeCovariance = measured_omega_cov; // gyro white noise in continuous - IMU_params->omegaCoriolis = w_coriolis; + auto imu_params = PreintegratedImuMeasurements::Params::MakeSharedU(g); + imu_params->accelerometerCovariance = measured_acc_cov; // acc white noise in continuous + imu_params->integrationCovariance = integration_error_cov; // integration uncertainty continuous + imu_params->gyroscopeCovariance = measured_omega_cov; // gyro white noise in continuous + imu_params->omegaCoriolis = w_coriolis; - std::shared_ptr currentSummarizedMeasurement = nullptr; + std::shared_ptr current_summarized_measurement = nullptr; // Set ISAM2 parameters and create ISAM2 solver object - ISAM2Params isamParams; - isamParams.factorization = ISAM2Params::CHOLESKY; - isamParams.relinearizeSkip = 10; + ISAM2Params isam_params; + isam_params.factorization = ISAM2Params::CHOLESKY; + isam_params.relinearizeSkip = 10; - ISAM2 isam(isamParams); + ISAM2 isam(isam_params); // Create the factor graph and values object that will store new factors and values to add to the incremental graph - NonlinearFactorGraph newFactors; - Values newValues; // values storing the initial estimates of new nodes in the factor graph + NonlinearFactorGraph new_factors; + Values new_values; // values storing the initial estimates of new nodes in the factor graph /// Main loop: /// (1) we read the measurements /// (2) we create the corresponding factors in the graph /// (3) we solve the graph to obtain and optimal estimate of robot trajectory printf("-- Starting main loop: inference is performed at each time step, but we plot trajectory every 10 steps\n"); - size_t imuMeasurementIndex = 0; - for (size_t gpsMeasurementIndex = firstGPSPose; gpsMeasurementIndex < GPS_measurements.size() - 1; gpsMeasurementIndex++) { + size_t j = 0; + for (size_t i = first_gps_pose; i < gps_measurements.size() - 1; i++) { // At each non=IMU measurement we initialize a new node in the graph - auto currentPoseKey = X(gpsMeasurementIndex); - auto currentVelKey = V(gpsMeasurementIndex); - auto currentBiasKey = B(gpsMeasurementIndex); - double t = GPS_measurements[gpsMeasurementIndex].Time; + auto current_pose_key = X(i); + auto current_vel_key = V(i); + auto current_bias_key = B(i); + double t = gps_measurements[i].time; - if (gpsMeasurementIndex == firstGPSPose) { + if (i == first_gps_pose) { // Create initial estimate and prior on initial pose, velocity, and biases - newValues.insert(currentPoseKey, currentPoseGlobal); - newValues.insert(currentVelKey, currentVelocityGlobal); - newValues.insert(currentBiasKey, currentBias); - newFactors.add(PriorFactor(currentPoseKey, currentPoseGlobal, sigma_init_x)); - newFactors.add(PriorFactor(currentVelKey, currentVelocityGlobal, sigma_init_v)); - newFactors.add(PriorFactor(currentBiasKey, currentBias, sigma_init_b)); + new_values.insert(current_pose_key, current_pose_global); + new_values.insert(current_vel_key, current_velocity_global); + new_values.insert(current_bias_key, current_bias); + new_factors.emplace_shared>(current_pose_key, current_pose_global, sigma_init_x); + new_factors.emplace_shared>(current_vel_key, current_velocity_global, sigma_init_v); + new_factors.emplace_shared>(current_bias_key, current_bias, sigma_init_b); } else { - double t_previous = GPS_measurements[gpsMeasurementIndex-1].Time; + double t_previous = gps_measurements[i-1].time; // Summarize IMU data between the previous GPS measurement and now - currentSummarizedMeasurement = std::make_shared(IMU_params, currentBias); - static size_t includedIMUmeasurementCount = 0; - while (imuMeasurementIndex < IMU_measurements.size() && IMU_measurements[imuMeasurementIndex].Time <= t) { - if (IMU_measurements[imuMeasurementIndex].Time >= t_previous) { - currentSummarizedMeasurement->integrateMeasurement(IMU_measurements[imuMeasurementIndex].Accelerometer, IMU_measurements[imuMeasurementIndex].Gyroscope, IMU_measurements[imuMeasurementIndex].dt); - includedIMUmeasurementCount++; + current_summarized_measurement = std::make_shared(imu_params, current_bias); + static size_t included_imu_measurement_count = 0; + while (j < imu_measurements.size() && imu_measurements[j].time <= t) { + if (imu_measurements[j].time >= t_previous) { + current_summarized_measurement->integrateMeasurement(imu_measurements[j].accelerometer, + imu_measurements[j].gyroscope, + imu_measurements[j].dt); + included_imu_measurement_count++; } - imuMeasurementIndex++; + j++; } // Create IMU factor - auto previousPoseKey = X(gpsMeasurementIndex-1); - auto previousVelKey = V(gpsMeasurementIndex-1); - auto previousBiasKey = B(gpsMeasurementIndex-1); + auto previous_pose_key = X(i-1); + auto previous_vel_key = V(i-1); + auto previous_bias_key = B(i-1); - newFactors.add(ImuFactor( - previousPoseKey, previousVelKey, - currentPoseKey, currentVelKey, - previousBiasKey, *currentSummarizedMeasurement)); + new_factors.emplace_shared(previous_pose_key, previous_vel_key, + current_pose_key, current_vel_key, + previous_bias_key, *current_summarized_measurement); // Bias evolution as given in the IMU metadata - noiseModel::Diagonal::shared_ptr sigma_between_b = noiseModel::Diagonal::Sigmas((Vector(6) << Vector3::Constant(sqrt(includedIMUmeasurementCount) * AccelerometerBiasSigma), Vector3::Constant(sqrt(includedIMUmeasurementCount) * GyroscopeBiasSigma)).finished()); - newFactors.add(BetweenFactor(previousBiasKey, currentBiasKey, imuBias::ConstantBias(), sigma_between_b)); + auto sigma_between_b = noiseModel::Diagonal::Sigmas((Vector(6) << + Vector3::Constant(sqrt(included_imu_measurement_count) * kitti_calibration.accelerometer_bias_sigma), + Vector3::Constant(sqrt(included_imu_measurement_count) * kitti_calibration.gyroscope_bias_sigma)) + .finished()); + new_factors.emplace_shared>(previous_bias_key, + current_bias_key, + imuBias::ConstantBias(), + sigma_between_b); // Create GPS factor - auto GPSPose = Pose3(currentPoseGlobal.rotation(), GPS_measurements[gpsMeasurementIndex].Position); - if ((gpsMeasurementIndex % GPSskip) == 0) { - newFactors.add(PriorFactor(currentPoseKey, GPSPose, noiseModelGPS)); - newValues.insert(currentPoseKey, GPSPose); + auto gps_pose = Pose3(current_pose_global.rotation(), gps_measurements[i].position); + if ((i % gps_skip) == 0) { + new_factors.emplace_shared>(current_pose_key, gps_pose, noise_model_gps); + new_values.insert(current_pose_key, gps_pose); printf("################ POSE INCLUDED AT TIME %lf ################\n", t); - GPSPose.translation().print(); + gps_pose.translation().print(); printf("\n\n"); } else { - newValues.insert(currentPoseKey, currentPoseGlobal); + new_values.insert(current_pose_key, current_pose_global); } // Add initial values for velocity and bias based on the previous estimates - newValues.insert(currentVelKey, currentVelocityGlobal); - newValues.insert(currentBiasKey, currentBias); + new_values.insert(current_vel_key, current_velocity_global); + new_values.insert(current_bias_key, current_bias); // Update solver // ======================================================================= // We accumulate 2*GPSskip GPS measurements before updating the solver at - //first so that the heading becomes observable. - if (gpsMeasurementIndex > (firstGPSPose + 2*GPSskip)) { + // first so that the heading becomes observable. + if (i > (first_gps_pose + 2*gps_skip)) { printf("################ NEW FACTORS AT TIME %lf ################\n", t); - newFactors.print(); + new_factors.print(); - isam.update(newFactors, newValues); + isam.update(new_factors, new_values); // Reset the newFactors and newValues list - newFactors.resize(0); - newValues.clear(); + new_factors.resize(0); + new_values.clear(); // Extract the result/current estimates Values result = isam.calculateEstimate(); - currentPoseGlobal = result.at(currentPoseKey); - currentVelocityGlobal = result.at(currentVelKey); - currentBias = result.at(currentBiasKey); + current_pose_global = result.at(current_pose_key); + current_velocity_global = result.at(current_vel_key); + current_bias = result.at(current_bias_key); printf("\n################ POSE AT TIME %lf ################\n", t); - currentPoseGlobal.print(); + current_pose_global.print(); printf("\n\n"); } } @@ -270,24 +330,24 @@ int main(int argc, char* argv[]) fprintf(fp_out, "#time(s),x(m),y(m),z(m),qx,qy,qz,qw,gt_x(m),gt_y(m),gt_z(m)\n"); Values result = isam.calculateEstimate(); - for (size_t gpsMeasurementIndex = firstGPSPose; gpsMeasurementIndex < GPS_measurements.size() - 1; gpsMeasurementIndex++) { - auto poseKey = X(gpsMeasurementIndex); - auto velKey = V(gpsMeasurementIndex); - auto biasKey = B(gpsMeasurementIndex); + for (size_t i = first_gps_pose; i < gps_measurements.size() - 1; i++) { + auto pose_key = X(i); + auto vel_key = V(i); + auto bias_key = B(i); - auto pose = result.at(poseKey); - auto velocity = result.at(velKey); - auto bias = result.at(biasKey); + auto pose = result.at(pose_key); + auto velocity = result.at(vel_key); + auto bias = result.at(bias_key); auto pose_quat = pose.rotation().toQuaternion(); - auto gps = GPS_measurements[gpsMeasurementIndex].Position; + auto gps = gps_measurements[i].position; fprintf(fp_out, "%f,%f,%f,%f,%f,%f,%f,%f,%f,%f,%f\n", - GPS_measurements[gpsMeasurementIndex].Time, + gps_measurements[i].time, pose.x(), pose.y(), pose.z(), pose_quat.x(), pose_quat.y(), pose_quat.z(), pose_quat.w(), gps(0), gps(1), gps(2)); } fclose(fp_out); -} \ No newline at end of file +} From 23ed11549e4a49be712cad70c545c7f2fc1a4164 Mon Sep 17 00:00:00 2001 From: akrishnan86 Date: Tue, 7 Jul 2020 23:40:57 -0700 Subject: [PATCH 152/869] adding tests --- gtsam/sfm/mfas.h | 22 ++++++++- gtsam/sfm/tests/testMFAS.cpp | 90 ++++++++++++++++++++++++++++++++++++ 2 files changed, 111 insertions(+), 1 deletion(-) create mode 100644 gtsam/sfm/tests/testMFAS.cpp diff --git a/gtsam/sfm/mfas.h b/gtsam/sfm/mfas.h index b76064ed6..6aec492c4 100644 --- a/gtsam/sfm/mfas.h +++ b/gtsam/sfm/mfas.h @@ -13,7 +13,6 @@ #define __MFAS_H__ #include -#include #include #include @@ -24,12 +23,33 @@ using KeyPair = std::pair; namespace mfas { +/* + * Given a vector of KeyPairs that constitutes edges in a graph and the weights corresponding to these edges, this + * function changes all the weights to positive numbers by flipping the direction of the edges that have a + * negative weight. The changes are made in place. + * @param edges reference to vector of KeyPairs + * @param weights weights corresponding to edges + */ void flipNegEdges(std::vector &edges, std::vector &weights); +/* + * Computes the MFAS ordering, ie an ordering of the nodes in the graph such that the source of any edge appears before its destination in the ordering. The weight of edges that are removed to obtain this ordering is minimized. + * @param edges: edges in the graph + * @param weights: weights corresponding to the edges (have to be positive) + * @param nodes: nodes in the graph + * @param ordered_positions: map from node to position in the ordering (0 indexed) + */ void mfasRatio(const std::vector &edges, const std::vector &weights, const KeyVector &nodes, FastMap &ordered_positions); +/* + * Returns the weights of edges that are not consistent with the input ordering. + * @param edges in the graph + * @param weights of the edges in the graph + * @param ordered_positions: ordering (obtained from MFAS solution) + * @param broken: reference to a map from edges to their "broken weights" + */ void brokenWeights(const std::vector &edges, const std::vector &weight, const FastMap &ordered_positions, diff --git a/gtsam/sfm/tests/testMFAS.cpp b/gtsam/sfm/tests/testMFAS.cpp new file mode 100644 index 000000000..0c52928c1 --- /dev/null +++ b/gtsam/sfm/tests/testMFAS.cpp @@ -0,0 +1,90 @@ +#include "gtsam/sfm/mfas.h" +#include + +using namespace std; +using namespace gtsam; + +// example from the paper +Key k0(0), k1(1), k2(2), k3(3), k4(4); +KeyPair e3_2(k3, k2), e0_1(k0, k1), e4_2(k4, k2), + e3_1(k3, k1), e4_0(k4, k0), e1_2(k1, k2), + e0_2(k0, k2), out_e3_0(k3, k0); + +vector graph = {make_pair(3, 2), make_pair(0, 1), make_pair(4, 2), + make_pair(3, 1), make_pair(4, 0), + make_pair(1, 2), make_pair(0, 2), make_pair(3, 0)}; +KeyVector nodes = {0, 1, 2, 3, 4}; +vector weights1 = {2, 1.5, -2, -0.5, -0.5, 0.25, 1, 0.75}; + + +TEST(MFAS, FlipNegEdges) { + vector graph_copy = graph; + vector weights1_copy = weights1; + mfas::flipNegEdges(graph_copy, weights1_copy); + + EXPECT_LONGS_EQUAL(graph_copy.size(), graph.size()); + EXPECT_LONGS_EQUAL(weights1_copy.size(), weights1.size()); + + for (int i = 0; i < weights1.size(); i++) { + if (weights1[i] < 0) { + EXPECT_DOUBLES_EQUAL(weights1_copy[i], -weights1[i], 1e-6); + EXPECT(graph_copy[i].first == graph[i].second && + graph_copy[i].second == graph[i].first); + } else { + EXPECT_DOUBLES_EQUAL(weights1_copy[i], weights1[i], 1e-6); + EXPECT(graph_copy[i].first == graph[i].first && + graph_copy[i].second == graph[i].second); + } + } +} + +// TEST(MFAS, Ordering) { + +// } + +TEST(MFAS, OrderingWithoutRemoval) { + vector graph_copy = graph; + vector weights1_copy = weights1; + mfas::flipNegEdges(graph_copy, weights1_copy); + FastMap ordered_positions; + mfas::mfasRatio(graph_copy, weights1_copy, nodes, ordered_positions); + + FastMap gt_ordered_positions; + gt_ordered_positions[4] = 0; + gt_ordered_positions[3] = 1; + gt_ordered_positions[0] = 2; + gt_ordered_positions[1] = 3; + gt_ordered_positions[2] = 4; + + for(auto it = ordered_positions.begin(); it != ordered_positions.end(); ++it) + { + EXPECT_LONGS_EQUAL(gt_ordered_positions[it->first], it->second); + } +} + +TEST(MFAS, BrokenWeights) { + vector graph_copy = graph; + vector weights1_copy = weights1; + mfas::flipNegEdges(graph_copy, weights1_copy); + + FastMap gt_ordered_positions; + gt_ordered_positions[4] = 0; + gt_ordered_positions[3] = 1; + gt_ordered_positions[0] = 2; + gt_ordered_positions[1] = 3; + gt_ordered_positions[2] = 4; + + FastMap broken_weights; + mfas::brokenWeights(graph, weights1_copy, gt_ordered_positions, + broken_weights); + for (auto it = broken_weights.begin(); it != broken_weights.end(); it++) { + EXPECT_LONGS_EQUAL(it->second, 0); + } +} + +/* ************************************************************************* */ +int main() { + TestResult tr; + return TestRegistry::runAllTests(tr); +} +/* ************************************************************************* */ From 00106ba3605201b6d0e0b61076521c974458a6f4 Mon Sep 17 00:00:00 2001 From: Mike Sheffler Date: Wed, 8 Jul 2020 02:30:19 -0700 Subject: [PATCH 153/869] Second attempt at a wrapper fix. 1) Some serialization code was missing from SOn.SOn.h (not sure why this wouldn't have been a problem before building the MATLAB toolbox ...) 2) FrobeniusFacotor stuff needed a couple GTSAM_EXPORT statements --- gtsam/geometry/SOn.h | 17 +++++++++++++++++ gtsam/slam/FrobeniusFactor.h | 4 ++-- 2 files changed, 19 insertions(+), 2 deletions(-) diff --git a/gtsam/geometry/SOn.h b/gtsam/geometry/SOn.h index a08f87783..74b7b8521 100644 --- a/gtsam/geometry/SOn.h +++ b/gtsam/geometry/SOn.h @@ -30,6 +30,9 @@ #include #include + // For save/load +#include + namespace gtsam { namespace internal { @@ -292,6 +295,10 @@ class SO : public LieGroup, internal::DimensionSO(N)> { boost::none) const; /// @} + template + friend void save(Archive&, SO&, const unsigned int); + template + friend void load(Archive&, SO&, const unsigned int); template friend void serialize(Archive&, SO&, const unsigned int); friend class boost::serialization::access; @@ -329,6 +336,16 @@ template <> SOn LieGroup::between(const SOn& g, DynamicJacobian H1, DynamicJacobian H2) const; +/** Serialization function */ +template +void serialize( + Archive& ar, SOn& Q, + const unsigned int file_version +) { + Matrix& M = Q.matrix_; + ar& M; +} + /* * Define the traits. internal::LieGroup provides both Lie group and Testable */ diff --git a/gtsam/slam/FrobeniusFactor.h b/gtsam/slam/FrobeniusFactor.h index 60fa82ab4..a73445ae0 100644 --- a/gtsam/slam/FrobeniusFactor.h +++ b/gtsam/slam/FrobeniusFactor.h @@ -33,7 +33,7 @@ namespace gtsam { * isotropic. If it is, we extend to 'Dim' dimensions, otherwise we throw an * error. If defaultToUnit == false throws an exception on unexepcted input. */ -boost::shared_ptr ConvertPose3NoiseModel( + GTSAM_EXPORT boost::shared_ptr ConvertPose3NoiseModel( const SharedNoiseModel& model, size_t d, bool defaultToUnit = true); /** @@ -125,7 +125,7 @@ class FrobeniusBetweenFactor : public NoiseModelFactor2 { * the SO(p) matrices down to a Stiefel manifold of p*d matrices. * TODO(frank): template on D=2 or 3 */ -class FrobeniusWormholeFactor : public NoiseModelFactor2 { +class GTSAM_EXPORT FrobeniusWormholeFactor : public NoiseModelFactor2 { Matrix M_; ///< measured rotation between R1 and R2 size_t p_, pp_, dimension_; ///< dimensionality constants Matrix G_; ///< matrix of vectorized generators From aaddf52cb102f2a5ab5440c807a1c0871ff81246 Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Wed, 8 Jul 2020 12:23:01 -0400 Subject: [PATCH 154/869] Abstracted out serialization code for PreintegrationBase --- gtsam/navigation/ManifoldPreintegration.h | 4 +--- gtsam/navigation/PreintegrationBase.h | 10 ++++++++++ gtsam/navigation/TangentPreintegration.h | 4 +--- 3 files changed, 12 insertions(+), 6 deletions(-) diff --git a/gtsam/navigation/ManifoldPreintegration.h b/gtsam/navigation/ManifoldPreintegration.h index 22897b9d4..97ad04744 100644 --- a/gtsam/navigation/ManifoldPreintegration.h +++ b/gtsam/navigation/ManifoldPreintegration.h @@ -118,10 +118,8 @@ private: template void serialize(ARCHIVE & ar, const unsigned int /*version*/) { namespace bs = ::boost::serialization; - ar & BOOST_SERIALIZATION_NVP(p_); - ar & BOOST_SERIALIZATION_NVP(deltaTij_); + ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(PreintegrationBase); ar & BOOST_SERIALIZATION_NVP(deltaXij_); - ar & BOOST_SERIALIZATION_NVP(biasHat_); ar & bs::make_nvp("delRdelBiasOmega_", bs::make_array(delRdelBiasOmega_.data(), delRdelBiasOmega_.size())); ar & bs::make_nvp("delPdelBiasAcc_", bs::make_array(delPdelBiasAcc_.data(), delPdelBiasAcc_.size())); ar & bs::make_nvp("delPdelBiasOmega_", bs::make_array(delPdelBiasOmega_.data(), delPdelBiasOmega_.size())); diff --git a/gtsam/navigation/PreintegrationBase.h b/gtsam/navigation/PreintegrationBase.h index eb30c1f13..29d7814b5 100644 --- a/gtsam/navigation/PreintegrationBase.h +++ b/gtsam/navigation/PreintegrationBase.h @@ -213,6 +213,16 @@ class GTSAM_EXPORT PreintegrationBase { /// @} #endif + private: + /** Serialization function */ + friend class boost::serialization::access; + template + void serialize(ARCHIVE & ar, const unsigned int /*version*/) { + ar & BOOST_SERIALIZATION_NVP(p_); + ar & BOOST_SERIALIZATION_NVP(biasHat_); + ar & BOOST_SERIALIZATION_NVP(deltaTij_); + } + public: GTSAM_MAKE_ALIGNED_OPERATOR_NEW }; diff --git a/gtsam/navigation/TangentPreintegration.h b/gtsam/navigation/TangentPreintegration.h index edf76e562..99aa10b3f 100644 --- a/gtsam/navigation/TangentPreintegration.h +++ b/gtsam/navigation/TangentPreintegration.h @@ -132,9 +132,7 @@ private: template void serialize(ARCHIVE & ar, const unsigned int /*version*/) { namespace bs = ::boost::serialization; - ar & BOOST_SERIALIZATION_NVP(p_); - ar & BOOST_SERIALIZATION_NVP(biasHat_); - ar & BOOST_SERIALIZATION_NVP(deltaTij_); + ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(PreintegrationBase); ar & bs::make_nvp("preintegrated_", bs::make_array(preintegrated_.data(), preintegrated_.size())); ar & bs::make_nvp("preintegrated_H_biasAcc_", bs::make_array(preintegrated_H_biasAcc_.data(), preintegrated_H_biasAcc_.size())); ar & bs::make_nvp("preintegrated_H_biasOmega_", bs::make_array(preintegrated_H_biasOmega_.data(), preintegrated_H_biasOmega_.size())); From 283999b017f8c0b41ada170a74030f41ef6c1ca1 Mon Sep 17 00:00:00 2001 From: Mike Sheffler Date: Wed, 8 Jul 2020 11:52:51 -0700 Subject: [PATCH 155/869] Unnecessary include statement --- gtsam/geometry/SOn.h | 3 --- 1 file changed, 3 deletions(-) diff --git a/gtsam/geometry/SOn.h b/gtsam/geometry/SOn.h index 74b7b8521..f44c578cc 100644 --- a/gtsam/geometry/SOn.h +++ b/gtsam/geometry/SOn.h @@ -30,9 +30,6 @@ #include #include - // For save/load -#include - namespace gtsam { namespace internal { From 8d921c82a0af925586f1a3e4f58640ad47afa4db Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Wed, 8 Jul 2020 16:10:33 -0400 Subject: [PATCH 156/869] Updated PreintegratedImuMeasurements docstring --- gtsam/navigation/ImuFactor.h | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/gtsam/navigation/ImuFactor.h b/gtsam/navigation/ImuFactor.h index 8e3f8f0a4..b5cff8147 100644 --- a/gtsam/navigation/ImuFactor.h +++ b/gtsam/navigation/ImuFactor.h @@ -87,8 +87,8 @@ public: /** * Constructor, initializes the class with no measurements - * @param bias Current estimate of acceleration and rotation rate biases - * @param p Parameters, typically fixed in a single application + * @param p Parameters, typically fixed in a single application + * @param biasHat Current estimate of acceleration and rotation rate biases */ PreintegratedImuMeasurements(const boost::shared_ptr& p, const imuBias::ConstantBias& biasHat = imuBias::ConstantBias()) : From f8b48db581730ea484d7307cdac685dcf8b545f9 Mon Sep 17 00:00:00 2001 From: Fan Jiang Date: Wed, 8 Jul 2020 17:10:43 -0400 Subject: [PATCH 157/869] Fix lambda check in logging optimizer --- cython/gtsam/utils/logging_optimizer.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/cython/gtsam/utils/logging_optimizer.py b/cython/gtsam/utils/logging_optimizer.py index b201bb8aa..34f0fe5c9 100644 --- a/cython/gtsam/utils/logging_optimizer.py +++ b/cython/gtsam/utils/logging_optimizer.py @@ -50,5 +50,5 @@ def gtsam_optimize(optimizer: NonlinearOptimizer, def check_convergence(optimizer, current_error, new_error): return (optimizer.iterations() >= params.getMaxIterations()) or ( gtsam.checkConvergence(params.getRelativeErrorTol(), params.getAbsoluteErrorTol(), params.getErrorTol(), - current_error, new_error)) + current_error, new_error)) or (optimizer.lambda_() > params.getlambdaUpperBound()) optimize(optimizer, check_convergence, hook) From cc2456678fb97a1d912f8f419b945a46efba9730 Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Wed, 8 Jul 2020 23:37:32 -0400 Subject: [PATCH 158/869] Replace scoped name with direct name and instantiate base class in constructor --- gtsam/navigation/PreintegratedRotation.cpp | 6 +++--- gtsam/navigation/PreintegrationParams.cpp | 6 +++--- gtsam/navigation/PreintegrationParams.h | 13 +++++++------ 3 files changed, 13 insertions(+), 12 deletions(-) diff --git a/gtsam/navigation/PreintegratedRotation.cpp b/gtsam/navigation/PreintegratedRotation.cpp index 8c29d85dd..c5d48b734 100644 --- a/gtsam/navigation/PreintegratedRotation.cpp +++ b/gtsam/navigation/PreintegratedRotation.cpp @@ -25,7 +25,7 @@ using namespace std; namespace gtsam { -void PreintegratedRotation::Params::print(const string& s) const { +void PreintegratedRotationParams::print(const string& s) const { cout << s << endl; cout << "gyroscopeCovariance:\n[\n" << gyroscopeCovariance << "\n]" << endl; if (omegaCoriolis) @@ -34,8 +34,8 @@ void PreintegratedRotation::Params::print(const string& s) const { body_P_sensor->print("body_P_sensor"); } -bool PreintegratedRotation::Params::equals( - const PreintegratedRotation::Params& other, double tol) const { +bool PreintegratedRotationParams::equals( + const PreintegratedRotationParams& other, double tol) const { if (body_P_sensor) { if (!other.body_P_sensor || !assert_equal(*body_P_sensor, *other.body_P_sensor, tol)) diff --git a/gtsam/navigation/PreintegrationParams.cpp b/gtsam/navigation/PreintegrationParams.cpp index 61cd1617c..2298bb696 100644 --- a/gtsam/navigation/PreintegrationParams.cpp +++ b/gtsam/navigation/PreintegrationParams.cpp @@ -27,7 +27,7 @@ namespace gtsam { //------------------------------------------------------------------------------ void PreintegrationParams::print(const string& s) const { - PreintegratedRotation::Params::print(s); + PreintegratedRotationParams::print(s); cout << "accelerometerCovariance:\n[\n" << accelerometerCovariance << "\n]" << endl; cout << "integrationCovariance:\n[\n" << integrationCovariance << "\n]" @@ -39,10 +39,10 @@ void PreintegrationParams::print(const string& s) const { } //------------------------------------------------------------------------------ -bool PreintegrationParams::equals(const PreintegratedRotation::Params& other, +bool PreintegrationParams::equals(const PreintegratedRotationParams& other, double tol) const { auto e = dynamic_cast(&other); - return e != nullptr && PreintegratedRotation::Params::equals(other, tol) && + return e != nullptr && PreintegratedRotationParams::equals(other, tol) && use2ndOrderCoriolis == e->use2ndOrderCoriolis && equal_with_abs_tol(accelerometerCovariance, e->accelerometerCovariance, tol) && diff --git a/gtsam/navigation/PreintegrationParams.h b/gtsam/navigation/PreintegrationParams.h index 4bff625ca..de9950e7d 100644 --- a/gtsam/navigation/PreintegrationParams.h +++ b/gtsam/navigation/PreintegrationParams.h @@ -31,7 +31,8 @@ struct GTSAM_EXPORT PreintegrationParams: PreintegratedRotationParams { /// Default constructor for serialization only PreintegrationParams() - : accelerometerCovariance(I_3x3), + : PreintegratedRotationParams(), + accelerometerCovariance(I_3x3), integrationCovariance(I_3x3), use2ndOrderCoriolis(false), n_gravity(0, 0, -1) {} @@ -39,7 +40,8 @@ struct GTSAM_EXPORT PreintegrationParams: PreintegratedRotationParams { /// The Params constructor insists on getting the navigation frame gravity vector /// For convenience, two commonly used conventions are provided by named constructors below PreintegrationParams(const Vector3& n_gravity) - : accelerometerCovariance(I_3x3), + : PreintegratedRotationParams(), + accelerometerCovariance(I_3x3), integrationCovariance(I_3x3), use2ndOrderCoriolis(false), n_gravity(n_gravity) {} @@ -54,8 +56,8 @@ struct GTSAM_EXPORT PreintegrationParams: PreintegratedRotationParams { return boost::shared_ptr(new PreintegrationParams(Vector3(0, 0, -g))); } - void print(const std::string& s) const; - bool equals(const PreintegratedRotation::Params& other, double tol) const; + void print(const std::string& s="") const; + bool equals(const PreintegratedRotationParams& other, double tol) const; void setAccelerometerCovariance(const Matrix3& cov) { accelerometerCovariance = cov; } void setIntegrationCovariance(const Matrix3& cov) { integrationCovariance = cov; } @@ -73,8 +75,7 @@ protected: template void serialize(ARCHIVE & ar, const unsigned int /*version*/) { namespace bs = ::boost::serialization; - ar & boost::serialization::make_nvp("PreintegratedRotation_Params", - boost::serialization::base_object(*this)); + ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(PreintegratedRotationParams); ar & bs::make_nvp("accelerometerCovariance", bs::make_array(accelerometerCovariance.data(), accelerometerCovariance.size())); ar & bs::make_nvp("integrationCovariance", bs::make_array(integrationCovariance.data(), integrationCovariance.size())); ar & BOOST_SERIALIZATION_NVP(use2ndOrderCoriolis); From 95b4a49f643efe0a8bdae4c04132cf6b110deab2 Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Thu, 9 Jul 2020 00:22:05 -0400 Subject: [PATCH 159/869] Major updates to CombinedImuFactor to make it Testable as well as serializable --- gtsam/navigation/CombinedImuFactor.cpp | 34 ++++++++ gtsam/navigation/CombinedImuFactor.h | 109 +++++++++++++++++++------ 2 files changed, 116 insertions(+), 27 deletions(-) diff --git a/gtsam/navigation/CombinedImuFactor.cpp b/gtsam/navigation/CombinedImuFactor.cpp index 149067269..7a8c73013 100644 --- a/gtsam/navigation/CombinedImuFactor.cpp +++ b/gtsam/navigation/CombinedImuFactor.cpp @@ -17,9 +17,11 @@ * @author Vadim Indelman * @author David Jensen * @author Frank Dellaert + * @author Varun Agrawal **/ #include +#include /* External or standard includes */ #include @@ -28,6 +30,31 @@ namespace gtsam { using namespace std; +//------------------------------------------------------------------------------ +// Inner class PreintegrationCombinedParams +//------------------------------------------------------------------------------ +void PreintegrationCombinedParams::print(const string& s) const { + PreintegrationParams::print(s); + cout << "biasAccCovariance:\n[\n" << biasAccCovariance << "\n]" + << endl; + cout << "biasOmegaCovariance:\n[\n" << biasOmegaCovariance << "\n]" + << endl; + cout << "biasAccOmegaInt:\n[\n" << biasAccOmegaInt << "\n]" + << endl; +} + +//------------------------------------------------------------------------------ +bool PreintegrationCombinedParams::equals(const PreintegrationParams& other, + double tol) const { + auto e = dynamic_cast(&other); + return e != nullptr && PreintegrationParams::equals(other, tol) && + equal_with_abs_tol(biasAccCovariance, e->biasAccCovariance, + tol) && + equal_with_abs_tol(biasOmegaCovariance, e->biasOmegaCovariance, + tol) && + equal_with_abs_tol(biasAccOmegaInt, e->biasAccOmegaInt, tol); +} + //------------------------------------------------------------------------------ // Inner class PreintegratedCombinedMeasurements //------------------------------------------------------------------------------ @@ -242,6 +269,13 @@ Vector CombinedImuFactor::evaluateError(const Pose3& pose_i, return r; } +//------------------------------------------------------------------------------ +std::ostream& operator<<(std::ostream& os, const CombinedImuFactor& f) { + f._PIM_.print("combined preintegrated measurements:\n"); + os << " noise model sigmas: " << f.noiseModel_->sigmas().transpose(); + return os; +} + //------------------------------------------------------------------------------ #ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V4 CombinedImuFactor::CombinedImuFactor( diff --git a/gtsam/navigation/CombinedImuFactor.h b/gtsam/navigation/CombinedImuFactor.h index 6b3bf979a..7a3a801f1 100644 --- a/gtsam/navigation/CombinedImuFactor.h +++ b/gtsam/navigation/CombinedImuFactor.h @@ -17,6 +17,7 @@ * @author Vadim Indelman * @author David Jensen * @author Frank Dellaert + * @author Varun Agrawal **/ #pragma once @@ -26,6 +27,7 @@ #include #include #include +#include namespace gtsam { @@ -61,10 +63,19 @@ struct GTSAM_EXPORT PreintegrationCombinedParams : PreintegrationParams { Matrix3 biasOmegaCovariance; ///< continuous-time "Covariance" describing gyroscope bias random walk Matrix6 biasAccOmegaInt; ///< covariance of bias used for pre-integration + /// Default constructor makes unitialized params struct. + /// Used for serialization. + PreintegrationCombinedParams() + : PreintegrationParams(), + biasAccCovariance(I_3x3), + biasOmegaCovariance(I_3x3), + biasAccOmegaInt(I_6x6) {} + /// See two named constructors below for good values of n_gravity in body frame -PreintegrationCombinedParams(const Vector3& n_gravity) : - PreintegrationParams(n_gravity), biasAccCovariance(I_3x3), biasOmegaCovariance( - I_3x3), biasAccOmegaInt(I_6x6) { + PreintegrationCombinedParams(const Vector3& n_gravity) : + PreintegrationParams(n_gravity), biasAccCovariance(I_3x3), + biasOmegaCovariance(I_3x3), biasAccOmegaInt(I_6x6) { + } // Default Params for a Z-down navigation frame, such as NED: gravity points along positive Z-axis @@ -77,6 +88,9 @@ PreintegrationCombinedParams(const Vector3& n_gravity) : return boost::shared_ptr(new PreintegrationCombinedParams(Vector3(0, 0, -g))); } + void print(const std::string& s="") const; + bool equals(const PreintegrationParams& other, double tol) const; + void setBiasAccCovariance(const Matrix3& cov) { biasAccCovariance=cov; } void setBiasOmegaCovariance(const Matrix3& cov) { biasOmegaCovariance=cov; } void setBiasAccOmegaInt(const Matrix6& cov) { biasAccOmegaInt=cov; } @@ -86,24 +100,25 @@ PreintegrationCombinedParams(const Vector3& n_gravity) : const Matrix6& getBiasAccOmegaInt() const { return biasAccOmegaInt; } private: - /// Default constructor makes unitialized params struct - PreintegrationCombinedParams() {} /** Serialization function */ friend class boost::serialization::access; template - void serialize(ARCHIVE& ar, const unsigned int /*version*/) { - ar& BOOST_SERIALIZATION_BASE_OBJECT_NVP(PreintegratedRotation::Params); - ar& BOOST_SERIALIZATION_NVP(biasAccCovariance); - ar& BOOST_SERIALIZATION_NVP(biasOmegaCovariance); - ar& BOOST_SERIALIZATION_NVP(biasAccOmegaInt); + void serialize(ARCHIVE& ar, const unsigned int /*version*/) { + namespace bs = ::boost::serialization; + ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(PreintegrationParams); + ar & bs::make_nvp("biasAccCovariance", + bs::make_array(biasAccCovariance.data(), biasAccCovariance.size())); + ar & bs::make_nvp("biasOmegaCovariance", + bs::make_array(biasOmegaCovariance.data(), biasOmegaCovariance.size())); + ar & bs::make_nvp("biasAccOmegaInt", bs::make_array(biasAccOmegaInt.data(), + biasAccOmegaInt.size())); } public: GTSAM_MAKE_ALIGNED_OPERATOR_NEW }; - /** * PreintegratedCombinedMeasurements integrates the IMU measurements * (rotation rates and accelerations) and the corresponding covariance matrix. @@ -128,7 +143,6 @@ public: */ Eigen::Matrix preintMeasCov_; - friend class CombinedImuFactor; public: @@ -136,11 +150,14 @@ public: /// @{ /// Default constructor only for serialization and Cython wrapper - PreintegratedCombinedMeasurements() {} + PreintegratedCombinedMeasurements() { + preintMeasCov_.setZero(); + } /** * Default constructor, initializes the class with no measurements - * @param bias Current estimate of acceleration and rotation rate biases + * @param p Parameters, typically fixed in a single application + * @param biasHat Current estimate of acceleration and rotation rate biases */ PreintegratedCombinedMeasurements( const boost::shared_ptr& p, @@ -149,6 +166,19 @@ public: preintMeasCov_.setZero(); } + /** + * Construct preintegrated directly from members: base class and preintMeasCov + * @param base PreintegrationType instance + * @param preintMeasCov Covariance matrix used in noise model. + */ + PreintegratedCombinedMeasurements(const PreintegrationType& base, const Eigen::Matrix& preintMeasCov) + : PreintegrationType(base), + preintMeasCov_(preintMeasCov) { + } + + /// Virtual destructor + virtual ~PreintegratedCombinedMeasurements() {} + /// @} /// @name Basic utilities @@ -158,20 +188,25 @@ public: void resetIntegration() override; /// const reference to params, shadows definition in base class - Params& p() const { return *boost::static_pointer_cast(this->p_);} + Params& p() const { return *boost::static_pointer_cast(this->p_); } /// @} /// @name Access instance variables /// @{ + /// Return pre-integrated measurement covariance Matrix preintMeasCov() const { return preintMeasCov_; } /// @} /// @name Testable /// @{ + /// print void print(const std::string& s = "Preintegrated Measurements:") const override; - bool equals(const PreintegratedCombinedMeasurements& expected, double tol = 1e-9) const; + /// equals + bool equals(const PreintegratedCombinedMeasurements& expected, + double tol = 1e-9) const; /// @} + /// @name Main functionality /// @{ @@ -205,8 +240,10 @@ public: friend class boost::serialization::access; template void serialize(ARCHIVE& ar, const unsigned int /*version*/) { + namespace bs = ::boost::serialization; ar& BOOST_SERIALIZATION_BASE_OBJECT_NVP(PreintegrationType); - ar& BOOST_SERIALIZATION_NVP(preintMeasCov_); + ar& bs::make_nvp("preintMeasCov_", bs::make_array(preintMeasCov_.data(), + preintMeasCov_.size())); } public: @@ -244,9 +281,6 @@ private: PreintegratedCombinedMeasurements _PIM_; - /** Default constructor - only use for serialization */ - CombinedImuFactor() {} - public: /** Shorthand for a smart pointer to a factor */ @@ -256,6 +290,9 @@ public: typedef boost::shared_ptr shared_ptr; #endif + /** Default constructor - only use for serialization */ + CombinedImuFactor() {} + /** * Constructor * @param pose_i Previous pose key @@ -277,12 +314,17 @@ public: /** implement functions needed for Testable */ + /// @name Testable + /// @{ + GTSAM_EXPORT friend std::ostream& operator<<(std::ostream& os, + const CombinedImuFactor&); /// print virtual void print(const std::string& s, const KeyFormatter& keyFormatter = DefaultKeyFormatter) const; /// equals virtual bool equals(const NonlinearFactor& expected, double tol = 1e-9) const; + /// @} /** Access the preintegrated measurements. */ @@ -321,14 +363,12 @@ public: #endif private: - /** Serialization function */ friend class boost::serialization::access; - template - void serialize(ARCHIVE & ar, const unsigned int /*version*/) { - ar & boost::serialization::make_nvp("NoiseModelFactor6", - boost::serialization::base_object(*this)); - ar & BOOST_SERIALIZATION_NVP(_PIM_); + template + void serialize(ARCHIVE& ar, const unsigned int /*version*/) { + ar& BOOST_SERIALIZATION_BASE_OBJECT_NVP(NoiseModelFactor6); + ar& BOOST_SERIALIZATION_NVP(_PIM_); } public: @@ -336,4 +376,19 @@ public: }; // class CombinedImuFactor -} /// namespace gtsam +template <> +struct traits + : public Testable {}; + +template <> +struct traits + : public Testable {}; + +template <> +struct traits : public Testable {}; + +} // namespace gtsam + +/// Add Boost serialization export for derived class +BOOST_CLASS_EXPORT_GUID(gtsam::PreintegrationCombinedParams, "gtsam_PreintegrationCombinedParams"); +// BOOST_CLASS_EXPORT_GUID(gtsam::CombinedImuFactor, "gtsam_CombinedImuFactor"); From d519d24b67bed4495f23098ec458102fd2e575e7 Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Thu, 9 Jul 2020 00:22:13 -0400 Subject: [PATCH 160/869] Fix typo --- gtsam/navigation/ImuFactor.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/gtsam/navigation/ImuFactor.h b/gtsam/navigation/ImuFactor.h index b5cff8147..408cefdf0 100644 --- a/gtsam/navigation/ImuFactor.h +++ b/gtsam/navigation/ImuFactor.h @@ -59,7 +59,7 @@ typedef ManifoldPreintegration PreintegrationType; */ /** - * PreintegratedIMUMeasurements accumulates (integrates) the IMU measurements + * PreintegratedImuMeasurements accumulates (integrates) the IMU measurements * (rotation rates and accelerations) and the corresponding covariance matrix. * The measurements are then used to build the Preintegrated IMU factor. * Integration is done incrementally (ideally, one integrates the measurement From 23e2b29dbe428ccda610cff133142fbc04cd533f Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Thu, 9 Jul 2020 00:22:42 -0400 Subject: [PATCH 161/869] Added and updated serialization tests to include all IMU factors --- .../tests/testImuFactorSerialization.cpp | 60 +++++++++++++++---- 1 file changed, 49 insertions(+), 11 deletions(-) diff --git a/gtsam/navigation/tests/testImuFactorSerialization.cpp b/gtsam/navigation/tests/testImuFactorSerialization.cpp index 59d0ac199..ed72e18e9 100644 --- a/gtsam/navigation/tests/testImuFactorSerialization.cpp +++ b/gtsam/navigation/tests/testImuFactorSerialization.cpp @@ -16,15 +16,19 @@ * @author Frank Dellaert * @author Richard Roberts * @author Stephen Williams + * @author Varun Agrawal */ -#include -#include #include +#include +#include +#include + #include using namespace std; using namespace gtsam; +using namespace gtsam::serializationTestHelpers; BOOST_CLASS_EXPORT_GUID(gtsam::noiseModel::Constrained, "gtsam_noiseModel_Constrained"); @@ -38,23 +42,23 @@ BOOST_CLASS_EXPORT_GUID(gtsam::noiseModel::Isotropic, BOOST_CLASS_EXPORT_GUID(gtsam::SharedNoiseModel, "gtsam_SharedNoiseModel"); BOOST_CLASS_EXPORT_GUID(gtsam::SharedDiagonal, "gtsam_SharedDiagonal"); -TEST(ImuFactor, serialization) { - using namespace gtsam::serializationTestHelpers; - +template +P getPreintegratedMeasurements() { // Create default parameters with Z-down and above noise paramaters - auto p = PreintegrationParams::MakeSharedD(9.81); - p->body_P_sensor = Pose3(Rot3::Ypr(0, 0, M_PI), Point3(0,0,0)); + auto p = P::Params::MakeSharedD(9.81); + p->body_P_sensor = Pose3(Rot3::Ypr(0, 0, M_PI), Point3(0, 0, 0)); p->accelerometerCovariance = 1e-7 * I_3x3; p->gyroscopeCovariance = 1e-8 * I_3x3; p->integrationCovariance = 1e-9 * I_3x3; const double deltaT = 0.005; - const imuBias::ConstantBias priorBias( - Vector3(0, 0, 0), Vector3(0, 0.01, 0)); // Biases (acc, rot) - PreintegratedImuMeasurements pim(p, priorBias); + // Biases (acc, rot) + const imuBias::ConstantBias priorBias(Vector3(0, 0, 0), Vector3(0, 0.01, 0)); - // measurements are needed for non-inf noise model, otherwise will throw err + P pim(p, priorBias); + + // measurements are needed for non-inf noise model, otherwise will throw error // when deserialize const Vector3 measuredOmega(0, 0.01, 0); const Vector3 measuredAcc(0, 0, -9.81); @@ -62,6 +66,16 @@ TEST(ImuFactor, serialization) { for (int j = 0; j < 200; ++j) pim.integrateMeasurement(measuredAcc, measuredOmega, deltaT); + return pim; +} + +TEST(ImuFactor, serialization) { + auto pim = getPreintegratedMeasurements(); + + EXPECT(equalsObj(pim)); + EXPECT(equalsXML(pim)); + EXPECT(equalsBinary(pim)); + ImuFactor factor(1, 2, 3, 4, 5, pim); EXPECT(equalsObj(factor)); @@ -69,6 +83,30 @@ TEST(ImuFactor, serialization) { EXPECT(equalsBinary(factor)); } +TEST(ImuFactor2, serialization) { + auto pim = getPreintegratedMeasurements(); + + ImuFactor2 factor(1, 2, 3, pim); + + EXPECT(equalsObj(factor)); + EXPECT(equalsXML(factor)); + EXPECT(equalsBinary(factor)); +} + +TEST(CombinedImuFactor, Serialization) { + auto pim = getPreintegratedMeasurements(); + + EXPECT(equalsObj(pim)); + EXPECT(equalsXML(pim)); + EXPECT(equalsBinary(pim)); + + const CombinedImuFactor factor(1, 2, 3, 4, 5, 6, pim); + + EXPECT(equalsObj(factor)); + EXPECT(equalsXML(factor)); + EXPECT(equalsBinary(factor)); +} + /* ************************************************************************* */ int main() { TestResult tr; From 0c199dd406fde5b27123b762b073a1e8ac98f20a Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Thu, 9 Jul 2020 00:46:21 -0400 Subject: [PATCH 162/869] revert variable change --- gtsam/slam/SmartFactorBase.h | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/gtsam/slam/SmartFactorBase.h b/gtsam/slam/SmartFactorBase.h index 3bedf599f..c9b510605 100644 --- a/gtsam/slam/SmartFactorBase.h +++ b/gtsam/slam/SmartFactorBase.h @@ -206,12 +206,12 @@ protected: boost::optional E = boost::none) const { Vector ue = cameras.reprojectionError(point, measured_, Fs, E); if (body_P_sensor_ && Fs) { - const Pose3 sensor_T_body = body_P_sensor_->inverse(); + const Pose3 sensor_P_body = body_P_sensor_->inverse(); for (size_t i = 0; i < Fs->size(); i++) { - const Pose3 world_T_body = cameras[i].pose() * sensor_T_body; + const Pose3 world_P_body = cameras[i].pose() * sensor_P_body; Matrix J(6, 6); // Call compose to compute Jacobian - world_T_body.compose(*body_P_sensor_, J); + world_P_body.compose(*body_P_sensor_, J); Fs->at(i) = Fs->at(i) * J; } } From b4e58795b7b6d8b5dcbdda46c8308fad4bbbaea8 Mon Sep 17 00:00:00 2001 From: akrishnan86 Date: Wed, 8 Jul 2020 23:38:19 -0700 Subject: [PATCH 163/869] tests and documentation --- gtsam/sfm/{mfas.cc => mfas.cpp} | 43 +++++++--- gtsam/sfm/mfas.h | 25 +++--- gtsam/sfm/tests/testMFAS.cpp | 135 ++++++++++++++++++++------------ 3 files changed, 133 insertions(+), 70 deletions(-) rename gtsam/sfm/{mfas.cc => mfas.cpp} (59%) diff --git a/gtsam/sfm/mfas.cc b/gtsam/sfm/mfas.cpp similarity index 59% rename from gtsam/sfm/mfas.cc rename to gtsam/sfm/mfas.cpp index f2244bdfc..4ac1783e3 100644 --- a/gtsam/sfm/mfas.cc +++ b/gtsam/sfm/mfas.cpp @@ -1,5 +1,14 @@ +/* + This file defines functions used to solve a Minimum feedback arc set (MFAS) + problem. This code was forked and modified from Kyle Wilson's repository at + https://github.com/wilsonkl/SfM_Init. + Copyright (c) 2014, Kyle Wilson + All rights reserved. +*/ + #include "mfas.h" +#include #include #include #include @@ -14,7 +23,7 @@ namespace mfas { void flipNegEdges(vector &edges, vector &weights) { // now renumber the edges - for (int i = 0; i < edges.size(); ++i) { + for (unsigned int i = 0; i < edges.size(); ++i) { if (weights[i] < 0.0) { Key tmp = edges[i].second; edges[i].second = edges[i].first; @@ -34,7 +43,7 @@ void mfasRatio(const std::vector &edges, FastMap > > onbrs; // stuff data structures - for (int ii = 0; ii < edges.size(); ++ii) { + for (unsigned int ii = 0; ii < edges.size(); ++ii) { int i = edges[ii].first; int j = edges[ii].second; double w = weights[ii]; @@ -45,13 +54,23 @@ void mfasRatio(const std::vector &edges, onbrs[i].push_back(pair(j, w)); } - int ordered_count = 0; + for (auto &node : nodes) { + std::cout << node << " " << win_deg[node] << " " << wout_deg[node] + << std::endl; + for (auto it = inbrs[node].begin(); it != inbrs[node].end(); it++) + std::cout << it->first << "," << it->second << " "; + std::cout << std::endl; + for (auto it = onbrs[node].begin(); it != onbrs[node].end(); it++) + std::cout << it->first << "," << it->second << " "; + std::cout << std::endl; + } + unsigned int ordered_count = 0; while (ordered_count < nodes.size()) { // choose an unchosen node Key choice; double max_score = 0.0; for (auto node : nodes) { - if (ordered_positions.find(node) != ordered_positions.end()) { + if (ordered_positions.find(node) == ordered_positions.end()) { // is this a source if (win_deg[node] < 1e-8) { choice = node; @@ -65,7 +84,7 @@ void mfasRatio(const std::vector &edges, } } } - + std::cout << "choice is " << choice << std::endl; // find its inbrs, adjust their wout_deg for (auto it = inbrs[choice].begin(); it != inbrs[choice].end(); ++it) wout_deg[it->first] -= it->second; @@ -77,16 +96,16 @@ void mfasRatio(const std::vector &edges, } } -void brokenWeights(const std::vector &edges, - const std::vector &weight, - const FastMap &ordered_positions, - FastMap &broken) { - // find the broken edges - for (int i = 0; i < edges.size(); ++i) { +void outlierWeights(const std::vector &edges, + const std::vector &weight, + const FastMap &ordered_positions, + FastMap &outlier_weights) { + // find the outlier edges + for (unsigned int i = 0; i < edges.size(); ++i) { int x0 = ordered_positions.at(edges[i].first); int x1 = ordered_positions.at(edges[i].second); if ((x1 - x0) * weight[i] < 0) - broken[i] += weight[i] > 0 ? weight[i] : -weight[i]; + outlier_weights[edges[i]] += weight[i] > 0 ? weight[i] : -weight[i]; } } diff --git a/gtsam/sfm/mfas.h b/gtsam/sfm/mfas.h index 6aec492c4..c3d852b92 100644 --- a/gtsam/sfm/mfas.h +++ b/gtsam/sfm/mfas.h @@ -24,20 +24,24 @@ using KeyPair = std::pair; namespace mfas { /* - * Given a vector of KeyPairs that constitutes edges in a graph and the weights corresponding to these edges, this - * function changes all the weights to positive numbers by flipping the direction of the edges that have a - * negative weight. The changes are made in place. + * Given a vector of KeyPairs that constitutes edges in a graph and the weights + * corresponding to these edges, this function changes all the weights to + * positive numbers by flipping the direction of the edges that have a negative + * weight. The changes are made in place. * @param edges reference to vector of KeyPairs * @param weights weights corresponding to edges */ void flipNegEdges(std::vector &edges, std::vector &weights); /* - * Computes the MFAS ordering, ie an ordering of the nodes in the graph such that the source of any edge appears before its destination in the ordering. The weight of edges that are removed to obtain this ordering is minimized. + * Computes the MFAS ordering, ie an ordering of the nodes in the graph such + * that the source of any edge appears before its destination in the ordering. + * The weight of edges that are removed to obtain this ordering is minimized. * @param edges: edges in the graph * @param weights: weights corresponding to the edges (have to be positive) * @param nodes: nodes in the graph - * @param ordered_positions: map from node to position in the ordering (0 indexed) + * @param ordered_positions: map from node to position in the ordering (0 + * indexed) */ void mfasRatio(const std::vector &edges, const std::vector &weights, const KeyVector &nodes, @@ -48,12 +52,13 @@ void mfasRatio(const std::vector &edges, * @param edges in the graph * @param weights of the edges in the graph * @param ordered_positions: ordering (obtained from MFAS solution) - * @param broken: reference to a map from edges to their "broken weights" + * @param outlier_weights: reference to a map from edges to their "outlier + * weights" */ -void brokenWeights(const std::vector &edges, - const std::vector &weight, - const FastMap &ordered_positions, - FastMap &broken); +void outlierWeights(const std::vector &edges, + const std::vector &weight, + const FastMap &ordered_positions, + FastMap &outlier_weights); } // namespace mfas } // namespace gtsam diff --git a/gtsam/sfm/tests/testMFAS.cpp b/gtsam/sfm/tests/testMFAS.cpp index 0c52928c1..83c03925b 100644 --- a/gtsam/sfm/tests/testMFAS.cpp +++ b/gtsam/sfm/tests/testMFAS.cpp @@ -1,84 +1,123 @@ -#include "gtsam/sfm/mfas.h" #include +#include + +#include "gtsam/sfm/mfas.h" + using namespace std; using namespace gtsam; -// example from the paper -Key k0(0), k1(1), k2(2), k3(3), k4(4); -KeyPair e3_2(k3, k2), e0_1(k0, k1), e4_2(k4, k2), - e3_1(k3, k1), e4_0(k4, k0), e1_2(k1, k2), - e0_2(k0, k2), out_e3_0(k3, k0); +/* We (partially) use the example from the paper on 1dsfm + * (https://research.cs.cornell.edu/1dsfm/docs/1DSfM_ECCV14.pdf, Fig 1, Page 5) + * for the unit tests here. The only change is that we leave out node 4 and use + * only nodes 0-3. This not only makes the test easier to understand but also + * avoids an ambiguity in the ground truth ordering that arises due to + * insufficient edges in the geaph. */ -vector graph = {make_pair(3, 2), make_pair(0, 1), make_pair(4, 2), - make_pair(3, 1), make_pair(4, 0), +// edges in the graph - last edge from node 3 to 0 is an outlier +vector graph = {make_pair(3, 2), make_pair(0, 1), make_pair(3, 1), make_pair(1, 2), make_pair(0, 2), make_pair(3, 0)}; -KeyVector nodes = {0, 1, 2, 3, 4}; -vector weights1 = {2, 1.5, -2, -0.5, -0.5, 0.25, 1, 0.75}; - +// nodes in the graph +KeyVector nodes = {Key(0), Key(1), Key(2), Key(3)}; +// weights from projecting in direction-1 (bad direction, outlier accepted) +vector weights1 = {2, 1.5, 0.5, 0.25, 1, 0.75}; +// weights from projecting in direction-2 (good direction, outlier rejected) +vector weights2 = {0.5, 0.75, -0.25, 0.75, 1, 0.5}; +// Testing the flipNegEdges function for weights1 TEST(MFAS, FlipNegEdges) { vector graph_copy = graph; - vector weights1_copy = weights1; - mfas::flipNegEdges(graph_copy, weights1_copy); + vector weights1_positive = weights1; + mfas::flipNegEdges(graph_copy, weights1_positive); + // resulting graph and edges must be of same size EXPECT_LONGS_EQUAL(graph_copy.size(), graph.size()); - EXPECT_LONGS_EQUAL(weights1_copy.size(), weights1.size()); + EXPECT_LONGS_EQUAL(weights1_positive.size(), weights1.size()); - for (int i = 0; i < weights1.size(); i++) { + for (unsigned int i = 0; i < weights1.size(); i++) { if (weights1[i] < 0) { - EXPECT_DOUBLES_EQUAL(weights1_copy[i], -weights1[i], 1e-6); + // if original weight was negative, edges must be flipped and new weight + // must be positive + EXPECT_DOUBLES_EQUAL(weights1_positive[i], -weights1[i], 1e-6); EXPECT(graph_copy[i].first == graph[i].second && - graph_copy[i].second == graph[i].first); + graph_copy[i].second == graph[i].first); } else { - EXPECT_DOUBLES_EQUAL(weights1_copy[i], weights1[i], 1e-6); + // unchanged if original weight was positive + EXPECT_DOUBLES_EQUAL(weights1_positive[i], weights1[i], 1e-6); EXPECT(graph_copy[i].first == graph[i].first && - graph_copy[i].second == graph[i].second); + graph_copy[i].second == graph[i].second); } } } -// TEST(MFAS, Ordering) { - -// } - -TEST(MFAS, OrderingWithoutRemoval) { +// test the ordering and the outlierWeights function using weights2 - outlier +// edge is rejected when projected in a direction that gives weights2 +TEST(MFAS, OrderingWeights2) { vector graph_copy = graph; - vector weights1_copy = weights1; - mfas::flipNegEdges(graph_copy, weights1_copy); + vector weights2_positive = weights2; + mfas::flipNegEdges(graph_copy, weights2_positive); FastMap ordered_positions; - mfas::mfasRatio(graph_copy, weights1_copy, nodes, ordered_positions); + // compute ordering from positive edge weights + mfas::mfasRatio(graph_copy, weights2_positive, nodes, ordered_positions); + // expected ordering in this example FastMap gt_ordered_positions; - gt_ordered_positions[4] = 0; - gt_ordered_positions[3] = 1; - gt_ordered_positions[0] = 2; - gt_ordered_positions[1] = 3; - gt_ordered_positions[2] = 4; + gt_ordered_positions[0] = 0; + gt_ordered_positions[1] = 1; + gt_ordered_positions[3] = 2; + gt_ordered_positions[2] = 3; - for(auto it = ordered_positions.begin(); it != ordered_positions.end(); ++it) - { - EXPECT_LONGS_EQUAL(gt_ordered_positions[it->first], it->second); + // check if the expected ordering is obtained + for (auto node : nodes) { + EXPECT_LONGS_EQUAL(gt_ordered_positions[node], ordered_positions[node]); + } + + // testing the outlierWeights method + FastMap outlier_weights; + mfas::outlierWeights(graph_copy, weights2_positive, gt_ordered_positions, + outlier_weights); + // since edge between 3 and 0 is inconsistent with the ordering, it must have + // positive outlier weight, other outlier weights must be zero + for (auto &edge : graph_copy) { + if (edge == make_pair(Key(3), Key(0)) || + edge == make_pair(Key(0), Key(3))) { + EXPECT_DOUBLES_EQUAL(outlier_weights[edge], 0.5, 1e-6); + } else { + EXPECT_DOUBLES_EQUAL(outlier_weights[edge], 0, 1e-6); + } } } -TEST(MFAS, BrokenWeights) { +// test the ordering function and the outlierWeights method using +// weights2 (outlier edge is accepted when projected in a direction that +// produces weights2) +TEST(MFAS, OrderingWeights1) { vector graph_copy = graph; - vector weights1_copy = weights1; - mfas::flipNegEdges(graph_copy, weights1_copy); + vector weights1_positive = weights1; + mfas::flipNegEdges(graph_copy, weights1_positive); + FastMap ordered_positions; + // compute ordering from positive edge weights + mfas::mfasRatio(graph_copy, weights1_positive, nodes, ordered_positions); + // expected "ground truth" ordering in this example FastMap gt_ordered_positions; - gt_ordered_positions[4] = 0; - gt_ordered_positions[3] = 1; - gt_ordered_positions[0] = 2; - gt_ordered_positions[1] = 3; - gt_ordered_positions[2] = 4; + gt_ordered_positions[3] = 0; + gt_ordered_positions[0] = 1; + gt_ordered_positions[1] = 2; + gt_ordered_positions[2] = 3; - FastMap broken_weights; - mfas::brokenWeights(graph, weights1_copy, gt_ordered_positions, - broken_weights); - for (auto it = broken_weights.begin(); it != broken_weights.end(); it++) { - EXPECT_LONGS_EQUAL(it->second, 0); + // check if the expected ordering is obtained + for (auto node : nodes) { + EXPECT_LONGS_EQUAL(gt_ordered_positions[node], ordered_positions[node]); + } + + // since all edges (including the outlier) are consistent with this ordering, + // all outlier_weights must be zero + FastMap outlier_weights; + mfas::outlierWeights(graph, weights1_positive, gt_ordered_positions, + outlier_weights); + for (auto &edge : graph) { + EXPECT_DOUBLES_EQUAL(outlier_weights[edge], 0, 1e-6); } } From 90e7fb8229bd6693cac494627ced996b8462d1ec Mon Sep 17 00:00:00 2001 From: akrishnan86 Date: Wed, 8 Jul 2020 23:52:36 -0700 Subject: [PATCH 164/869] formatting headers and removing debugging code --- gtsam/sfm/mfas.cpp | 14 +------------- gtsam/sfm/tests/testMFAS.cpp | 6 ++---- 2 files changed, 3 insertions(+), 17 deletions(-) diff --git a/gtsam/sfm/mfas.cpp b/gtsam/sfm/mfas.cpp index 4ac1783e3..4764f2703 100644 --- a/gtsam/sfm/mfas.cpp +++ b/gtsam/sfm/mfas.cpp @@ -6,9 +6,8 @@ All rights reserved. */ -#include "mfas.h" +#include -#include #include #include #include @@ -54,16 +53,6 @@ void mfasRatio(const std::vector &edges, onbrs[i].push_back(pair(j, w)); } - for (auto &node : nodes) { - std::cout << node << " " << win_deg[node] << " " << wout_deg[node] - << std::endl; - for (auto it = inbrs[node].begin(); it != inbrs[node].end(); it++) - std::cout << it->first << "," << it->second << " "; - std::cout << std::endl; - for (auto it = onbrs[node].begin(); it != onbrs[node].end(); it++) - std::cout << it->first << "," << it->second << " "; - std::cout << std::endl; - } unsigned int ordered_count = 0; while (ordered_count < nodes.size()) { // choose an unchosen node @@ -84,7 +73,6 @@ void mfasRatio(const std::vector &edges, } } } - std::cout << "choice is " << choice << std::endl; // find its inbrs, adjust their wout_deg for (auto it = inbrs[choice].begin(); it != inbrs[choice].end(); ++it) wout_deg[it->first] -= it->second; diff --git a/gtsam/sfm/tests/testMFAS.cpp b/gtsam/sfm/tests/testMFAS.cpp index 83c03925b..d5daee1a6 100644 --- a/gtsam/sfm/tests/testMFAS.cpp +++ b/gtsam/sfm/tests/testMFAS.cpp @@ -1,9 +1,7 @@ +#include + #include -#include - -#include "gtsam/sfm/mfas.h" - using namespace std; using namespace gtsam; From 7dfc79971aa26a203aa9ef0bacb042a3955994b9 Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Thu, 9 Jul 2020 11:52:06 -0400 Subject: [PATCH 165/869] reduced tolerance for checking jacobian --- gtsam/slam/tests/testSmartFactorBase.cpp | 8 +++++--- 1 file changed, 5 insertions(+), 3 deletions(-) diff --git a/gtsam/slam/tests/testSmartFactorBase.cpp b/gtsam/slam/tests/testSmartFactorBase.cpp index bb04ad56d..fd771f102 100644 --- a/gtsam/slam/tests/testSmartFactorBase.cpp +++ b/gtsam/slam/tests/testSmartFactorBase.cpp @@ -67,9 +67,9 @@ TEST(SmartFactorBase, PinholeWithSensor) { PinholeFactor::Cameras cameras; // Assume body at origin. - Pose3 world_T_body = Pose3(); + Pose3 world_P_body = Pose3(); // Camera coordinates in world frame. - Pose3 wTc = world_T_body * body_P_sensor; + Pose3 wTc = world_P_body * body_P_sensor; cameras.push_back(PinholeCamera(wTc)); // Simple point to project slightly off image center @@ -88,7 +88,9 @@ TEST(SmartFactorBase, PinholeWithSensor) { expectedE << 0.1, 0, 0.01, 0, 0.1, 0; EXPECT(assert_equal(error, expectedError)); - EXPECT(assert_equal(expectedFs, Fs[0])); // We only have the jacobian for the 1 camera + // We only have the jacobian for the 1 camera + // Use of a lower tolerance value due to compiler precision mismatch. + EXPECT(assert_equal(expectedFs, Fs[0], 1e-3)); EXPECT(assert_equal(expectedE, E)); } From 4a0b031a2a07fa15dad643d091a6b3beb4f6bd2a Mon Sep 17 00:00:00 2001 From: Fan Jiang Date: Thu, 9 Jul 2020 14:26:18 -0400 Subject: [PATCH 166/869] add return value in gtsam_optimize --- cython/gtsam/utils/logging_optimizer.py | 1 + 1 file changed, 1 insertion(+) diff --git a/cython/gtsam/utils/logging_optimizer.py b/cython/gtsam/utils/logging_optimizer.py index 34f0fe5c9..3f0110945 100644 --- a/cython/gtsam/utils/logging_optimizer.py +++ b/cython/gtsam/utils/logging_optimizer.py @@ -52,3 +52,4 @@ def gtsam_optimize(optimizer: NonlinearOptimizer, gtsam.checkConvergence(params.getRelativeErrorTol(), params.getAbsoluteErrorTol(), params.getErrorTol(), current_error, new_error)) or (optimizer.lambda_() > params.getlambdaUpperBound()) optimize(optimizer, check_convergence, hook) + return optimizer.values() From 2c544018bf9f6dbd78e55ef441182f43067edafd Mon Sep 17 00:00:00 2001 From: Frank dellaert Date: Thu, 9 Jul 2020 16:27:21 -0400 Subject: [PATCH 167/869] Eliminated some copy/paste --- gtsam/slam/tests/testDataset.cpp | 150 ++++++++++++++----------------- 1 file changed, 67 insertions(+), 83 deletions(-) diff --git a/gtsam/slam/tests/testDataset.cpp b/gtsam/slam/tests/testDataset.cpp index 9a3c797b2..cd05b4f98 100644 --- a/gtsam/slam/tests/testDataset.cpp +++ b/gtsam/slam/tests/testDataset.cpp @@ -122,45 +122,6 @@ TEST( dataSet, Balbianello) EXPECT(assert_equal(expected,actual,1)); } -/* ************************************************************************* */ -TEST( dataSet, readG2o) -{ - const string g2oFile = findExampleDataFile("pose2example"); - NonlinearFactorGraph::shared_ptr actualGraph; - Values::shared_ptr actualValues; - boost::tie(actualGraph, actualValues) = readG2o(g2oFile); - - Values expectedValues; - expectedValues.insert(0, Pose2(0.000000, 0.000000, 0.000000)); - expectedValues.insert(1, Pose2(1.030390, 0.011350, -0.081596)); - expectedValues.insert(2, Pose2(2.036137, -0.129733, -0.301887)); - expectedValues.insert(3, Pose2(3.015097, -0.442395, -0.345514)); - expectedValues.insert(4, Pose2(3.343949, 0.506678, 1.214715)); - expectedValues.insert(5, Pose2(3.684491, 1.464049, 1.183785)); - expectedValues.insert(6, Pose2(4.064626, 2.414783, 1.176333)); - expectedValues.insert(7, Pose2(4.429778, 3.300180, 1.259169)); - expectedValues.insert(8, Pose2(4.128877, 2.321481, -1.825391)); - expectedValues.insert(9, Pose2(3.884653, 1.327509, -1.953016)); - expectedValues.insert(10, Pose2(3.531067, 0.388263, -2.148934)); - EXPECT(assert_equal(expectedValues,*actualValues,1e-5)); - - noiseModel::Diagonal::shared_ptr model = noiseModel::Diagonal::Precisions(Vector3(44.721360, 44.721360, 30.901699)); - NonlinearFactorGraph expectedGraph; - expectedGraph.emplace_shared >(0, 1, Pose2(1.030390, 0.011350, -0.081596), model); - expectedGraph.emplace_shared >(1, 2, Pose2(1.013900, -0.058639, -0.220291), model); - expectedGraph.emplace_shared >(2, 3, Pose2(1.027650, -0.007456, -0.043627), model); - expectedGraph.emplace_shared >(3, 4, Pose2(-0.012016, 1.004360, 1.560229), model); - expectedGraph.emplace_shared >(4, 5, Pose2(1.016030, 0.014565, -0.030930), model); - expectedGraph.emplace_shared >(5, 6, Pose2(1.023890, 0.006808, -0.007452), model); - expectedGraph.emplace_shared >(6, 7, Pose2(0.957734, 0.003159, 0.082836), model); - expectedGraph.emplace_shared >(7, 8, Pose2(-1.023820, -0.013668, -3.084560), model); - expectedGraph.emplace_shared >(8, 9, Pose2(1.023440, 0.013984, -0.127624), model); - expectedGraph.emplace_shared >(9,10, Pose2(1.003350, 0.022250, -0.195918), model); - expectedGraph.emplace_shared >(5, 9, Pose2(0.033943, 0.032439, 3.073637), model); - expectedGraph.emplace_shared >(3,10, Pose2(0.044020, 0.988477, -1.553511), model); - EXPECT(assert_equal(expectedGraph,*actualGraph,1e-5)); -} - /* ************************************************************************* */ TEST(dataSet, readG2o3D) { const string g2oFile = findExampleDataFile("pose3example"); @@ -273,59 +234,82 @@ TEST( dataSet, readG2o3DNonDiagonalNoise) } /* ************************************************************************* */ -TEST( dataSet, readG2oHuber) -{ - const string g2oFile = findExampleDataFile("pose2example"); - NonlinearFactorGraph::shared_ptr actualGraph; - Values::shared_ptr actualValues; - bool is3D = false; - boost::tie(actualGraph, actualValues) = readG2o(g2oFile, is3D, KernelFunctionTypeHUBER); - - noiseModel::Diagonal::shared_ptr baseModel = noiseModel::Diagonal::Precisions(Vector3(44.721360, 44.721360, 30.901699)); - SharedNoiseModel model = noiseModel::Robust::Create(noiseModel::mEstimator::Huber::Create(1.345), baseModel); - - NonlinearFactorGraph expectedGraph; - expectedGraph.emplace_shared >(0, 1, Pose2(1.030390, 0.011350, -0.081596), model); - expectedGraph.emplace_shared >(1, 2, Pose2(1.013900, -0.058639, -0.220291), model); - expectedGraph.emplace_shared >(2, 3, Pose2(1.027650, -0.007456, -0.043627), model); - expectedGraph.emplace_shared >(3, 4, Pose2(-0.012016, 1.004360, 1.560229), model); - expectedGraph.emplace_shared >(4, 5, Pose2(1.016030, 0.014565, -0.030930), model); - expectedGraph.emplace_shared >(5, 6, Pose2(1.023890, 0.006808, -0.007452), model); - expectedGraph.emplace_shared >(6, 7, Pose2(0.957734, 0.003159, 0.082836), model); - expectedGraph.emplace_shared >(7, 8, Pose2(-1.023820, -0.013668, -3.084560), model); - expectedGraph.emplace_shared >(8, 9, Pose2(1.023440, 0.013984, -0.127624), model); - expectedGraph.emplace_shared >(9,10, Pose2(1.003350, 0.022250, -0.195918), model); - expectedGraph.emplace_shared >(5, 9, Pose2(0.033943, 0.032439, 3.073637), model); - expectedGraph.emplace_shared >(3,10, Pose2(0.044020, 0.988477, -1.553511), model); - EXPECT(assert_equal(expectedGraph,*actualGraph,1e-5)); +static NonlinearFactorGraph expectedGraph(const SharedNoiseModel& model) { + NonlinearFactorGraph g; + using Factor = BetweenFactor; + g.emplace_shared(0, 1, Pose2(1.030390, 0.011350, -0.081596), model); + g.emplace_shared(1, 2, Pose2(1.013900, -0.058639, -0.220291), model); + g.emplace_shared(2, 3, Pose2(1.027650, -0.007456, -0.043627), model); + g.emplace_shared(3, 4, Pose2(-0.012016, 1.004360, 1.560229), model); + g.emplace_shared(4, 5, Pose2(1.016030, 0.014565, -0.030930), model); + g.emplace_shared(5, 6, Pose2(1.023890, 0.006808, -0.007452), model); + g.emplace_shared(6, 7, Pose2(0.957734, 0.003159, 0.082836), model); + g.emplace_shared(7, 8, Pose2(-1.023820, -0.013668, -3.084560), model); + g.emplace_shared(8, 9, Pose2(1.023440, 0.013984, -0.127624), model); + g.emplace_shared(9, 10, Pose2(1.003350, 0.022250, -0.195918), model); + g.emplace_shared(5, 9, Pose2(0.033943, 0.032439, 3.073637), model); + g.emplace_shared(3, 10, Pose2(0.044020, 0.988477, -1.553511), model); + return g; } /* ************************************************************************* */ -TEST( dataSet, readG2oTukey) -{ +TEST(dataSet, readG2o) { + const string g2oFile = findExampleDataFile("pose2example"); + NonlinearFactorGraph::shared_ptr actualGraph; + Values::shared_ptr actualValues; + boost::tie(actualGraph, actualValues) = readG2o(g2oFile); + + auto model = noiseModel::Diagonal::Precisions( + Vector3(44.721360, 44.721360, 30.901699)); + EXPECT(assert_equal(expectedGraph(model), *actualGraph, 1e-5)); + + Values expectedValues; + expectedValues.insert(0, Pose2(0.000000, 0.000000, 0.000000)); + expectedValues.insert(1, Pose2(1.030390, 0.011350, -0.081596)); + expectedValues.insert(2, Pose2(2.036137, -0.129733, -0.301887)); + expectedValues.insert(3, Pose2(3.015097, -0.442395, -0.345514)); + expectedValues.insert(4, Pose2(3.343949, 0.506678, 1.214715)); + expectedValues.insert(5, Pose2(3.684491, 1.464049, 1.183785)); + expectedValues.insert(6, Pose2(4.064626, 2.414783, 1.176333)); + expectedValues.insert(7, Pose2(4.429778, 3.300180, 1.259169)); + expectedValues.insert(8, Pose2(4.128877, 2.321481, -1.825391)); + expectedValues.insert(9, Pose2(3.884653, 1.327509, -1.953016)); + expectedValues.insert(10, Pose2(3.531067, 0.388263, -2.148934)); + EXPECT(assert_equal(expectedValues, *actualValues, 1e-5)); +} + +/* ************************************************************************* */ +TEST(dataSet, readG2oHuber) { const string g2oFile = findExampleDataFile("pose2example"); NonlinearFactorGraph::shared_ptr actualGraph; Values::shared_ptr actualValues; bool is3D = false; - boost::tie(actualGraph, actualValues) = readG2o(g2oFile, is3D, KernelFunctionTypeTUKEY); + boost::tie(actualGraph, actualValues) = + readG2o(g2oFile, is3D, KernelFunctionTypeHUBER); - noiseModel::Diagonal::shared_ptr baseModel = noiseModel::Diagonal::Precisions(Vector3(44.721360, 44.721360, 30.901699)); - SharedNoiseModel model = noiseModel::Robust::Create(noiseModel::mEstimator::Tukey::Create(4.6851), baseModel); + auto baseModel = noiseModel::Diagonal::Precisions( + Vector3(44.721360, 44.721360, 30.901699)); + auto model = noiseModel::Robust::Create( + noiseModel::mEstimator::Huber::Create(1.345), baseModel); - NonlinearFactorGraph expectedGraph; - expectedGraph.emplace_shared >(0, 1, Pose2(1.030390, 0.011350, -0.081596), model); - expectedGraph.emplace_shared >(1, 2, Pose2(1.013900, -0.058639, -0.220291), model); - expectedGraph.emplace_shared >(2, 3, Pose2(1.027650, -0.007456, -0.043627), model); - expectedGraph.emplace_shared >(3, 4, Pose2(-0.012016, 1.004360, 1.560229), model); - expectedGraph.emplace_shared >(4, 5, Pose2(1.016030, 0.014565, -0.030930), model); - expectedGraph.emplace_shared >(5, 6, Pose2(1.023890, 0.006808, -0.007452), model); - expectedGraph.emplace_shared >(6, 7, Pose2(0.957734, 0.003159, 0.082836), model); - expectedGraph.emplace_shared >(7, 8, Pose2(-1.023820, -0.013668, -3.084560), model); - expectedGraph.emplace_shared >(8, 9, Pose2(1.023440, 0.013984, -0.127624), model); - expectedGraph.emplace_shared >(9,10, Pose2(1.003350, 0.022250, -0.195918), model); - expectedGraph.emplace_shared >(5, 9, Pose2(0.033943, 0.032439, 3.073637), model); - expectedGraph.emplace_shared >(3,10, Pose2(0.044020, 0.988477, -1.553511), model); - EXPECT(assert_equal(expectedGraph,*actualGraph,1e-5)); + EXPECT(assert_equal(expectedGraph(model), *actualGraph, 1e-5)); +} + +/* ************************************************************************* */ +TEST(dataSet, readG2oTukey) { + const string g2oFile = findExampleDataFile("pose2example"); + NonlinearFactorGraph::shared_ptr actualGraph; + Values::shared_ptr actualValues; + bool is3D = false; + boost::tie(actualGraph, actualValues) = + readG2o(g2oFile, is3D, KernelFunctionTypeTUKEY); + + auto baseModel = noiseModel::Diagonal::Precisions( + Vector3(44.721360, 44.721360, 30.901699)); + auto model = noiseModel::Robust::Create( + noiseModel::mEstimator::Tukey::Create(4.6851), baseModel); + + EXPECT(assert_equal(expectedGraph(model), *actualGraph, 1e-5)); } /* ************************************************************************* */ From dc65a0a1d9e5bdff16c814bb22b2042c2456982a Mon Sep 17 00:00:00 2001 From: Frank dellaert Date: Thu, 9 Jul 2020 16:27:32 -0400 Subject: [PATCH 168/869] Added g2o test files --- examples/Data/Klaus3.g2o | 6 ++++++ examples/Data/toyExample.g2o | 11 +++++++++++ 2 files changed, 17 insertions(+) create mode 100644 examples/Data/Klaus3.g2o create mode 100755 examples/Data/toyExample.g2o diff --git a/examples/Data/Klaus3.g2o b/examples/Data/Klaus3.g2o new file mode 100644 index 000000000..4c7233fa7 --- /dev/null +++ b/examples/Data/Klaus3.g2o @@ -0,0 +1,6 @@ +VERTEX_SE3:QUAT 0 -3.865747774038187 0.06639337702667497 -0.16064874691945374 0.024595211709139555 0.49179523413089893 -0.06279232989379242 0.8680954132776109 +VERTEX_SE3:QUAT 1 -3.614793159814815 0.04774490041587656 -0.2837650367985949 0.00991721787943912 0.4854918961891193 -0.042343290945895576 0.8731588132957809 +VERTEX_SE3:QUAT 2 -3.255096913553434 0.013296754286114112 -0.5339792269680574 -0.027851108010665374 0.585478168397957 -0.05088341463532465 0.8086102325762403 +EDGE_SE3:QUAT 0 1 0.2509546142233723 -0.01864847661079841 -0.12311628987914114 -0.022048798853273946 -0.01796327847857683 0.010210006313668573 0.9995433591728293 100.0 0.0 0.0 0.0 0.0 0.0 100.0 0.0 0.0 0.0 0.0 100.0 0.0 0.0 0.0 25.0 0.0 0.0 25.0 0.0 25.0 +EDGE_SE3:QUAT 0 2 0.6106508604847534 -0.05309662274056086 -0.3733304800486037 -0.054972994022992064 0.10432547598981769 -0.02221474884651081 0.9927742290779572 100.0 0.0 0.0 0.0 0.0 0.0 100.0 0.0 0.0 0.0 0.0 100.0 0.0 0.0 0.0 25.0 0.0 0.0 25.0 0.0 25.0 +EDGE_SE3:QUAT 1 2 0.3596962462613811 -0.03444814612976245 -0.25021419016946256 -0.03174661848656213 0.11646825423134777 -0.02951742735854383 0.9922479626852876 100.0 0.0 0.0 0.0 0.0 0.0 100.0 0.0 0.0 0.0 0.0 100.0 0.0 0.0 0.0 25.0 0.0 0.0 25.0 0.0 25.0 diff --git a/examples/Data/toyExample.g2o b/examples/Data/toyExample.g2o new file mode 100755 index 000000000..5ff1ba74a --- /dev/null +++ b/examples/Data/toyExample.g2o @@ -0,0 +1,11 @@ +VERTEX_SE3:QUAT 0 0 0 0 0 0 0 1 +VERTEX_SE3:QUAT 1 0 0 0 0 0 0 1 +VERTEX_SE3:QUAT 2 0 0 0 0.00499994 0.00499994 0.00499994 0.999963 +VERTEX_SE3:QUAT 3 0 0 0 -0.00499994 -0.00499994 -0.00499994 0.999963 +VERTEX_SE3:QUAT 4 0 0 0 0.00499994 0.00499994 0.00499994 0.999963 +EDGE_SE3:QUAT 1 2 1 2 0 0 0 0.707107 0.707107 100 0 0 0 0 0 100 0 0 0 0 100 0 0 0 100 0 0 100 0 100 +EDGE_SE3:QUAT 2 3 -3.26795e-07 1 0 0 0 0.707107 0.707107 100 0 0 0 0 0 100 0 0 0 0 100 0 0 0 100 0 0 100 0 100 +EDGE_SE3:QUAT 3 4 1 1 0 0 0 0.707107 0.707107 100 0 0 0 0 0 100 0 0 0 0 100 0 0 0 100 0 0 100 0 100 +EDGE_SE3:QUAT 3 1 6.9282e-07 2 0 0 0 1 1.73205e-07 100 0 0 0 0 0 100 0 0 0 0 100 0 0 0 100 0 0 100 0 100 +EDGE_SE3:QUAT 1 4 -1 1 0 0 0 -0.707107 0.707107 100 0 0 0 0 0 100 0 0 0 0 100 0 0 0 100 0 0 100 0 100 +EDGE_SE3:QUAT 0 1 0 0 0 0 0 0 1 100 0 0 0 0 0 100 0 0 0 0 100 0 0 0 100 0 0 100 0 100 From 5ab16c8b5167c45ea1706371cd3e2eb37fc7161a Mon Sep 17 00:00:00 2001 From: Frank dellaert Date: Thu, 9 Jul 2020 17:15:28 -0400 Subject: [PATCH 169/869] Added tests on determinants of read rotations --- gtsam/slam/tests/testDataset.cpp | 23 ++++++++++++++++++++++- 1 file changed, 22 insertions(+), 1 deletion(-) diff --git a/gtsam/slam/tests/testDataset.cpp b/gtsam/slam/tests/testDataset.cpp index cd05b4f98..8088ab18a 100644 --- a/gtsam/slam/tests/testDataset.cpp +++ b/gtsam/slam/tests/testDataset.cpp @@ -233,6 +233,27 @@ TEST( dataSet, readG2o3DNonDiagonalNoise) EXPECT(assert_equal(expectedGraph,*actualGraph,1e-2)); } +/* ************************************************************************* */ +TEST(dataSet, readG2oCheckDeterminants) { + const string g2oFile = findExampleDataFile("toyExample.g2o"); + + // Check determinants in factors + auto factors = parse3DFactors(g2oFile); + EXPECT_LONGS_EQUAL(6, factors.size()); + for (const auto& factor : factors) { + const Rot3 R = factor->measured().rotation(); + EXPECT_DOUBLES_EQUAL(1.0, R.matrix().determinant(), 1e-9); + } + + // Check determinants in initial values + const map poses = parse3DPoses(g2oFile); + EXPECT_LONGS_EQUAL(5, poses.size()); + for (const auto& key_value : poses) { + const Rot3 R = key_value.second.rotation(); + EXPECT_DOUBLES_EQUAL(1.0, R.matrix().determinant(), 1e-9); + } +} + /* ************************************************************************* */ static NonlinearFactorGraph expectedGraph(const SharedNoiseModel& model) { NonlinearFactorGraph g; @@ -479,7 +500,7 @@ TEST( dataSet, writeBALfromValues_Dubrovnik){ SfmData readData; readBAL(filenameToRead, readData); - Pose3 poseChange = Pose3(Rot3::Ypr(-M_PI/10, 0., -M_PI/10), gtsam::Point3(0.3,0.1,0.3)); + Pose3 poseChange = Pose3(Rot3::Ypr(-M_PI/10, 0., -M_PI/10), Point3(0.3,0.1,0.3)); Values value; for(size_t i=0; i < readData.number_cameras(); i++){ // for each camera From 4960f755950de0137c5b13aec53c510e8d7f89ed Mon Sep 17 00:00:00 2001 From: Frank dellaert Date: Thu, 9 Jul 2020 17:16:11 -0400 Subject: [PATCH 170/869] Normalized quaternions before converting to Rot3 to account for limited precision in text files. --- gtsam/slam/dataset.cpp | 12 +++++++++--- 1 file changed, 9 insertions(+), 3 deletions(-) diff --git a/gtsam/slam/dataset.cpp b/gtsam/slam/dataset.cpp index 66e8fc4c0..1bb03dfe4 100644 --- a/gtsam/slam/dataset.cpp +++ b/gtsam/slam/dataset.cpp @@ -511,6 +511,11 @@ void writeG2o(const NonlinearFactorGraph& graph, const Values& estimate, stream.close(); } +/* ************************************************************************* */ +static Rot3 NormalizedRot3(double w, double x, double y, double z) { + const double norm = sqrt(w * w + x * x + y * y + z * z), f = 1.0 / norm; + return Rot3::Quaternion(f * w, f * x, f * y, f * z); +} /* ************************************************************************* */ std::map parse3DPoses(const string& filename) { ifstream is(filename.c_str()); @@ -535,14 +540,15 @@ std::map parse3DPoses(const string& filename) { Key id; double x, y, z, qx, qy, qz, qw; ls >> id >> x >> y >> z >> qx >> qy >> qz >> qw; - poses.emplace(id, Pose3(Rot3::Quaternion(qw, qx, qy, qz), {x, y, z})); + poses.emplace(id, Pose3(NormalizedRot3(qw, qx, qy, qz), {x, y, z})); } } return poses; } /* ************************************************************************* */ -BetweenFactorPose3s parse3DFactors(const string& filename, +BetweenFactorPose3s parse3DFactors( + const string& filename, const noiseModel::Diagonal::shared_ptr& corruptingNoise) { ifstream is(filename.c_str()); if (!is) throw invalid_argument("parse3DFactors: can not find file " + filename); @@ -592,7 +598,7 @@ BetweenFactorPose3s parse3DFactors(const string& filename, mgtsam.block<3, 3>(3, 0) = m.block<3, 3>(3, 0); // off diagonal SharedNoiseModel model = noiseModel::Gaussian::Information(mgtsam); - auto R12 = Rot3::Quaternion(qw, qx, qy, qz); + auto R12 = NormalizedRot3(qw, qx, qy, qz); if (sampler) { R12 = R12.retract(sampler->sample()); } From a484c910ab11ac5153dfa605baf781393ebd15ef Mon Sep 17 00:00:00 2001 From: Frank dellaert Date: Thu, 9 Jul 2020 17:27:06 -0400 Subject: [PATCH 171/869] Avoided extra conversions to quaternions --- gtsam/slam/dataset.cpp | 23 +++++++++++------------ 1 file changed, 11 insertions(+), 12 deletions(-) diff --git a/gtsam/slam/dataset.cpp b/gtsam/slam/dataset.cpp index 1bb03dfe4..669935994 100644 --- a/gtsam/slam/dataset.cpp +++ b/gtsam/slam/dataset.cpp @@ -442,11 +442,11 @@ void writeG2o(const NonlinearFactorGraph& graph, const Values& estimate, auto p = dynamic_cast*>(&key_value.value); if (!p) continue; const Pose3& pose = p->value(); - Point3 t = pose.translation(); - Rot3 R = pose.rotation(); - stream << "VERTEX_SE3:QUAT " << key_value.key << " " << t.x() << " " << t.y() << " " << t.z() - << " " << R.toQuaternion().x() << " " << R.toQuaternion().y() << " " << R.toQuaternion().z() - << " " << R.toQuaternion().w() << endl; + const Point3 t = pose.translation(); + const auto q = pose.rotation().toQuaternion(); + stream << "VERTEX_SE3:QUAT " << key_value.key << " " << t.x() << " " + << t.y() << " " << t.z() << " " << q.x() << " " << q.y() << " " + << q.z() << " " << q.w() << endl; } // save edges (2D or 3D) @@ -486,13 +486,12 @@ void writeG2o(const NonlinearFactorGraph& graph, const Values& estimate, throw invalid_argument("writeG2o: invalid noise model!"); } Matrix Info = gaussianModel->R().transpose() * gaussianModel->R(); - Pose3 pose3D = factor3D->measured(); - Point3 p = pose3D.translation(); - Rot3 R = pose3D.rotation(); - - stream << "EDGE_SE3:QUAT " << factor3D->key1() << " " << factor3D->key2() << " " - << p.x() << " " << p.y() << " " << p.z() << " " << R.toQuaternion().x() - << " " << R.toQuaternion().y() << " " << R.toQuaternion().z() << " " << R.toQuaternion().w(); + const Pose3 pose3D = factor3D->measured(); + const Point3 p = pose3D.translation(); + const auto q = pose3D.rotation().toQuaternion(); + stream << "EDGE_SE3:QUAT " << factor3D->key1() << " " << factor3D->key2() + << " " << p.x() << " " << p.y() << " " << p.z() << " " << q.x() + << " " << q.y() << " " << q.z() << " " << q.w(); Matrix InfoG2o = I_6x6; InfoG2o.block(0,0,3,3) = Info.block(3,3,3,3); // cov translation From f23587fafd9ceb388eeef6e4cec0c685dcf4be2d Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Thu, 9 Jul 2020 20:02:09 -0400 Subject: [PATCH 172/869] Add indentation --- gtsam/geometry/PinholePose.h | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/gtsam/geometry/PinholePose.h b/gtsam/geometry/PinholePose.h index 60088577c..79dbb9ce9 100644 --- a/gtsam/geometry/PinholePose.h +++ b/gtsam/geometry/PinholePose.h @@ -107,9 +107,9 @@ public: // If needed, apply chain rule if (Dpose) - *Dpose = Dpi_pn * *Dpose; + *Dpose = Dpi_pn * *Dpose; if (Dpoint) - *Dpoint = Dpi_pn * *Dpoint; + *Dpoint = Dpi_pn * *Dpoint; return pi; } From 60c88f67e9b5271d867efd16322080e6e02236ec Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Thu, 9 Jul 2020 20:02:30 -0400 Subject: [PATCH 173/869] Handle extrinsics and intrinsics for jacobian --- gtsam/slam/SmartFactorBase.h | 12 +++++++++--- 1 file changed, 9 insertions(+), 3 deletions(-) diff --git a/gtsam/slam/SmartFactorBase.h b/gtsam/slam/SmartFactorBase.h index c9b510605..912de0bc1 100644 --- a/gtsam/slam/SmartFactorBase.h +++ b/gtsam/slam/SmartFactorBase.h @@ -207,11 +207,17 @@ protected: Vector ue = cameras.reprojectionError(point, measured_, Fs, E); if (body_P_sensor_ && Fs) { const Pose3 sensor_P_body = body_P_sensor_->inverse(); + size_t camera_dim = size_t(traits::dimension); + size_t pose_dim = size_t(traits::dimension); + for (size_t i = 0; i < Fs->size(); i++) { const Pose3 world_P_body = cameras[i].pose() * sensor_P_body; - Matrix J(6, 6); - // Call compose to compute Jacobian - world_P_body.compose(*body_P_sensor_, J); + Matrix J = Matrix::Zero(camera_dim, camera_dim); + // Call compose to compute Jacobian for camera extrinsics + Matrix H(pose_dim, pose_dim); + world_P_body.compose(*body_P_sensor_, H); + // Assign extrinsics + J.block(0, 0, pose_dim, pose_dim) = H; Fs->at(i) = Fs->at(i) * J; } } From 3dcff34b468988b97d47aefe3a0c0b26d78d82f3 Mon Sep 17 00:00:00 2001 From: Frank dellaert Date: Thu, 9 Jul 2020 20:46:12 -0400 Subject: [PATCH 174/869] Formatted and fixed discrete examples --- examples/CMakeLists.txt | 3 - examples/DiscreteBayesNet_FG.cpp | 119 ++++++++++++++++--------------- examples/UGM_chain.cpp | 74 ++++++++----------- examples/UGM_small.cpp | 19 ++--- 4 files changed, 98 insertions(+), 117 deletions(-) diff --git a/examples/CMakeLists.txt b/examples/CMakeLists.txt index 7251c2b6f..476f4ae21 100644 --- a/examples/CMakeLists.txt +++ b/examples/CMakeLists.txt @@ -1,7 +1,4 @@ set (excluded_examples - DiscreteBayesNet_FG.cpp - UGM_chain.cpp - UGM_small.cpp elaboratePoint2KalmanFilter.cpp ) diff --git a/examples/DiscreteBayesNet_FG.cpp b/examples/DiscreteBayesNet_FG.cpp index 6eb08c12e..9802b5984 100644 --- a/examples/DiscreteBayesNet_FG.cpp +++ b/examples/DiscreteBayesNet_FG.cpp @@ -10,110 +10,111 @@ * -------------------------------------------------------------------------- */ /** - * @file DiscreteBayesNet_FG.cpp + * @file DiscreteBayesNet_graph.cpp * @brief Discrete Bayes Net example using Factor Graphs * @author Abhijit * @date Jun 4, 2012 * - * We use the famous Rain/Cloudy/Sprinkler Example of [Russell & Norvig, 2009, p529] - * You may be familiar with other graphical model packages like BNT (available - * at http://bnt.googlecode.com/svn/trunk/docs/usage.html) where this is used as an - * example. The following demo is same as that in the above link, except that - * everything is using GTSAM. + * We use the famous Rain/Cloudy/Sprinkler Example of [Russell & Norvig, 2009, + * p529] You may be familiar with other graphical model packages like BNT + * (available at http://bnt.googlecode.com/svn/trunk/docs/usage.html) where this + * is used as an example. The following demo is same as that in the above link, + * except that everything is using GTSAM. */ #include -#include +#include + #include using namespace std; using namespace gtsam; int main(int argc, char **argv) { + // Define keys and a print function + Key C(1), S(2), R(3), W(4); + auto print = [=](DiscreteFactor::sharedValues values) { + cout << boolalpha << "Cloudy = " << static_cast((*values)[C]) + << " Sprinkler = " << static_cast((*values)[S]) + << " Rain = " << boolalpha << static_cast((*values)[R]) + << " WetGrass = " << static_cast((*values)[W]) << endl; + }; // We assume binary state variables // we have 0 == "False" and 1 == "True" const size_t nrStates = 2; // define variables - DiscreteKey Cloudy(1, nrStates), Sprinkler(2, nrStates), Rain(3, nrStates), - WetGrass(4, nrStates); + DiscreteKey Cloudy(C, nrStates), Sprinkler(S, nrStates), Rain(R, nrStates), + WetGrass(W, nrStates); // create Factor Graph of the bayes net DiscreteFactorGraph graph; // add factors - graph.add(Cloudy, "0.5 0.5"); //P(Cloudy) - graph.add(Cloudy & Sprinkler, "0.5 0.5 0.9 0.1"); //P(Sprinkler | Cloudy) - graph.add(Cloudy & Rain, "0.8 0.2 0.2 0.8"); //P(Rain | Cloudy) + graph.add(Cloudy, "0.5 0.5"); // P(Cloudy) + graph.add(Cloudy & Sprinkler, "0.5 0.5 0.9 0.1"); // P(Sprinkler | Cloudy) + graph.add(Cloudy & Rain, "0.8 0.2 0.2 0.8"); // P(Rain | Cloudy) graph.add(Sprinkler & Rain & WetGrass, - "1 0 0.1 0.9 0.1 0.9 0.001 0.99"); //P(WetGrass | Sprinkler, Rain) + "1 0 0.1 0.9 0.1 0.9 0.001 0.99"); // P(WetGrass | Sprinkler, Rain) - // Alternatively we can also create a DiscreteBayesNet, add DiscreteConditional - // factors and create a FactorGraph from it. (See testDiscreteBayesNet.cpp) + // Alternatively we can also create a DiscreteBayesNet, add + // DiscreteConditional factors and create a FactorGraph from it. (See + // testDiscreteBayesNet.cpp) // Since this is a relatively small distribution, we can as well print // the whole distribution.. cout << "Distribution of Example: " << endl; cout << setw(11) << "Cloudy(C)" << setw(14) << "Sprinkler(S)" << setw(10) - << "Rain(R)" << setw(14) << "WetGrass(W)" << setw(15) << "P(C,S,R,W)" - << endl; + << "Rain(R)" << setw(14) << "WetGrass(W)" << setw(15) << "P(C,S,R,W)" + << endl; for (size_t a = 0; a < nrStates; a++) for (size_t m = 0; m < nrStates; m++) for (size_t h = 0; h < nrStates; h++) for (size_t c = 0; c < nrStates; c++) { DiscreteFactor::Values values; - values[Cloudy.first] = c; - values[Sprinkler.first] = h; - values[Rain.first] = m; - values[WetGrass.first] = a; + values[C] = c; + values[S] = h; + values[R] = m; + values[W] = a; double prodPot = graph(values); - cout << boolalpha << setw(8) << (bool) c << setw(14) - << (bool) h << setw(12) << (bool) m << setw(13) - << (bool) a << setw(16) << prodPot << endl; + cout << setw(8) << static_cast(c) << setw(14) + << static_cast(h) << setw(12) << static_cast(m) + << setw(13) << static_cast(a) << setw(16) << prodPot + << endl; } - // "Most Probable Explanation", i.e., configuration with largest value - DiscreteSequentialSolver solver(graph); - DiscreteFactor::sharedValues optimalDecoding = solver.optimize(); - cout <<"\nMost Probable Explanation (MPE):" << endl; - cout << boolalpha << "Cloudy = " << (bool)(*optimalDecoding)[Cloudy.first] - << " Sprinkler = " << (bool)(*optimalDecoding)[Sprinkler.first] - << " Rain = " << boolalpha << (bool)(*optimalDecoding)[Rain.first] - << " WetGrass = " << (bool)(*optimalDecoding)[WetGrass.first]<< endl; + DiscreteFactor::sharedValues mpe = graph.eliminateSequential()->optimize(); + cout << "\nMost Probable Explanation (MPE):" << endl; + print(mpe); + // "Inference" We show an inference query like: probability that the Sprinkler + // was on; given that the grass is wet i.e. P( S | C=0) = ? - // "Inference" We show an inference query like: probability that the Sprinkler was on; - // given that the grass is wet i.e. P( S | W=1) =? - cout << "\nInference Query: Probability of Sprinkler being on given Grass is Wet" << endl; + // add evidence that it is not Cloudy + graph.add(Cloudy, "1 0"); - // Method 1: we can compute the joint marginal P(S,W) and from that we can compute - // P(S | W=1) = P(S,W=1)/P(W=1) We do this in following three steps.. + // solve again, now with evidence + DiscreteBayesNet::shared_ptr chordal = graph.eliminateSequential(); + DiscreteFactor::sharedValues mpe_with_evidence = chordal->optimize(); - //Step1: Compute P(S,W) - DiscreteFactorGraph jointFG; - jointFG = *solver.jointFactorGraph(DiscreteKeys(Sprinkler & WetGrass).indices()); - DecisionTreeFactor probSW = jointFG.product(); + cout << "\nMPE given C=0:" << endl; + print(mpe_with_evidence); - //Step2: Compute P(W) - DiscreteFactor::shared_ptr probW = solver.marginalFactor(WetGrass.first); - - //Step3: Computer P(S | W=1) = P(S,W=1)/P(W=1) - DiscreteFactor::Values values; - values[WetGrass.first] = 1; - - //print P(S=0|W=1) - values[Sprinkler.first] = 0; - cout << "P(S=0|W=1) = " << probSW(values)/(*probW)(values) << endl; - - //print P(S=1|W=1) - values[Sprinkler.first] = 1; - cout << "P(S=1|W=1) = " << probSW(values)/(*probW)(values) << endl; - - // TODO: Method 2 : One way is to modify the factor graph to - // incorporate the evidence node and compute the marginal - // TODO: graph.addEvidence(Cloudy,0); + // we can also calculate arbitrary marginals: + DiscreteMarginals marginals(graph); + cout << "\nP(S=1|C=0):" << marginals.marginalProbabilities(Sprinkler)[1] + << endl; + cout << "\nP(R=0|C=0):" << marginals.marginalProbabilities(Rain)[0] << endl; + cout << "\nP(W=1|C=0):" << marginals.marginalProbabilities(WetGrass)[1] + << endl; + // We can also sample from it + cout << "\n10 samples:" << endl; + for (size_t i = 0; i < 10; i++) { + DiscreteFactor::sharedValues sample = chordal->sample(); + print(sample); + } return 0; } diff --git a/examples/UGM_chain.cpp b/examples/UGM_chain.cpp index 4ce4e7af4..3a885a844 100644 --- a/examples/UGM_chain.cpp +++ b/examples/UGM_chain.cpp @@ -10,7 +10,7 @@ * -------------------------------------------------------------------------- */ /** - * @file small.cpp + * @file UGM_chain.cpp * @brief UGM (undirected graphical model) examples: chain * @author Frank Dellaert * @author Abhijit Kundu @@ -19,10 +19,9 @@ * for more explanation. This code demos the same example using GTSAM. */ -#include -#include -#include #include +#include +#include #include @@ -30,9 +29,8 @@ using namespace std; using namespace gtsam; int main(int argc, char** argv) { - - // Set Number of Nodes in the Graph - const int nrNodes = 60; + // Set Number of Nodes in the Graph + const int nrNodes = 60; // Each node takes 1 of 7 possible states denoted by 0-6 in following order: // ["VideoGames" "Industry" "GradSchool" "VideoGames(with PhD)" @@ -40,70 +38,55 @@ int main(int argc, char** argv) { const size_t nrStates = 7; // define variables - vector nodes; - for (int i = 0; i < nrNodes; i++){ - DiscreteKey dk(i, nrStates); - nodes.push_back(dk); - } + vector nodes; + for (int i = 0; i < nrNodes; i++) { + DiscreteKey dk(i, nrStates); + nodes.push_back(dk); + } // create graph DiscreteFactorGraph graph; // add node potentials graph.add(nodes[0], ".3 .6 .1 0 0 0 0"); - for (int i = 1; i < nrNodes; i++) - graph.add(nodes[i], "1 1 1 1 1 1 1"); + for (int i = 1; i < nrNodes; i++) graph.add(nodes[i], "1 1 1 1 1 1 1"); - const std::string edgePotential = ".08 .9 .01 0 0 0 .01 " - ".03 .95 .01 0 0 0 .01 " - ".06 .06 .75 .05 .05 .02 .01 " - "0 0 0 .3 .6 .09 .01 " - "0 0 0 .02 .95 .02 .01 " - "0 0 0 .01 .01 .97 .01 " - "0 0 0 0 0 0 1"; + const std::string edgePotential = + ".08 .9 .01 0 0 0 .01 " + ".03 .95 .01 0 0 0 .01 " + ".06 .06 .75 .05 .05 .02 .01 " + "0 0 0 .3 .6 .09 .01 " + "0 0 0 .02 .95 .02 .01 " + "0 0 0 .01 .01 .97 .01 " + "0 0 0 0 0 0 1"; // add edge potentials for (int i = 0; i < nrNodes - 1; i++) graph.add(nodes[i] & nodes[i + 1], edgePotential); cout << "Created Factor Graph with " << nrNodes << " variable nodes and " - << graph.size() << " factors (Unary+Edge)."; + << graph.size() << " factors (Unary+Edge)."; // "Decoding", i.e., configuration with largest value // We use sequential variable elimination - DiscreteSequentialSolver solver(graph); - DiscreteFactor::sharedValues optimalDecoding = solver.optimize(); + DiscreteBayesNet::shared_ptr chordal = graph.eliminateSequential(); + DiscreteFactor::sharedValues optimalDecoding = chordal->optimize(); optimalDecoding->print("\nMost Probable Explanation (optimalDecoding)\n"); // "Inference" Computing marginals for each node - - - cout << "\nComputing Node Marginals ..(Sequential Elimination)" << endl; - gttic_(Sequential); - for (vector::iterator itr = nodes.begin(); itr != nodes.end(); - ++itr) { - //Compute the marginal - Vector margProbs = solver.marginalProbabilities(*itr); - - //Print the marginals - cout << "Node#" << setw(4) << itr->first << " : "; - print(margProbs); - } - gttoc_(Sequential); - // Here we'll make use of DiscreteMarginals class, which makes use of // bayes-tree based shortcut evaluation of marginals DiscreteMarginals marginals(graph); cout << "\nComputing Node Marginals ..(BayesTree based)" << endl; gttic_(Multifrontal); - for (vector::iterator itr = nodes.begin(); itr != nodes.end(); - ++itr) { - //Compute the marginal - Vector margProbs = marginals.marginalProbabilities(*itr); + for (vector::iterator it = nodes.begin(); it != nodes.end(); + ++it) { + // Compute the marginal + Vector margProbs = marginals.marginalProbabilities(*it); - //Print the marginals - cout << "Node#" << setw(4) << itr->first << " : "; + // Print the marginals + cout << "Node#" << setw(4) << it->first << " : "; print(margProbs); } gttoc_(Multifrontal); @@ -111,4 +94,3 @@ int main(int argc, char** argv) { tictoc_print_(); return 0; } - diff --git a/examples/UGM_small.cpp b/examples/UGM_small.cpp index f5338bc67..27a6205a3 100644 --- a/examples/UGM_small.cpp +++ b/examples/UGM_small.cpp @@ -10,15 +10,16 @@ * -------------------------------------------------------------------------- */ /** - * @file small.cpp + * @file UGM_small.cpp * @brief UGM (undirected graphical model) examples: small * @author Frank Dellaert * * See http://www.di.ens.fr/~mschmidt/Software/UGM/small.html */ +#include #include -#include +#include using namespace std; using namespace gtsam; @@ -61,24 +62,24 @@ int main(int argc, char** argv) { // "Decoding", i.e., configuration with largest value (MPE) // We use sequential variable elimination - DiscreteSequentialSolver solver(graph); - DiscreteFactor::sharedValues optimalDecoding = solver.optimize(); + DiscreteBayesNet::shared_ptr chordal = graph.eliminateSequential(); + DiscreteFactor::sharedValues optimalDecoding = chordal->optimize(); optimalDecoding->print("\noptimalDecoding"); // "Inference" Computing marginals cout << "\nComputing Node Marginals .." << endl; - Vector margProbs; + DiscreteMarginals marginals(graph); - margProbs = solver.marginalProbabilities(Cathy); + Vector margProbs = marginals.marginalProbabilities(Cathy); print(margProbs, "Cathy's Node Marginal:"); - margProbs = solver.marginalProbabilities(Heather); + margProbs = marginals.marginalProbabilities(Heather); print(margProbs, "Heather's Node Marginal"); - margProbs = solver.marginalProbabilities(Mark); + margProbs = marginals.marginalProbabilities(Mark); print(margProbs, "Mark's Node Marginal"); - margProbs = solver.marginalProbabilities(Allison); + margProbs = marginals.marginalProbabilities(Allison); print(margProbs, "Allison's Node Marginal"); return 0; From 904ecf4f1f341db840f1edfed0e9e42fedef25d2 Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Thu, 9 Jul 2020 23:11:20 -0400 Subject: [PATCH 175/869] Use built in Matrix serialization --- gtsam/navigation/CombinedImuFactor.h | 18 ++++++------------ gtsam/navigation/ImuFactor.h | 2 +- gtsam/navigation/ManifoldPreintegration.h | 10 +++++----- gtsam/navigation/PreintegratedRotation.h | 2 +- gtsam/navigation/PreintegrationParams.h | 4 ++-- gtsam/navigation/TangentPreintegration.h | 6 +++--- 6 files changed, 18 insertions(+), 24 deletions(-) diff --git a/gtsam/navigation/CombinedImuFactor.h b/gtsam/navigation/CombinedImuFactor.h index 7a3a801f1..f47ce8846 100644 --- a/gtsam/navigation/CombinedImuFactor.h +++ b/gtsam/navigation/CombinedImuFactor.h @@ -63,11 +63,10 @@ struct GTSAM_EXPORT PreintegrationCombinedParams : PreintegrationParams { Matrix3 biasOmegaCovariance; ///< continuous-time "Covariance" describing gyroscope bias random walk Matrix6 biasAccOmegaInt; ///< covariance of bias used for pre-integration - /// Default constructor makes unitialized params struct. + /// Default constructor makes uninitialized params struct. /// Used for serialization. PreintegrationCombinedParams() - : PreintegrationParams(), - biasAccCovariance(I_3x3), + : biasAccCovariance(I_3x3), biasOmegaCovariance(I_3x3), biasAccOmegaInt(I_6x6) {} @@ -107,12 +106,9 @@ private: void serialize(ARCHIVE& ar, const unsigned int /*version*/) { namespace bs = ::boost::serialization; ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(PreintegrationParams); - ar & bs::make_nvp("biasAccCovariance", - bs::make_array(biasAccCovariance.data(), biasAccCovariance.size())); - ar & bs::make_nvp("biasOmegaCovariance", - bs::make_array(biasOmegaCovariance.data(), biasOmegaCovariance.size())); - ar & bs::make_nvp("biasAccOmegaInt", bs::make_array(biasAccOmegaInt.data(), - biasAccOmegaInt.size())); + ar & BOOST_SERIALIZATION_NVP(biasAccCovariance); + ar & BOOST_SERIALIZATION_NVP(biasOmegaCovariance); + ar & BOOST_SERIALIZATION_NVP(biasAccOmegaInt); } public: @@ -242,8 +238,7 @@ public: void serialize(ARCHIVE& ar, const unsigned int /*version*/) { namespace bs = ::boost::serialization; ar& BOOST_SERIALIZATION_BASE_OBJECT_NVP(PreintegrationType); - ar& bs::make_nvp("preintMeasCov_", bs::make_array(preintMeasCov_.data(), - preintMeasCov_.size())); + ar& BOOST_SERIALIZATION_NVP(preintMeasCov_); } public: @@ -391,4 +386,3 @@ struct traits : public Testable {}; /// Add Boost serialization export for derived class BOOST_CLASS_EXPORT_GUID(gtsam::PreintegrationCombinedParams, "gtsam_PreintegrationCombinedParams"); -// BOOST_CLASS_EXPORT_GUID(gtsam::CombinedImuFactor, "gtsam_CombinedImuFactor"); diff --git a/gtsam/navigation/ImuFactor.h b/gtsam/navigation/ImuFactor.h index 408cefdf0..7e080ffd5 100644 --- a/gtsam/navigation/ImuFactor.h +++ b/gtsam/navigation/ImuFactor.h @@ -164,7 +164,7 @@ private: void serialize(ARCHIVE & ar, const unsigned int /*version*/) { namespace bs = ::boost::serialization; ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(PreintegrationType); - ar & bs::make_nvp("preintMeasCov_", bs::make_array(preintMeasCov_.data(), preintMeasCov_.size())); + ar & BOOST_SERIALIZATION_NVP(preintMeasCov_); } }; diff --git a/gtsam/navigation/ManifoldPreintegration.h b/gtsam/navigation/ManifoldPreintegration.h index 97ad04744..a290972e4 100644 --- a/gtsam/navigation/ManifoldPreintegration.h +++ b/gtsam/navigation/ManifoldPreintegration.h @@ -120,11 +120,11 @@ private: namespace bs = ::boost::serialization; ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(PreintegrationBase); ar & BOOST_SERIALIZATION_NVP(deltaXij_); - ar & bs::make_nvp("delRdelBiasOmega_", bs::make_array(delRdelBiasOmega_.data(), delRdelBiasOmega_.size())); - ar & bs::make_nvp("delPdelBiasAcc_", bs::make_array(delPdelBiasAcc_.data(), delPdelBiasAcc_.size())); - ar & bs::make_nvp("delPdelBiasOmega_", bs::make_array(delPdelBiasOmega_.data(), delPdelBiasOmega_.size())); - ar & bs::make_nvp("delVdelBiasAcc_", bs::make_array(delVdelBiasAcc_.data(), delVdelBiasAcc_.size())); - ar & bs::make_nvp("delVdelBiasOmega_", bs::make_array(delVdelBiasOmega_.data(), delVdelBiasOmega_.size())); + ar & BOOST_SERIALIZATION_NVP(delRdelBiasOmega_); + ar & BOOST_SERIALIZATION_NVP(delPdelBiasAcc_); + ar & BOOST_SERIALIZATION_NVP(delPdelBiasOmega_); + ar & BOOST_SERIALIZATION_NVP(delVdelBiasAcc_); + ar & BOOST_SERIALIZATION_NVP(delVdelBiasOmega_); } }; diff --git a/gtsam/navigation/PreintegratedRotation.h b/gtsam/navigation/PreintegratedRotation.h index 12938a625..9346f749a 100644 --- a/gtsam/navigation/PreintegratedRotation.h +++ b/gtsam/navigation/PreintegratedRotation.h @@ -61,7 +61,7 @@ struct GTSAM_EXPORT PreintegratedRotationParams { template void serialize(ARCHIVE & ar, const unsigned int /*version*/) { namespace bs = ::boost::serialization; - ar & bs::make_nvp("gyroscopeCovariance", bs::make_array(gyroscopeCovariance.data(), gyroscopeCovariance.size())); + ar & BOOST_SERIALIZATION_NVP(gyroscopeCovariance); ar & BOOST_SERIALIZATION_NVP(omegaCoriolis); ar & BOOST_SERIALIZATION_NVP(body_P_sensor); } diff --git a/gtsam/navigation/PreintegrationParams.h b/gtsam/navigation/PreintegrationParams.h index de9950e7d..9ae66e678 100644 --- a/gtsam/navigation/PreintegrationParams.h +++ b/gtsam/navigation/PreintegrationParams.h @@ -76,8 +76,8 @@ protected: void serialize(ARCHIVE & ar, const unsigned int /*version*/) { namespace bs = ::boost::serialization; ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(PreintegratedRotationParams); - ar & bs::make_nvp("accelerometerCovariance", bs::make_array(accelerometerCovariance.data(), accelerometerCovariance.size())); - ar & bs::make_nvp("integrationCovariance", bs::make_array(integrationCovariance.data(), integrationCovariance.size())); + ar & BOOST_SERIALIZATION_NVP(accelerometerCovariance); + ar & BOOST_SERIALIZATION_NVP(integrationCovariance); ar & BOOST_SERIALIZATION_NVP(use2ndOrderCoriolis); ar & BOOST_SERIALIZATION_NVP(n_gravity); } diff --git a/gtsam/navigation/TangentPreintegration.h b/gtsam/navigation/TangentPreintegration.h index 99aa10b3f..1b51b4e1e 100644 --- a/gtsam/navigation/TangentPreintegration.h +++ b/gtsam/navigation/TangentPreintegration.h @@ -133,9 +133,9 @@ private: void serialize(ARCHIVE & ar, const unsigned int /*version*/) { namespace bs = ::boost::serialization; ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(PreintegrationBase); - ar & bs::make_nvp("preintegrated_", bs::make_array(preintegrated_.data(), preintegrated_.size())); - ar & bs::make_nvp("preintegrated_H_biasAcc_", bs::make_array(preintegrated_H_biasAcc_.data(), preintegrated_H_biasAcc_.size())); - ar & bs::make_nvp("preintegrated_H_biasOmega_", bs::make_array(preintegrated_H_biasOmega_.data(), preintegrated_H_biasOmega_.size())); + ar & BOOST_SERIALIZATION_NVP(preintegrated_); + ar & BOOST_SERIALIZATION_NVP(preintegrated_H_biasAcc_); + ar & BOOST_SERIALIZATION_NVP(preintegrated_H_biasOmega_); } public: From 018e6ba68cda05707fc250f3eab80c930710196f Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Thu, 9 Jul 2020 23:12:35 -0400 Subject: [PATCH 176/869] Generic Eigen::Matrix serialization for boost --- gtsam/base/Matrix.h | 41 ++++++++++++++++++++++++++++++++++------- 1 file changed, 34 insertions(+), 7 deletions(-) diff --git a/gtsam/base/Matrix.h b/gtsam/base/Matrix.h index fa70e5b00..b1c6268a7 100644 --- a/gtsam/base/Matrix.h +++ b/gtsam/base/Matrix.h @@ -549,16 +549,32 @@ namespace boost { namespace serialization { // split version - sends sizes ahead - template - void save(Archive & ar, const gtsam::Matrix & m, unsigned int /*version*/) { + template + void save(Archive & ar, + const Eigen::Matrix & m, + const unsigned int /*version*/) { const size_t rows = m.rows(), cols = m.cols(); ar << BOOST_SERIALIZATION_NVP(rows); ar << BOOST_SERIALIZATION_NVP(cols); ar << make_nvp("data", make_array(m.data(), m.size())); } - template - void load(Archive & ar, gtsam::Matrix & m, unsigned int /*version*/) { + template + void load(Archive & ar, + Eigen::Matrix & m, + const unsigned int /*version*/) { size_t rows, cols; ar >> BOOST_SERIALIZATION_NVP(rows); ar >> BOOST_SERIALIZATION_NVP(cols); @@ -566,8 +582,19 @@ namespace boost { ar >> make_nvp("data", make_array(m.data(), m.size())); } + // templated version of BOOST_SERIALIZATION_SPLIT_FREE(Eigen::Matrix); + template + void serialize(Archive & ar, + Eigen::Matrix & m, + const unsigned int version) { + split_free(ar, m, version); + } + } // namespace serialization } // namespace boost - -BOOST_SERIALIZATION_SPLIT_FREE(gtsam::Matrix); - From b1dda699a336ff868d498401b138869bbf9441b8 Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Thu, 9 Jul 2020 23:49:23 -0400 Subject: [PATCH 177/869] add compiler flags to suppress warnings if built in release mode --- gtsam/CMakeLists.txt | 5 +++++ 1 file changed, 5 insertions(+) diff --git a/gtsam/CMakeLists.txt b/gtsam/CMakeLists.txt index 3d1bbd2a7..2ca83e093 100644 --- a/gtsam/CMakeLists.txt +++ b/gtsam/CMakeLists.txt @@ -106,6 +106,11 @@ add_library(gtsam ${gtsam_srcs}) target_link_libraries(gtsam PUBLIC ${GTSAM_BOOST_LIBRARIES}) target_link_libraries(gtsam PUBLIC ${GTSAM_ADDITIONAL_LIBRARIES}) +if(${CMAKE_BUILD_TYPE} STREQUAL "Release") + # Suppress warnings if Release build + target_compile_options(gtsam PRIVATE -w) +endif() + # Apply build flags: gtsam_apply_build_flags(gtsam) From ca1427640459c23c07043746713b10559835cd9d Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Fri, 10 Jul 2020 00:15:12 -0400 Subject: [PATCH 178/869] Add MATLAB root and Mex paths to cmake output, align GTSAM specific output --- CMakeLists.txt | 50 +++++++++++++++++++++++++++----------------------- 1 file changed, 27 insertions(+), 23 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index a810ac9df..f6f012118 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -537,54 +537,54 @@ endif() print_build_options_for_target(gtsam) -message(STATUS " Use System Eigen : ${GTSAM_USE_SYSTEM_EIGEN} (Using version: ${GTSAM_EIGEN_VERSION})") +message(STATUS " Use System Eigen : ${GTSAM_USE_SYSTEM_EIGEN} (Using version: ${GTSAM_EIGEN_VERSION})") if(GTSAM_USE_TBB) - message(STATUS " Use Intel TBB : Yes") + message(STATUS " Use Intel TBB : Yes") elseif(TBB_FOUND) - message(STATUS " Use Intel TBB : TBB found but GTSAM_WITH_TBB is disabled") + message(STATUS " Use Intel TBB : TBB found but GTSAM_WITH_TBB is disabled") else() - message(STATUS " Use Intel TBB : TBB not found") + message(STATUS " Use Intel TBB : TBB not found") endif() if(GTSAM_USE_EIGEN_MKL) - message(STATUS " Eigen will use MKL : Yes") + message(STATUS " Eigen will use MKL : Yes") elseif(MKL_FOUND) - message(STATUS " Eigen will use MKL : MKL found but GTSAM_WITH_EIGEN_MKL is disabled") + message(STATUS " Eigen will use MKL : MKL found but GTSAM_WITH_EIGEN_MKL is disabled") else() - message(STATUS " Eigen will use MKL : MKL not found") + message(STATUS " Eigen will use MKL : MKL not found") endif() if(GTSAM_USE_EIGEN_MKL_OPENMP) - message(STATUS " Eigen will use MKL and OpenMP : Yes") + message(STATUS " Eigen will use MKL and OpenMP : Yes") elseif(OPENMP_FOUND AND NOT GTSAM_WITH_EIGEN_MKL) - message(STATUS " Eigen will use MKL and OpenMP : OpenMP found but GTSAM_WITH_EIGEN_MKL is disabled") + message(STATUS " Eigen will use MKL and OpenMP : OpenMP found but GTSAM_WITH_EIGEN_MKL is disabled") elseif(OPENMP_FOUND AND NOT MKL_FOUND) - message(STATUS " Eigen will use MKL and OpenMP : OpenMP found but MKL not found") + message(STATUS " Eigen will use MKL and OpenMP : OpenMP found but MKL not found") elseif(OPENMP_FOUND) - message(STATUS " Eigen will use MKL and OpenMP : OpenMP found but GTSAM_WITH_EIGEN_MKL_OPENMP is disabled") + message(STATUS " Eigen will use MKL and OpenMP : OpenMP found but GTSAM_WITH_EIGEN_MKL_OPENMP is disabled") else() - message(STATUS " Eigen will use MKL and OpenMP : OpenMP not found") + message(STATUS " Eigen will use MKL and OpenMP : OpenMP not found") endif() -message(STATUS " Default allocator : ${GTSAM_DEFAULT_ALLOCATOR}") +message(STATUS " Default allocator : ${GTSAM_DEFAULT_ALLOCATOR}") if(GTSAM_THROW_CHEIRALITY_EXCEPTION) - message(STATUS " Cheirality exceptions enabled : YES") + message(STATUS " Cheirality exceptions enabled : YES") else() - message(STATUS " Cheirality exceptions enabled : NO") + message(STATUS " Cheirality exceptions enabled : NO") endif() if(NOT MSVC AND NOT XCODE_VERSION) if(CCACHE_FOUND AND GTSAM_BUILD_WITH_CCACHE) - message(STATUS " Build with ccache : Yes") + message(STATUS " Build with ccache : Yes") elseif(CCACHE_FOUND) - message(STATUS " Build with ccache : ccache found but GTSAM_BUILD_WITH_CCACHE is disabled") + message(STATUS " Build with ccache : ccache found but GTSAM_BUILD_WITH_CCACHE is disabled") else() - message(STATUS " Build with ccache : No") + message(STATUS " Build with ccache : No") endif() endif() message(STATUS "Packaging flags ") -message(STATUS " CPack Source Generator : ${CPACK_SOURCE_GENERATOR}") -message(STATUS " CPack Generator : ${CPACK_GENERATOR}") +message(STATUS " CPack Source Generator : ${CPACK_SOURCE_GENERATOR}") +message(STATUS " CPack Generator : ${CPACK_GENERATOR}") message(STATUS "GTSAM flags ") print_config_flag(${GTSAM_USE_QUATERNIONS} "Quaternions as default Rot3 ") @@ -595,13 +595,17 @@ print_config_flag(${GTSAM_ALLOW_DEPRECATED_SINCE_V4} "Deprecated in GTSAM 4 al print_config_flag(${GTSAM_TYPEDEF_POINTS_TO_VECTORS} "Point3 is typedef to Vector3 ") print_config_flag(${GTSAM_SUPPORT_NESTED_DISSECTION} "Metis-based Nested Dissection ") print_config_flag(${GTSAM_TANGENT_PREINTEGRATION} "Use tangent-space preintegration") -print_config_flag(${GTSAM_BUILD_WRAP} "Build Wrap ") +print_config_flag(${GTSAM_BUILD_WRAP} "Build Wrap ") message(STATUS "MATLAB toolbox flags ") -print_config_flag(${GTSAM_INSTALL_MATLAB_TOOLBOX} "Install matlab toolbox ") +print_config_flag(${GTSAM_INSTALL_MATLAB_TOOLBOX} "Install MATLAB toolbox ") +if (${GTSAM_INSTALL_MATLAB_TOOLBOX}) + message(STATUS " MATLAB root : ${MATLAB_ROOT}") + message(STATUS " MEX binary : ${MEX_COMMAND}") +endif() message(STATUS "Cython toolbox flags ") -print_config_flag(${GTSAM_INSTALL_CYTHON_TOOLBOX} "Install Cython toolbox ") +print_config_flag(${GTSAM_INSTALL_CYTHON_TOOLBOX} "Install Cython toolbox ") if(GTSAM_INSTALL_CYTHON_TOOLBOX) message(STATUS " Python version : ${GTSAM_PYTHON_VERSION}") endif() From 10a131fc365146f970e33dc0c3939dc9189385f3 Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Fri, 10 Jul 2020 00:19:54 -0400 Subject: [PATCH 179/869] Quote variable so it works on Windows --- gtsam/CMakeLists.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/gtsam/CMakeLists.txt b/gtsam/CMakeLists.txt index 2ca83e093..c4ad0a755 100644 --- a/gtsam/CMakeLists.txt +++ b/gtsam/CMakeLists.txt @@ -106,7 +106,7 @@ add_library(gtsam ${gtsam_srcs}) target_link_libraries(gtsam PUBLIC ${GTSAM_BOOST_LIBRARIES}) target_link_libraries(gtsam PUBLIC ${GTSAM_ADDITIONAL_LIBRARIES}) -if(${CMAKE_BUILD_TYPE} STREQUAL "Release") +if("${CMAKE_BUILD_TYPE}" STREQUAL "Release") # Suppress warnings if Release build target_compile_options(gtsam PRIVATE -w) endif() From 7259f899d9a37b575853cc2d0ce415e6966d6c6e Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Fri, 10 Jul 2020 09:26:48 -0400 Subject: [PATCH 180/869] Use static matrix and constexpr --- gtsam/slam/SmartFactorBase.h | 13 +++++++------ 1 file changed, 7 insertions(+), 6 deletions(-) diff --git a/gtsam/slam/SmartFactorBase.h b/gtsam/slam/SmartFactorBase.h index 912de0bc1..1c80b8744 100644 --- a/gtsam/slam/SmartFactorBase.h +++ b/gtsam/slam/SmartFactorBase.h @@ -207,17 +207,18 @@ protected: Vector ue = cameras.reprojectionError(point, measured_, Fs, E); if (body_P_sensor_ && Fs) { const Pose3 sensor_P_body = body_P_sensor_->inverse(); - size_t camera_dim = size_t(traits::dimension); - size_t pose_dim = size_t(traits::dimension); + constexpr int camera_dim = traits::dimension; + constexpr int pose_dim = traits::dimension; for (size_t i = 0; i < Fs->size(); i++) { const Pose3 world_P_body = cameras[i].pose() * sensor_P_body; - Matrix J = Matrix::Zero(camera_dim, camera_dim); + Eigen::Matrix J; + J.setZero(); + Eigen::Matrix H; // Call compose to compute Jacobian for camera extrinsics - Matrix H(pose_dim, pose_dim); world_P_body.compose(*body_P_sensor_, H); - // Assign extrinsics - J.block(0, 0, pose_dim, pose_dim) = H; + // Assign extrinsics part of the Jacobian + J.template block(0, 0) = H; Fs->at(i) = Fs->at(i) * J; } } From b735174707aa379cdc47e3dce5a7c74f20e7c36f Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Fri, 10 Jul 2020 10:03:38 -0400 Subject: [PATCH 181/869] use boost serialization macro instead of make_array --- gtsam/navigation/ImuFactor.h | 2 +- gtsam/navigation/ManifoldPreintegration.h | 10 +++++----- gtsam/navigation/PreintegratedRotation.h | 2 +- gtsam/navigation/PreintegrationParams.h | 4 ++-- gtsam/navigation/TangentPreintegration.h | 6 +++--- 5 files changed, 12 insertions(+), 12 deletions(-) diff --git a/gtsam/navigation/ImuFactor.h b/gtsam/navigation/ImuFactor.h index 8e3f8f0a4..a69fab6e9 100644 --- a/gtsam/navigation/ImuFactor.h +++ b/gtsam/navigation/ImuFactor.h @@ -164,7 +164,7 @@ private: void serialize(ARCHIVE & ar, const unsigned int /*version*/) { namespace bs = ::boost::serialization; ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(PreintegrationType); - ar & bs::make_nvp("preintMeasCov_", bs::make_array(preintMeasCov_.data(), preintMeasCov_.size())); + ar & BOOST_SERIALIZATION_NVP(preintMeasCov_); } }; diff --git a/gtsam/navigation/ManifoldPreintegration.h b/gtsam/navigation/ManifoldPreintegration.h index 22897b9d4..ee983a78f 100644 --- a/gtsam/navigation/ManifoldPreintegration.h +++ b/gtsam/navigation/ManifoldPreintegration.h @@ -122,11 +122,11 @@ private: ar & BOOST_SERIALIZATION_NVP(deltaTij_); ar & BOOST_SERIALIZATION_NVP(deltaXij_); ar & BOOST_SERIALIZATION_NVP(biasHat_); - ar & bs::make_nvp("delRdelBiasOmega_", bs::make_array(delRdelBiasOmega_.data(), delRdelBiasOmega_.size())); - ar & bs::make_nvp("delPdelBiasAcc_", bs::make_array(delPdelBiasAcc_.data(), delPdelBiasAcc_.size())); - ar & bs::make_nvp("delPdelBiasOmega_", bs::make_array(delPdelBiasOmega_.data(), delPdelBiasOmega_.size())); - ar & bs::make_nvp("delVdelBiasAcc_", bs::make_array(delVdelBiasAcc_.data(), delVdelBiasAcc_.size())); - ar & bs::make_nvp("delVdelBiasOmega_", bs::make_array(delVdelBiasOmega_.data(), delVdelBiasOmega_.size())); + ar & BOOST_SERIALIZATION_NVP(delRdelBiasOmega_); + ar & BOOST_SERIALIZATION_NVP(delPdelBiasAcc_); + ar & BOOST_SERIALIZATION_NVP(delPdelBiasOmega_); + ar & BOOST_SERIALIZATION_NVP(delVdelBiasAcc_); + ar & BOOST_SERIALIZATION_NVP(delVdelBiasOmega_); } }; diff --git a/gtsam/navigation/PreintegratedRotation.h b/gtsam/navigation/PreintegratedRotation.h index 12938a625..9346f749a 100644 --- a/gtsam/navigation/PreintegratedRotation.h +++ b/gtsam/navigation/PreintegratedRotation.h @@ -61,7 +61,7 @@ struct GTSAM_EXPORT PreintegratedRotationParams { template void serialize(ARCHIVE & ar, const unsigned int /*version*/) { namespace bs = ::boost::serialization; - ar & bs::make_nvp("gyroscopeCovariance", bs::make_array(gyroscopeCovariance.data(), gyroscopeCovariance.size())); + ar & BOOST_SERIALIZATION_NVP(gyroscopeCovariance); ar & BOOST_SERIALIZATION_NVP(omegaCoriolis); ar & BOOST_SERIALIZATION_NVP(body_P_sensor); } diff --git a/gtsam/navigation/PreintegrationParams.h b/gtsam/navigation/PreintegrationParams.h index 4bff625ca..d997ccbed 100644 --- a/gtsam/navigation/PreintegrationParams.h +++ b/gtsam/navigation/PreintegrationParams.h @@ -75,8 +75,8 @@ protected: namespace bs = ::boost::serialization; ar & boost::serialization::make_nvp("PreintegratedRotation_Params", boost::serialization::base_object(*this)); - ar & bs::make_nvp("accelerometerCovariance", bs::make_array(accelerometerCovariance.data(), accelerometerCovariance.size())); - ar & bs::make_nvp("integrationCovariance", bs::make_array(integrationCovariance.data(), integrationCovariance.size())); + ar & BOOST_SERIALIZATION_NVP(accelerometerCovariance); + ar & BOOST_SERIALIZATION_NVP(integrationCovariance); ar & BOOST_SERIALIZATION_NVP(use2ndOrderCoriolis); ar & BOOST_SERIALIZATION_NVP(n_gravity); } diff --git a/gtsam/navigation/TangentPreintegration.h b/gtsam/navigation/TangentPreintegration.h index edf76e562..29318a6bb 100644 --- a/gtsam/navigation/TangentPreintegration.h +++ b/gtsam/navigation/TangentPreintegration.h @@ -135,9 +135,9 @@ private: ar & BOOST_SERIALIZATION_NVP(p_); ar & BOOST_SERIALIZATION_NVP(biasHat_); ar & BOOST_SERIALIZATION_NVP(deltaTij_); - ar & bs::make_nvp("preintegrated_", bs::make_array(preintegrated_.data(), preintegrated_.size())); - ar & bs::make_nvp("preintegrated_H_biasAcc_", bs::make_array(preintegrated_H_biasAcc_.data(), preintegrated_H_biasAcc_.size())); - ar & bs::make_nvp("preintegrated_H_biasOmega_", bs::make_array(preintegrated_H_biasOmega_.data(), preintegrated_H_biasOmega_.size())); + ar & BOOST_SERIALIZATION_NVP(preintegrated_); + ar & BOOST_SERIALIZATION_NVP(preintegrated_H_biasAcc_); + ar & BOOST_SERIALIZATION_NVP(preintegrated_H_biasOmega_); } public: From 3f4731a9482d71ce65174140713b9c0384a38eec Mon Sep 17 00:00:00 2001 From: Fan Jiang Date: Fri, 10 Jul 2020 15:00:57 -0400 Subject: [PATCH 182/869] Added wrapping for the PCG solver in Cython --- gtsam.h | 16 ++++++++++++++++ gtsam/linear/PCGSolver.cpp | 11 +++++++++++ gtsam/linear/PCGSolver.h | 4 ++++ 3 files changed, 31 insertions(+) diff --git a/gtsam.h b/gtsam.h index 614db91c7..d65186439 100644 --- a/gtsam.h +++ b/gtsam.h @@ -1937,6 +1937,22 @@ virtual class ConjugateGradientParameters : gtsam::IterativeOptimizationParamete void print() const; }; +#include +virtual class PreconditionerParameters { + PreconditionerParameters(); +}; + +virtual class DummyPreconditionerParameters : gtsam::PreconditionerParameters { + DummyPreconditionerParameters(); +}; + +#include +virtual class PCGSolverParameters : gtsam::ConjugateGradientParameters { + PCGSolverParameters(); + void print(string s); + void setPreconditionerParams(gtsam::PreconditionerParameters* preconditioner); +}; + #include virtual class SubgraphSolverParameters : gtsam::ConjugateGradientParameters { SubgraphSolverParameters(); diff --git a/gtsam/linear/PCGSolver.cpp b/gtsam/linear/PCGSolver.cpp index 08307c5ab..a7af7d8d8 100644 --- a/gtsam/linear/PCGSolver.cpp +++ b/gtsam/linear/PCGSolver.cpp @@ -45,6 +45,17 @@ PCGSolver::PCGSolver(const PCGSolverParameters &p) { preconditioner_ = createPreconditioner(p.preconditioner_); } +void PCGSolverParameters::setPreconditionerParams(const boost::shared_ptr preconditioner) { + preconditioner_ = preconditioner; +} + +void PCGSolverParameters::print(const std::string &s) const { + std::cout << s << std::endl;; + std::ostringstream os; + print(os); + std::cout << os.str() << std::endl; +} + /*****************************************************************************/ VectorValues PCGSolver::optimize(const GaussianFactorGraph &gfg, const KeyInfo &keyInfo, const std::map &lambda, diff --git a/gtsam/linear/PCGSolver.h b/gtsam/linear/PCGSolver.h index f5b278ae5..3e72c7cbe 100644 --- a/gtsam/linear/PCGSolver.h +++ b/gtsam/linear/PCGSolver.h @@ -48,7 +48,11 @@ public: return *preconditioner_; } + void print(const std::string &s) const; + boost::shared_ptr preconditioner_; + + void setPreconditionerParams(const boost::shared_ptr preconditioner); }; /** From 7f293eb84e66b6468c92257e52741fbdfd8d13b0 Mon Sep 17 00:00:00 2001 From: Fan Jiang Date: Fri, 10 Jul 2020 15:01:54 -0400 Subject: [PATCH 183/869] add comments --- gtsam/linear/PCGSolver.h | 1 + 1 file changed, 1 insertion(+) diff --git a/gtsam/linear/PCGSolver.h b/gtsam/linear/PCGSolver.h index 3e72c7cbe..7752902ba 100644 --- a/gtsam/linear/PCGSolver.h +++ b/gtsam/linear/PCGSolver.h @@ -48,6 +48,7 @@ public: return *preconditioner_; } + // needed for python wrapper void print(const std::string &s) const; boost::shared_ptr preconditioner_; From 1fadf1e7ef032e5e6a6d74e5a1a5e8cf7865ce3d Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Fri, 10 Jul 2020 21:43:30 -0400 Subject: [PATCH 184/869] suppress warnings only for 3rd party code for Release builds --- gtsam/CMakeLists.txt | 17 +++++++++-------- 1 file changed, 9 insertions(+), 8 deletions(-) diff --git a/gtsam/CMakeLists.txt b/gtsam/CMakeLists.txt index c4ad0a755..a927ca3a0 100644 --- a/gtsam/CMakeLists.txt +++ b/gtsam/CMakeLists.txt @@ -15,7 +15,7 @@ set (gtsam_subdirs sfm slam smart - navigation + navigation ) set(gtsam_srcs) @@ -106,11 +106,6 @@ add_library(gtsam ${gtsam_srcs}) target_link_libraries(gtsam PUBLIC ${GTSAM_BOOST_LIBRARIES}) target_link_libraries(gtsam PUBLIC ${GTSAM_ADDITIONAL_LIBRARIES}) -if("${CMAKE_BUILD_TYPE}" STREQUAL "Release") - # Suppress warnings if Release build - target_compile_options(gtsam PRIVATE -w) -endif() - # Apply build flags: gtsam_apply_build_flags(gtsam) @@ -191,11 +186,17 @@ install( list(APPEND GTSAM_EXPORTED_TARGETS gtsam) set(GTSAM_EXPORTED_TARGETS "${GTSAM_EXPORTED_TARGETS}" PARENT_SCOPE) -# make sure that ccolamd compiles even in face of warnings +# Make sure that ccolamd compiles even in face of warnings +# and suppress all warnings from 3rd party code if Release build if(WIN32) - set_source_files_properties(${3rdparty_srcs} PROPERTIES COMPILE_FLAGS "-w") + set_source_files_properties(${3rdparty_srcs} PROPERTIES COMPILE_FLAGS "-w") else() + if("${CMAKE_BUILD_TYPE}" STREQUAL "Release") + # Suppress all warnings from 3rd party sources. + set_source_files_properties(${3rdparty_srcs} PROPERTIES COMPILE_FLAGS "-w") + else() set_source_files_properties(${3rdparty_srcs} PROPERTIES COMPILE_FLAGS "-Wno-error") + endif() endif() # Create the matlab toolbox for the gtsam library From e41dbfc26cff7c0f6d0dd44ba61280a779438298 Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Fri, 10 Jul 2020 21:45:01 -0400 Subject: [PATCH 185/869] fix init issues with Vector3, use static matrices where possible --- examples/IMUKittiExampleGPS.cpp | 22 ++++++++++++++-------- 1 file changed, 14 insertions(+), 8 deletions(-) diff --git a/examples/IMUKittiExampleGPS.cpp b/examples/IMUKittiExampleGPS.cpp index 7cfccbc11..f1d89b47a 100644 --- a/examples/IMUKittiExampleGPS.cpp +++ b/examples/IMUKittiExampleGPS.cpp @@ -163,7 +163,7 @@ int main(int argc, char* argv[]) { vector gps_measurements; loadKittiData(kitti_calibration, imu_measurements, gps_measurements); - Vector6 BodyP = (Vector(6) << kitti_calibration.body_ptx, kitti_calibration.body_pty, kitti_calibration.body_ptz, + Vector6 BodyP = (Vector6() << kitti_calibration.body_ptx, kitti_calibration.body_pty, kitti_calibration.body_ptz, kitti_calibration.body_prx, kitti_calibration.body_pry, kitti_calibration.body_prz) .finished(); auto body_T_imu = Pose3::Expmap(BodyP); @@ -173,28 +173,29 @@ int main(int argc, char* argv[]) { } // Configure different variables - double t_offset = gps_measurements[0].time; + // double t_offset = gps_measurements[0].time; size_t first_gps_pose = 1; size_t gps_skip = 10; // Skip this many GPS measurements each time double g = 9.8; - auto w_coriolis = Vector3(); // zero vector + auto w_coriolis = Vector3::Zero(); // zero vector // Configure noise models - auto noise_model_gps = noiseModel::Diagonal::Precisions((Vector(6) << Vector3::Constant(0), + auto noise_model_gps = noiseModel::Diagonal::Precisions((Vector6() << Vector3::Constant(0), Vector3::Constant(1.0/0.07)) .finished()); // Set initial conditions for the estimated trajectory // initial pose is the reference frame (navigation frame) auto current_pose_global = Pose3(Rot3(), gps_measurements[first_gps_pose].position); - auto current_velocity_global = Vector3(); // the vehicle is stationary at the beginning at position 0,0,0 + // the vehicle is stationary at the beginning at position 0,0,0 + Vector3 current_velocity_global = Vector3::Zero(); auto current_bias = imuBias::ConstantBias(); // init with zero bias - auto sigma_init_x = noiseModel::Diagonal::Precisions((Vector(6) << Vector3::Constant(0), + auto sigma_init_x = noiseModel::Diagonal::Precisions((Vector6() << Vector3::Constant(0), Vector3::Constant(1.0)) .finished()); auto sigma_init_v = noiseModel::Diagonal::Sigmas(Vector3::Constant(1000.0)); - auto sigma_init_b = noiseModel::Diagonal::Sigmas((Vector(6) << Vector3::Constant(0.100), + auto sigma_init_b = noiseModel::Diagonal::Sigmas((Vector6() << Vector3::Constant(0.100), Vector3::Constant(5.00e-05)) .finished()); @@ -270,7 +271,7 @@ int main(int argc, char* argv[]) { previous_bias_key, *current_summarized_measurement); // Bias evolution as given in the IMU metadata - auto sigma_between_b = noiseModel::Diagonal::Sigmas((Vector(6) << + auto sigma_between_b = noiseModel::Diagonal::Sigmas((Vector6() << Vector3::Constant(sqrt(included_imu_measurement_count) * kitti_calibration.accelerometer_bias_sigma), Vector3::Constant(sqrt(included_imu_measurement_count) * kitti_calibration.gyroscope_bias_sigma)) .finished()); @@ -342,6 +343,11 @@ int main(int argc, char* argv[]) { auto pose_quat = pose.rotation().toQuaternion(); auto gps = gps_measurements[i].position; + cout << "State at #" << i << endl; + cout << "Pose:" << endl << pose << endl; + cout << "Velocity:" << endl << velocity << endl; + cout << "Bias:" << endl << bias << endl; + fprintf(fp_out, "%f,%f,%f,%f,%f,%f,%f,%f,%f,%f,%f\n", gps_measurements[i].time, pose.x(), pose.y(), pose.z(), From 09ddd433a60f4c89286202d08ade957bbd06269b Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Fri, 10 Jul 2020 21:51:36 -0400 Subject: [PATCH 186/869] added note about code source and eigen resize for both static and dynamic matrices --- gtsam/base/Matrix.h | 14 ++++++++++++++ 1 file changed, 14 insertions(+) diff --git a/gtsam/base/Matrix.h b/gtsam/base/Matrix.h index b1c6268a7..37ae1dd9a 100644 --- a/gtsam/base/Matrix.h +++ b/gtsam/base/Matrix.h @@ -548,6 +548,20 @@ GTSAM_EXPORT Vector columnNormSquare(const Matrix &A); namespace boost { namespace serialization { + /** + * Ref. https://stackoverflow.com/questions/18382457/eigen-and-boostserialize/22903063#22903063 + * + * Eigen supports calling resize() on both static and dynamic matrices. + * This allows for a uniform API, with resize having no effect if the static matrix + * is already the correct size. + * https://eigen.tuxfamily.org/dox/group__TutorialMatrixClass.html#TutorialMatrixSizesResizing + * + * We use all the Matrix template parameters to ensure wide compatibility. + * + * eigen_typekit in ROS uses the same code + * http://docs.ros.org/lunar/api/eigen_typekit/html/eigen__mqueue_8cpp_source.html + */ + // split version - sends sizes ahead template Date: Fri, 10 Jul 2020 23:01:18 -0400 Subject: [PATCH 187/869] Explicit type definition to handle warning --- examples/SFMExample.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/examples/SFMExample.cpp b/examples/SFMExample.cpp index 7f0c79e0e..fddca8169 100644 --- a/examples/SFMExample.cpp +++ b/examples/SFMExample.cpp @@ -109,7 +109,7 @@ int main(int argc, char* argv[]) { Symbol('x', i), corrupted_pose); } for (size_t j = 0; j < points.size(); ++j) { - auto corrupted_point = points[j] + Point3(-0.25, 0.20, 0.15); + Point3 corrupted_point = points[j] + Point3(-0.25, 0.20, 0.15); initialEstimate.insert(Symbol('l', j), corrupted_point); } initialEstimate.print("Initial Estimates:\n"); From 7d274315724268c858a269991e6cafafd6c13f1d Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Sat, 11 Jul 2020 02:52:34 -0400 Subject: [PATCH 188/869] support for landmarks in g2o files --- gtsam/slam/dataset.cpp | 102 ++++++++++++++++++++++++++----- gtsam/slam/dataset.h | 17 +++++- gtsam/slam/tests/testDataset.cpp | 27 +++++++- 3 files changed, 128 insertions(+), 18 deletions(-) diff --git a/gtsam/slam/dataset.cpp b/gtsam/slam/dataset.cpp index 669935994..cb15f84a8 100644 --- a/gtsam/slam/dataset.cpp +++ b/gtsam/slam/dataset.cpp @@ -11,7 +11,10 @@ /** * @file dataset.cpp * @date Jan 22, 2010 - * @author Kai Ni, Luca Carlone, Frank Dellaert + * @author Kai Ni + * @author Luca Carlone + * @author Frank Dellaert + * @author Varun Agrawal * @brief utility functions for loading datasets */ @@ -193,7 +196,7 @@ static SharedNoiseModel readNoiseModel(ifstream& is, bool smart, } /* ************************************************************************* */ -boost::optional parseVertex(istream& is, const string& tag) { +boost::optional parseVertexPose(istream& is, const string& tag) { if ((tag == "VERTEX2") || (tag == "VERTEX_SE2") || (tag == "VERTEX")) { Key id; double x, y, yaw; @@ -204,6 +207,18 @@ boost::optional parseVertex(istream& is, const string& tag) { } } +/* ************************************************************************* */ +boost::optional parseVertexLandmark(istream& is, const string& tag) { + if (tag == "VERTEX_XY") { + Key id; + double x, y; + is >> id >> x >> y; + return IndexedLandmark(id, Point2(x, y)); + } else { + return boost::none; + } +} + /* ************************************************************************* */ boost::optional parseEdge(istream& is, const string& tag) { if ((tag == "EDGE2") || (tag == "EDGE") || (tag == "EDGE_SE2") @@ -232,12 +247,12 @@ GraphAndValues load2D(const string& filename, SharedNoiseModel model, Key maxID, string tag; - // load the poses + // load the poses and landmarks while (!is.eof()) { if (!(is >> tag)) break; - const auto indexed_pose = parseVertex(is, tag); + const auto indexed_pose = parseVertexPose(is, tag); if (indexed_pose) { Key id = indexed_pose->first; @@ -247,6 +262,16 @@ GraphAndValues load2D(const string& filename, SharedNoiseModel model, Key maxID, initial->insert(id, indexed_pose->second); } + const auto indexed_landmark = parseVertexLandmark(is, tag); + if (indexed_landmark) { + Key id = indexed_landmark->first; + + // optional filter + if (maxID && id >= maxID) + continue; + + initial->insert(id, indexed_landmark->second); + } is.ignore(LINESIZE, '\n'); } is.clear(); /* clears the end-of-file and error flags */ @@ -429,7 +454,7 @@ void writeG2o(const NonlinearFactorGraph& graph, const Values& estimate, const string& filename) { fstream stream(filename.c_str(), fstream::out); - // save 2D & 3D poses + // save 2D poses for (const auto& key_value : estimate) { auto p = dynamic_cast*>(&key_value.value); if (!p) continue; @@ -438,15 +463,34 @@ void writeG2o(const NonlinearFactorGraph& graph, const Values& estimate, << pose.y() << " " << pose.theta() << endl; } + // save 3D poses for(const auto& key_value: estimate) { - auto p = dynamic_cast*>(&key_value.value); - if (!p) continue; - const Pose3& pose = p->value(); - const Point3 t = pose.translation(); - const auto q = pose.rotation().toQuaternion(); - stream << "VERTEX_SE3:QUAT " << key_value.key << " " << t.x() << " " - << t.y() << " " << t.z() << " " << q.x() << " " << q.y() << " " - << q.z() << " " << q.w() << endl; + auto p = dynamic_cast*>(&key_value.value); + if (!p) continue; + const Pose3& pose = p->value(); + const Point3 t = pose.translation(); + const auto q = pose.rotation().toQuaternion(); + stream << "VERTEX_SE3:QUAT " << key_value.key << " " << t.x() << " " + << t.y() << " " << t.z() << " " << q.x() << " " << q.y() << " " + << q.z() << " " << q.w() << endl; + } + + // save 2D landmarks + for(const auto& key_value: estimate) { + auto p = dynamic_cast*>(&key_value.value); + if (!p) continue; + const Point2& point = p->value(); + stream << "VERTEX_XY " << key_value.key << " " << point.x() << " " + << point.y() << endl; + } + + // save 3D landmarks + for(const auto& key_value: estimate) { + auto p = dynamic_cast*>(&key_value.value); + if (!p) continue; + const Point3& point = p->value(); + stream << "VERTEX_TRACKXYZ " << key_value.key << " " << point.x() << " " + << point.y() << " " << point.z() << endl; } // save edges (2D or 3D) @@ -515,6 +559,7 @@ static Rot3 NormalizedRot3(double w, double x, double y, double z) { const double norm = sqrt(w * w + x * x + y * y + z * z), f = 1.0 / norm; return Rot3::Quaternion(f * w, f * x, f * y, f * z); } + /* ************************************************************************* */ std::map parse3DPoses(const string& filename) { ifstream is(filename.c_str()); @@ -545,6 +590,30 @@ std::map parse3DPoses(const string& filename) { return poses; } +/* ************************************************************************* */ +std::map parse3DLandmarks(const string& filename) { + ifstream is(filename.c_str()); + if (!is) + throw invalid_argument("parse3DLandmarks: can not find file " + filename); + + std::map landmarks; + while (!is.eof()) { + char buf[LINESIZE]; + is.getline(buf, LINESIZE); + istringstream ls(buf); + string tag; + ls >> tag; + + if (tag == "VERTEX_TRACKXYZ") { + Key id; + double x, y, z; + ls >> id >> x >> y >> z; + landmarks.emplace(id, Point3(x, y, z)); + } + } + return landmarks; +} + /* ************************************************************************* */ BetweenFactorPose3s parse3DFactors( const string& filename, @@ -617,11 +686,16 @@ GraphAndValues load3D(const string& filename) { graph->push_back(factor); } - const auto poses = parse3DPoses(filename); Values::shared_ptr initial(new Values); + + const auto poses = parse3DPoses(filename); for (const auto& key_pose : poses) { initial->insert(key_pose.first, key_pose.second); } + const auto landmarks = parse3DLandmarks(filename); + for (const auto& key_landmark : landmarks) { + initial->insert(key_landmark.first, key_landmark.second); + } return make_pair(graph, initial); } diff --git a/gtsam/slam/dataset.h b/gtsam/slam/dataset.h index 032799429..a18ae12f6 100644 --- a/gtsam/slam/dataset.h +++ b/gtsam/slam/dataset.h @@ -76,6 +76,7 @@ enum KernelFunctionType { /// Return type for auxiliary functions typedef std::pair IndexedPose; +typedef std::pair IndexedLandmark; typedef std::pair, Pose2> IndexedEdge; /** @@ -83,9 +84,18 @@ typedef std::pair, Pose2> IndexedEdge; * @param is input stream * @param tag string parsed from input stream, will only parse if vertex type */ -GTSAM_EXPORT boost::optional parseVertex(std::istream& is, +GTSAM_EXPORT boost::optional parseVertexPose(std::istream& is, const std::string& tag); +/** + * Parse G2O landmark vertex "id x y" + * @param is input stream + * @param tag string parsed from input stream, will only parse if vertex type + */ + +GTSAM_EXPORT boost::optional parseVertexLandmark(std::istream& is, + const std::string& tag) + /** * Parse TORO/G2O edge "id1 id2 x y yaw" * @param is input stream @@ -162,9 +172,12 @@ using BetweenFactorPose3s = std::vector::shared_ptr> GTSAM_EXPORT BetweenFactorPose3s parse3DFactors(const std::string& filename, const noiseModel::Diagonal::shared_ptr& corruptingNoise=nullptr); -/// Parse vertices in 3D TORO graph file into a map of Pose3s. +/// Parse vertices in 3D TORO/g2o graph file into a map of Pose3s. GTSAM_EXPORT std::map parse3DPoses(const std::string& filename); +/// Parse landmarks in 3D g2o graph file into a map of Point3s. +GTSAM_EXPORT std::map parse3DLandmarks(const string& filename) + /// Load TORO 3D Graph GTSAM_EXPORT GraphAndValues load3D(const std::string& filename); diff --git a/gtsam/slam/tests/testDataset.cpp b/gtsam/slam/tests/testDataset.cpp index 8088ab18a..136b7a93c 100644 --- a/gtsam/slam/tests/testDataset.cpp +++ b/gtsam/slam/tests/testDataset.cpp @@ -43,13 +43,13 @@ TEST(dataSet, findExampleDataFile) { } /* ************************************************************************* */ -TEST( dataSet, parseVertex) +TEST( dataSet, parseVertexPose) { const string str = "VERTEX2 1 2.000000 3.000000 4.000000"; istringstream is(str); string tag; EXPECT(is >> tag); - const auto actual = parseVertex(is, tag); + const auto actual = parseVertexPose(is, tag); EXPECT(actual); if (actual) { EXPECT_LONGS_EQUAL(1, actual->first); @@ -57,6 +57,21 @@ TEST( dataSet, parseVertex) } } +/* ************************************************************************* */ +TEST( dataSet, parseVertexLandmark) +{ + const string str = "VERTEX_XY 1 2.000000 3.000000"; + istringstream is(str); + string tag; + EXPECT(is >> tag); + const auto actual = parseVertexLandmark(is, tag); + EXPECT(actual); + if (actual) { + EXPECT_LONGS_EQUAL(1, actual->first); + EXPECT(assert_equal(Point2(2, 3), actual->second)); + } +} + /* ************************************************************************* */ TEST( dataSet, parseEdge) { @@ -182,6 +197,12 @@ TEST(dataSet, readG2o3D) { EXPECT(assert_equal(poses[j], actualPoses.at(j), 1e-5)); } + // Check landmark parsing + const auto actualLandmarks = parse3DLandmarks(g2oFile); + for (size_t j : {0, 1, 2, 3, 4}) { + EXPECT(assert_equal(poses[j], actualPoses.at(j), 1e-5)); + } + // Check graph version NonlinearFactorGraph::shared_ptr actualGraph; Values::shared_ptr actualValues; @@ -252,6 +273,8 @@ TEST(dataSet, readG2oCheckDeterminants) { const Rot3 R = key_value.second.rotation(); EXPECT_DOUBLES_EQUAL(1.0, R.matrix().determinant(), 1e-9); } + const map landmarks = parse3DLandmarks(g2oFile); + EXPECT_LONGS_EQUAL(0, landmarks.size()); } /* ************************************************************************* */ From 8e5f1447e3d57b4722f1089b1fc5152e966cfc00 Mon Sep 17 00:00:00 2001 From: Fan Jiang Date: Sat, 11 Jul 2020 11:54:40 -0400 Subject: [PATCH 189/869] Add check to ensure we are calling lambda on a LM --- cython/gtsam/tests/test_logging_optimizer.py | 15 +++++++++++++++ cython/gtsam/utils/logging_optimizer.py | 3 ++- 2 files changed, 17 insertions(+), 1 deletion(-) diff --git a/cython/gtsam/tests/test_logging_optimizer.py b/cython/gtsam/tests/test_logging_optimizer.py index 69665db65..2560a72a2 100644 --- a/cython/gtsam/tests/test_logging_optimizer.py +++ b/cython/gtsam/tests/test_logging_optimizer.py @@ -43,6 +43,11 @@ class TestOptimizeComet(GtsamTestCase): self.optimizer = gtsam.GaussNewtonOptimizer( graph, initial, self.params) + self.lmparams = gtsam.LevenbergMarquardtParams() + self.lmoptimizer = gtsam.LevenbergMarquardtOptimizer( + graph, initial, self.lmparams + ) + # setup output capture self.capturedOutput = StringIO() sys.stdout = self.capturedOutput @@ -65,6 +70,16 @@ class TestOptimizeComet(GtsamTestCase): actual = self.optimizer.values() self.gtsamAssertEquals(actual.atRot3(KEY), self.expected, tol=1e-6) + def test_lm_simple_printing(self): + """Make sure we are properly terminating LM""" + def hook(_, error): + print(error) + + gtsam_optimize(self.lmoptimizer, self.lmparams, hook) + + actual = self.lmoptimizer.values() + self.gtsamAssertEquals(actual.atRot3(KEY), self.expected, tol=1e-6) + @unittest.skip("Not a test we want run every time, as needs comet.ml account") def test_comet(self): """Test with a comet hook.""" diff --git a/cython/gtsam/utils/logging_optimizer.py b/cython/gtsam/utils/logging_optimizer.py index a48413212..27b9b3a3a 100644 --- a/cython/gtsam/utils/logging_optimizer.py +++ b/cython/gtsam/utils/logging_optimizer.py @@ -46,6 +46,7 @@ def gtsam_optimize(optimizer, def check_convergence(optimizer, current_error, new_error): return (optimizer.iterations() >= params.getMaxIterations()) or ( gtsam.checkConvergence(params.getRelativeErrorTol(), params.getAbsoluteErrorTol(), params.getErrorTol(), - current_error, new_error)) or (optimizer.lambda_() > params.getlambdaUpperBound()) + current_error, new_error)) or ( + type(optimizer).__name__ == "LevenbergMarquardtOptimizer" and optimizer.lambda_() > params.getlambdaUpperBound()) optimize(optimizer, check_convergence, hook) return optimizer.values() From 7b23f570f9758d4bf407436d6c42c88d7f9d5ad7 Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Sat, 11 Jul 2020 14:33:40 -0400 Subject: [PATCH 190/869] correct compiler flag for Windows --- gtsam/CMakeLists.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/gtsam/CMakeLists.txt b/gtsam/CMakeLists.txt index a927ca3a0..16dca6736 100644 --- a/gtsam/CMakeLists.txt +++ b/gtsam/CMakeLists.txt @@ -189,7 +189,7 @@ set(GTSAM_EXPORTED_TARGETS "${GTSAM_EXPORTED_TARGETS}" PARENT_SCOPE) # Make sure that ccolamd compiles even in face of warnings # and suppress all warnings from 3rd party code if Release build if(WIN32) - set_source_files_properties(${3rdparty_srcs} PROPERTIES COMPILE_FLAGS "-w") + set_source_files_properties(${3rdparty_srcs} PROPERTIES COMPILE_FLAGS "/w") else() if("${CMAKE_BUILD_TYPE}" STREQUAL "Release") # Suppress all warnings from 3rd party sources. From 25513379e319132bb0b79c4873500e22ec330945 Mon Sep 17 00:00:00 2001 From: Fan Jiang Date: Sat, 11 Jul 2020 14:37:54 -0400 Subject: [PATCH 191/869] Add unit test --- cython/gtsam/tests/test_NonlinearOptimizer.py | 13 ++++++++++++- 1 file changed, 12 insertions(+), 1 deletion(-) diff --git a/cython/gtsam/tests/test_NonlinearOptimizer.py b/cython/gtsam/tests/test_NonlinearOptimizer.py index efefb218a..985dc30a2 100644 --- a/cython/gtsam/tests/test_NonlinearOptimizer.py +++ b/cython/gtsam/tests/test_NonlinearOptimizer.py @@ -17,7 +17,8 @@ import unittest import gtsam from gtsam import (DoglegOptimizer, DoglegParams, GaussNewtonOptimizer, GaussNewtonParams, LevenbergMarquardtOptimizer, - LevenbergMarquardtParams, NonlinearFactorGraph, Ordering, + LevenbergMarquardtParams, PCGSolverParameters, + DummyPreconditionerParameters, NonlinearFactorGraph, Ordering, Point2, PriorFactorPoint2, Values) from gtsam.utils.test_case import GtsamTestCase @@ -61,6 +62,16 @@ class TestScenario(GtsamTestCase): fg, initial_values, lmParams).optimize() self.assertAlmostEqual(0, fg.error(actual2)) + # Levenberg-Marquardt + lmParams = LevenbergMarquardtParams.CeresDefaults() + lmParams.setLinearSolverType("ITERATIVE") + cgParams = PCGSolverParameters() + cgParams.setPreconditionerParams(DummyPreconditionerParameters()) + lmParams.setIterativeParams(cgParams) + actual2 = LevenbergMarquardtOptimizer( + fg, initial_values, lmParams).optimize() + self.assertAlmostEqual(0, fg.error(actual2)) + # Dogleg dlParams = DoglegParams() dlParams.setOrdering(ordering) From 566467de5ddec015f419d3be6237899955e4017d Mon Sep 17 00:00:00 2001 From: Fan Jiang Date: Sat, 11 Jul 2020 16:50:25 -0400 Subject: [PATCH 192/869] use isinstance --- cython/gtsam/utils/logging_optimizer.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/cython/gtsam/utils/logging_optimizer.py b/cython/gtsam/utils/logging_optimizer.py index 27b9b3a3a..3d9175951 100644 --- a/cython/gtsam/utils/logging_optimizer.py +++ b/cython/gtsam/utils/logging_optimizer.py @@ -47,6 +47,6 @@ def gtsam_optimize(optimizer, return (optimizer.iterations() >= params.getMaxIterations()) or ( gtsam.checkConvergence(params.getRelativeErrorTol(), params.getAbsoluteErrorTol(), params.getErrorTol(), current_error, new_error)) or ( - type(optimizer).__name__ == "LevenbergMarquardtOptimizer" and optimizer.lambda_() > params.getlambdaUpperBound()) + isinstance(optimizer, gtsam.LevenbergMarquardtOptimizer) and optimizer.lambda_() > params.getlambdaUpperBound()) optimize(optimizer, check_convergence, hook) return optimizer.values() From 289ab6271dcfe4c9c956507d6f19c1a15f811942 Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Sat, 11 Jul 2020 21:44:38 -0400 Subject: [PATCH 193/869] added cmake policy for AppleClang compiler identification --- cmake/GtsamBuildTypes.cmake | 5 +++++ 1 file changed, 5 insertions(+) diff --git a/cmake/GtsamBuildTypes.cmake b/cmake/GtsamBuildTypes.cmake index 15a02b6e8..088ba7ad2 100644 --- a/cmake/GtsamBuildTypes.cmake +++ b/cmake/GtsamBuildTypes.cmake @@ -1,3 +1,8 @@ +# Set cmake policy to recognize the AppleClang compiler +# independently from the Clang compiler. +if(POLICY CMP0025) + cmake_policy(SET CMP0025 NEW) +endif() # function: list_append_cache(var [new_values ...]) # Like "list(APPEND ...)" but working for CACHE variables. From 8b9c199d0b079bacf29997c7c496520b471a49b6 Mon Sep 17 00:00:00 2001 From: Fan Jiang Date: Sun, 12 Jul 2020 10:28:23 -0400 Subject: [PATCH 194/869] Move the declaration to cpp --- gtsam/navigation/CombinedImuFactor.h | 2 -- gtsam/navigation/tests/testImuFactorSerialization.cpp | 3 +++ 2 files changed, 3 insertions(+), 2 deletions(-) diff --git a/gtsam/navigation/CombinedImuFactor.h b/gtsam/navigation/CombinedImuFactor.h index f47ce8846..f7ea25371 100644 --- a/gtsam/navigation/CombinedImuFactor.h +++ b/gtsam/navigation/CombinedImuFactor.h @@ -384,5 +384,3 @@ struct traits : public Testable {}; } // namespace gtsam -/// Add Boost serialization export for derived class -BOOST_CLASS_EXPORT_GUID(gtsam::PreintegrationCombinedParams, "gtsam_PreintegrationCombinedParams"); diff --git a/gtsam/navigation/tests/testImuFactorSerialization.cpp b/gtsam/navigation/tests/testImuFactorSerialization.cpp index ed72e18e9..6a9e727f2 100644 --- a/gtsam/navigation/tests/testImuFactorSerialization.cpp +++ b/gtsam/navigation/tests/testImuFactorSerialization.cpp @@ -42,6 +42,9 @@ BOOST_CLASS_EXPORT_GUID(gtsam::noiseModel::Isotropic, BOOST_CLASS_EXPORT_GUID(gtsam::SharedNoiseModel, "gtsam_SharedNoiseModel"); BOOST_CLASS_EXPORT_GUID(gtsam::SharedDiagonal, "gtsam_SharedDiagonal"); +/// Add Boost serialization export for derived class +BOOST_CLASS_EXPORT_GUID(gtsam::PreintegrationCombinedParams, "gtsam_PreintegrationCombinedParams"); + template P getPreintegratedMeasurements() { // Create default parameters with Z-down and above noise paramaters From a500b4147312d0756e73c82c03bb2da46d0a3e79 Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Sun, 12 Jul 2020 11:39:47 -0400 Subject: [PATCH 195/869] Better way of exporting Boost serialization guid --- gtsam/navigation/CombinedImuFactor.cpp | 3 +++ gtsam/navigation/CombinedImuFactor.h | 2 ++ gtsam/navigation/tests/testImuFactorSerialization.cpp | 3 --- 3 files changed, 5 insertions(+), 3 deletions(-) diff --git a/gtsam/navigation/CombinedImuFactor.cpp b/gtsam/navigation/CombinedImuFactor.cpp index 7a8c73013..7f58f7e64 100644 --- a/gtsam/navigation/CombinedImuFactor.cpp +++ b/gtsam/navigation/CombinedImuFactor.cpp @@ -313,3 +313,6 @@ void CombinedImuFactor::Predict(const Pose3& pose_i, const Vector3& vel_i, } /// namespace gtsam +/// Boost serialization export definition for derived class +BOOST_CLASS_EXPORT_IMPLEMENT(gtsam::PreintegrationCombinedParams); + diff --git a/gtsam/navigation/CombinedImuFactor.h b/gtsam/navigation/CombinedImuFactor.h index f7ea25371..8b6dcd3f2 100644 --- a/gtsam/navigation/CombinedImuFactor.h +++ b/gtsam/navigation/CombinedImuFactor.h @@ -384,3 +384,5 @@ struct traits : public Testable {}; } // namespace gtsam +/// Add Boost serialization export key (declaration) for derived class +BOOST_CLASS_EXPORT_KEY(gtsam::PreintegrationCombinedParams); diff --git a/gtsam/navigation/tests/testImuFactorSerialization.cpp b/gtsam/navigation/tests/testImuFactorSerialization.cpp index 6a9e727f2..ed72e18e9 100644 --- a/gtsam/navigation/tests/testImuFactorSerialization.cpp +++ b/gtsam/navigation/tests/testImuFactorSerialization.cpp @@ -42,9 +42,6 @@ BOOST_CLASS_EXPORT_GUID(gtsam::noiseModel::Isotropic, BOOST_CLASS_EXPORT_GUID(gtsam::SharedNoiseModel, "gtsam_SharedNoiseModel"); BOOST_CLASS_EXPORT_GUID(gtsam::SharedDiagonal, "gtsam_SharedDiagonal"); -/// Add Boost serialization export for derived class -BOOST_CLASS_EXPORT_GUID(gtsam::PreintegrationCombinedParams, "gtsam_PreintegrationCombinedParams"); - template P getPreintegratedMeasurements() { // Create default parameters with Z-down and above noise paramaters From 58362579bb6d22ca9b94d4c0a3daf63bda0508a2 Mon Sep 17 00:00:00 2001 From: Frank dellaert Date: Sun, 12 Jul 2020 12:27:10 -0400 Subject: [PATCH 196/869] Resurrecting DiscreteBayesTree tests --- gtsam/discrete/DiscreteBayesNet.h | 3 +- gtsam/discrete/DiscreteBayesTree.cpp | 13 +- gtsam/discrete/DiscreteBayesTree.h | 3 + .../discrete/tests/testDiscreteBayesTree.cpp | 499 +++++++++--------- 4 files changed, 257 insertions(+), 261 deletions(-) diff --git a/gtsam/discrete/DiscreteBayesNet.h b/gtsam/discrete/DiscreteBayesNet.h index dcc336f89..237caf745 100644 --- a/gtsam/discrete/DiscreteBayesNet.h +++ b/gtsam/discrete/DiscreteBayesNet.h @@ -20,13 +20,14 @@ #include #include #include +#include #include #include namespace gtsam { /** A Bayes net made from linear-Discrete densities */ - class GTSAM_EXPORT DiscreteBayesNet: public FactorGraph + class GTSAM_EXPORT DiscreteBayesNet: public BayesNet { public: diff --git a/gtsam/discrete/DiscreteBayesTree.cpp b/gtsam/discrete/DiscreteBayesTree.cpp index bed50a470..8fcc34e25 100644 --- a/gtsam/discrete/DiscreteBayesTree.cpp +++ b/gtsam/discrete/DiscreteBayesTree.cpp @@ -29,10 +29,19 @@ namespace gtsam { template class BayesTreeCliqueBase; template class BayesTree; + /* ************************************************************************* */ + double DiscreteBayesTreeClique::evaluate( + const DiscreteConditional::Values& values) const { + // evaluate all conditionals and multiply + double result = (*conditional_)(values); + for (const auto& child : children) { + result *= child->evaluate(values); + } + return result; + } /* ************************************************************************* */ - bool DiscreteBayesTree::equals(const This& other, double tol) const - { + bool DiscreteBayesTree::equals(const This& other, double tol) const { return Base::equals(other, tol); } diff --git a/gtsam/discrete/DiscreteBayesTree.h b/gtsam/discrete/DiscreteBayesTree.h index 0df6ab476..aa8f4657c 100644 --- a/gtsam/discrete/DiscreteBayesTree.h +++ b/gtsam/discrete/DiscreteBayesTree.h @@ -42,6 +42,9 @@ namespace gtsam { typedef boost::weak_ptr weak_ptr; DiscreteBayesTreeClique() {} DiscreteBayesTreeClique(const boost::shared_ptr& conditional) : Base(conditional) {} + + //** evaluate conditional probability of subtree for given Values */ + double evaluate(const DiscreteConditional::Values & values) const; }; /* ************************************************************************* */ diff --git a/gtsam/discrete/tests/testDiscreteBayesTree.cpp b/gtsam/discrete/tests/testDiscreteBayesTree.cpp index 93126f642..f58fd2b19 100644 --- a/gtsam/discrete/tests/testDiscreteBayesTree.cpp +++ b/gtsam/discrete/tests/testDiscreteBayesTree.cpp @@ -1,261 +1,245 @@ -///* ---------------------------------------------------------------------------- -// -// * GTSAM Copyright 2010, Georgia Tech Research Corporation, -// * Atlanta, Georgia 30332-0415 -// * All Rights Reserved -// * Authors: Frank Dellaert, et al. (see THANKS for the full author list) -// -// * See LICENSE for the license information -// -// * -------------------------------------------------------------------------- */ -// -///* -// * @file testDiscreteBayesTree.cpp -// * @date sept 15, 2012 -// * @author Frank Dellaert -// */ -// -//#include -//#include -//#include -// -//#include -//using namespace boost::assign; -// +/* ---------------------------------------------------------------------------- + +* GTSAM Copyright 2010-2020, Georgia Tech Research Corporation, +* Atlanta, Georgia 30332-0415 +* All Rights Reserved +* Authors: Frank Dellaert, et al. (see THANKS for the full author list) + +* See LICENSE for the license information + +* -------------------------------------------------------------------------- */ + +/* + * @file testDiscreteBayesTree.cpp + * @date sept 15, 2012 + * @author Frank Dellaert + */ + +#include +#include +#include +#include +#include + +#include +using namespace boost::assign; + #include -// -//using namespace std; -//using namespace gtsam; -// -//static bool debug = false; -// -///** -// * Custom clique class to debug shortcuts -// */ -////class Clique: public BayesTreeCliqueBaseOrdered { -//// -////protected: -//// -////public: -//// -//// typedef BayesTreeCliqueBaseOrdered Base; -//// typedef boost::shared_ptr shared_ptr; -//// -//// // Constructors -//// Clique() { -//// } -//// Clique(const DiscreteConditional::shared_ptr& conditional) : -//// Base(conditional) { -//// } -//// Clique( -//// const std::pair& result) : -//// Base(result) { -//// } -//// -//// /// print index signature only -//// void printSignature(const std::string& s = "Clique: ", -//// const KeyFormatter& indexFormatter = DefaultKeyFormatter) const { -//// ((IndexConditionalOrdered::shared_ptr) conditional_)->print(s, indexFormatter); -//// } -//// -//// /// evaluate value of sub-tree -//// double evaluate(const DiscreteConditional::Values & values) { -//// double result = (*(this->conditional_))(values); -//// // evaluate all children and multiply into result -//// for(boost::shared_ptr c: children_) -//// result *= c->evaluate(values); -//// return result; -//// } -//// -////}; -// -////typedef BayesTreeOrdered DiscreteBayesTree; -//// -/////* ************************************************************************* */ -////double evaluate(const DiscreteBayesTree& tree, -//// const DiscreteConditional::Values & values) { -//// return tree.root()->evaluate(values); -////} -// -///* ************************************************************************* */ -// -//TEST_UNSAFE( DiscreteBayesTree, thinTree ) { -// -// const int nrNodes = 15; -// const size_t nrStates = 2; -// -// // define variables -// vector key; -// for (int i = 0; i < nrNodes; i++) { -// DiscreteKey key_i(i, nrStates); -// key.push_back(key_i); -// } -// -// // create a thin-tree Bayesnet, a la Jean-Guillaume -// DiscreteBayesNet bayesNet; -// bayesNet.add(key[14] % "1/3"); -// -// bayesNet.add(key[13] | key[14] = "1/3 3/1"); -// bayesNet.add(key[12] | key[14] = "3/1 3/1"); -// -// bayesNet.add((key[11] | key[13], key[14]) = "1/4 2/3 3/2 4/1"); -// bayesNet.add((key[10] | key[13], key[14]) = "1/4 3/2 2/3 4/1"); -// bayesNet.add((key[9] | key[12], key[14]) = "4/1 2/3 F 1/4"); -// bayesNet.add((key[8] | key[12], key[14]) = "T 1/4 3/2 4/1"); -// -// bayesNet.add((key[7] | key[11], key[13]) = "1/4 2/3 3/2 4/1"); -// bayesNet.add((key[6] | key[11], key[13]) = "1/4 3/2 2/3 4/1"); -// bayesNet.add((key[5] | key[10], key[13]) = "4/1 2/3 3/2 1/4"); -// bayesNet.add((key[4] | key[10], key[13]) = "2/3 1/4 3/2 4/1"); -// -// bayesNet.add((key[3] | key[9], key[12]) = "1/4 2/3 3/2 4/1"); -// bayesNet.add((key[2] | key[9], key[12]) = "1/4 8/2 2/3 4/1"); -// bayesNet.add((key[1] | key[8], key[12]) = "4/1 2/3 3/2 1/4"); -// bayesNet.add((key[0] | key[8], key[12]) = "2/3 1/4 3/2 4/1"); -// -//// if (debug) { -//// GTSAM_PRINT(bayesNet); -//// bayesNet.saveGraph("/tmp/discreteBayesNet.dot"); -//// } -// -// // create a BayesTree out of a Bayes net -// DiscreteBayesTree bayesTree(bayesNet); -// if (debug) { -// GTSAM_PRINT(bayesTree); -// bayesTree.saveGraph("/tmp/discreteBayesTree.dot"); -// } -// -// // Check whether BN and BT give the same answer on all configurations -// // Also calculate all some marginals -// Vector marginals = zero(15); -// double joint_12_14 = 0, joint_9_12_14 = 0, joint_8_12_14 = 0, joint_8_12 = 0, -// joint82 = 0, joint12 = 0, joint24 = 0, joint45 = 0, joint46 = 0, -// joint_4_11 = 0; -// vector allPosbValues = cartesianProduct( -// key[0] & key[1] & key[2] & key[3] & key[4] & key[5] & key[6] & key[7] -// & key[8] & key[9] & key[10] & key[11] & key[12] & key[13] & key[14]); -// for (size_t i = 0; i < allPosbValues.size(); ++i) { -// DiscreteFactor::Values x = allPosbValues[i]; -// double expected = evaluate(bayesNet, x); -// double actual = evaluate(bayesTree, x); -// DOUBLES_EQUAL(expected, actual, 1e-9); -// // collect marginals -// for (size_t i = 0; i < 15; i++) -// if (x[i]) -// marginals[i] += actual; -// // calculate shortcut 8 and 0 -// if (x[12] && x[14]) -// joint_12_14 += actual; -// if (x[9] && x[12] & x[14]) -// joint_9_12_14 += actual; -// if (x[8] && x[12] & x[14]) -// joint_8_12_14 += actual; -// if (x[8] && x[12]) -// joint_8_12 += actual; -// if (x[8] && x[2]) -// joint82 += actual; -// if (x[1] && x[2]) -// joint12 += actual; -// if (x[2] && x[4]) -// joint24 += actual; -// if (x[4] && x[5]) -// joint45 += actual; -// if (x[4] && x[6]) -// joint46 += actual; -// if (x[4] && x[11]) -// joint_4_11 += actual; -// } -// DiscreteFactor::Values all1 = allPosbValues.back(); -// -// Clique::shared_ptr R = bayesTree.root(); -// -// // check separator marginal P(S0) -// Clique::shared_ptr c = bayesTree[0]; -// DiscreteFactorGraph separatorMarginal0 = c->separatorMarginal(R, -// EliminateDiscrete); -// EXPECT_DOUBLES_EQUAL(joint_8_12, separatorMarginal0(all1), 1e-9); -// -// // check separator marginal P(S9), should be P(14) -// c = bayesTree[9]; -// DiscreteFactorGraph separatorMarginal9 = c->separatorMarginal(R, -// EliminateDiscrete); -// EXPECT_DOUBLES_EQUAL(marginals[14], separatorMarginal9(all1), 1e-9); -// -// // check separator marginal of root, should be empty -// c = bayesTree[11]; -// DiscreteFactorGraph separatorMarginal11 = c->separatorMarginal(R, -// EliminateDiscrete); -// EXPECT_LONGS_EQUAL(0, separatorMarginal11.size()); -// -// // check shortcut P(S9||R) to root -// c = bayesTree[9]; -// DiscreteBayesNet shortcut = c->shortcut(R, EliminateDiscrete); -// EXPECT_LONGS_EQUAL(0, shortcut.size()); -// -// // check shortcut P(S8||R) to root -// c = bayesTree[8]; -// shortcut = c->shortcut(R, EliminateDiscrete); -// EXPECT_DOUBLES_EQUAL(joint_12_14/marginals[14], evaluate(shortcut,all1), -// 1e-9); -// -// // check shortcut P(S2||R) to root -// c = bayesTree[2]; -// shortcut = c->shortcut(R, EliminateDiscrete); -// EXPECT_DOUBLES_EQUAL(joint_9_12_14/marginals[14], evaluate(shortcut,all1), -// 1e-9); -// -// // check shortcut P(S0||R) to root -// c = bayesTree[0]; -// shortcut = c->shortcut(R, EliminateDiscrete); -// EXPECT_DOUBLES_EQUAL(joint_8_12_14/marginals[14], evaluate(shortcut,all1), -// 1e-9); -// -// // calculate all shortcuts to root -// DiscreteBayesTree::Nodes cliques = bayesTree.nodes(); -// for(Clique::shared_ptr c: cliques) { -// DiscreteBayesNet shortcut = c->shortcut(R, EliminateDiscrete); -// if (debug) { -// c->printSignature(); -// shortcut.print("shortcut:"); -// } -// } -// -// // Check all marginals -// DiscreteFactor::shared_ptr marginalFactor; -// for (size_t i = 0; i < 15; i++) { -// marginalFactor = bayesTree.marginalFactor(i, EliminateDiscrete); -// double actual = (*marginalFactor)(all1); -// EXPECT_DOUBLES_EQUAL(marginals[i], actual, 1e-9); -// } -// -// DiscreteBayesNet::shared_ptr actualJoint; -// -// // Check joint P(8,2) TODO: not disjoint ! -//// actualJoint = bayesTree.jointBayesNet(8, 2, EliminateDiscrete); -//// EXPECT_DOUBLES_EQUAL(joint82, evaluate(*actualJoint,all1), 1e-9); -// -// // Check joint P(1,2) TODO: not disjoint ! -//// actualJoint = bayesTree.jointBayesNet(1, 2, EliminateDiscrete); -//// EXPECT_DOUBLES_EQUAL(joint12, evaluate(*actualJoint,all1), 1e-9); -// -// // Check joint P(2,4) -// actualJoint = bayesTree.jointBayesNet(2, 4, EliminateDiscrete); -// EXPECT_DOUBLES_EQUAL(joint24, evaluate(*actualJoint,all1), 1e-9); -// -// // Check joint P(4,5) TODO: not disjoint ! -//// actualJoint = bayesTree.jointBayesNet(4, 5, EliminateDiscrete); -//// EXPECT_DOUBLES_EQUAL(joint46, evaluate(*actualJoint,all1), 1e-9); -// -// // Check joint P(4,6) TODO: not disjoint ! -//// actualJoint = bayesTree.jointBayesNet(4, 6, EliminateDiscrete); -//// EXPECT_DOUBLES_EQUAL(joint46, evaluate(*actualJoint,all1), 1e-9); -// -// // Check joint P(4,11) -// actualJoint = bayesTree.jointBayesNet(4, 11, EliminateDiscrete); -// EXPECT_DOUBLES_EQUAL(joint_4_11, evaluate(*actualJoint,all1), 1e-9); -// -//} + +#include + +using namespace std; +using namespace gtsam; + +static bool debug = false; + +// /** +// * Custom clique class to debug shortcuts +// */ +// struct Clique : public BayesTreeCliqueBase { +// typedef BayesTreeCliqueBase Base; +// typedef boost::shared_ptr shared_ptr; + +// // Constructors +// Clique() {} +// explicit Clique(const DiscreteConditional::shared_ptr& conditional) +// : Base(conditional) {} +// Clique(const std::pair& +// result) +// : Base(result) {} + +// /// print index signature only +// void printSignature( +// const std::string& s = "Clique: ", +// const KeyFormatter& indexFormatter = DefaultKeyFormatter) const { +// ((IndexConditionalOrdered::shared_ptr)conditional_) +// ->print(s, indexFormatter); +// } + +// /// evaluate value of sub-tree +// double evaluate(const DiscreteConditional::Values& values) { +// double result = (*(this->conditional_))(values); +// // evaluate all children and multiply into result +// for (boost::shared_ptr c : children_) result *= +// c->evaluate(values); return result; +// } +// }; + +// typedef BayesTreeOrdered DiscreteBayesTree; + +/* ************************************************************************* */ + +TEST_UNSAFE(DiscreteBayesTree, thinTree) { + const int nrNodes = 15; + const size_t nrStates = 2; + + // define variables + vector key; + for (int i = 0; i < nrNodes; i++) { + DiscreteKey key_i(i, nrStates); + key.push_back(key_i); + } + + // create a thin-tree Bayesnet, a la Jean-Guillaume + DiscreteBayesNet bayesNet; + bayesNet.add(key[14] % "1/3"); + + bayesNet.add(key[13] | key[14] = "1/3 3/1"); + bayesNet.add(key[12] | key[14] = "3/1 3/1"); + + bayesNet.add((key[11] | key[13], key[14]) = "1/4 2/3 3/2 4/1"); + bayesNet.add((key[10] | key[13], key[14]) = "1/4 3/2 2/3 4/1"); + bayesNet.add((key[9] | key[12], key[14]) = "4/1 2/3 F 1/4"); + bayesNet.add((key[8] | key[12], key[14]) = "T 1/4 3/2 4/1"); + + bayesNet.add((key[7] | key[11], key[13]) = "1/4 2/3 3/2 4/1"); + bayesNet.add((key[6] | key[11], key[13]) = "1/4 3/2 2/3 4/1"); + bayesNet.add((key[5] | key[10], key[13]) = "4/1 2/3 3/2 1/4"); + bayesNet.add((key[4] | key[10], key[13]) = "2/3 1/4 3/2 4/1"); + + bayesNet.add((key[3] | key[9], key[12]) = "1/4 2/3 3/2 4/1"); + bayesNet.add((key[2] | key[9], key[12]) = "1/4 8/2 2/3 4/1"); + bayesNet.add((key[1] | key[8], key[12]) = "4/1 2/3 3/2 1/4"); + bayesNet.add((key[0] | key[8], key[12]) = "2/3 1/4 3/2 4/1"); + + if (debug) { + GTSAM_PRINT(bayesNet); + bayesNet.saveGraph("/tmp/discreteBayesNet.dot"); + } + + // create a BayesTree out of a Bayes net + auto bayesTree = DiscreteFactorGraph(bayesNet).eliminateMultifrontal(); + if (debug) { + GTSAM_PRINT(*bayesTree); + bayesTree->saveGraph("/tmp/discreteBayesTree.dot"); + } + + auto R = bayesTree->roots().front(); + + // Check whether BN and BT give the same answer on all configurations + vector allPosbValues = cartesianProduct( + key[0] & key[1] & key[2] & key[3] & key[4] & key[5] & key[6] & key[7] & + key[8] & key[9] & key[10] & key[11] & key[12] & key[13] & key[14]); + for (size_t i = 0; i < allPosbValues.size(); ++i) { + DiscreteFactor::Values x = allPosbValues[i]; + double expected = bayesNet.evaluate(x); + double actual = R->evaluate(x); + DOUBLES_EQUAL(expected, actual, 1e-9); + } + + // Calculate all some marginals + Vector marginals = zero(15); + double joint_12_14 = 0, joint_9_12_14 = 0, joint_8_12_14 = 0, joint_8_12 = 0, + joint82 = 0, joint12 = 0, joint24 = 0, joint45 = 0, joint46 = 0, + joint_4_11 = 0; + for (size_t i = 0; i < allPosbValues.size(); ++i) { + DiscreteFactor::Values x = allPosbValues[i]; + double px = R->evaluate(x); + for (size_t i = 0; i < 15; i++) + if (x[i]) marginals[i] += px; + // calculate shortcut 8 and 0 + if (x[12] && x[14]) joint_12_14 += px; + if (x[9] && x[12] & x[14]) joint_9_12_14 += px; + if (x[8] && x[12] & x[14]) joint_8_12_14 += px; + if (x[8] && x[12]) joint_8_12 += px; + if (x[8] && x[2]) joint82 += px; + if (x[1] && x[2]) joint12 += px; + if (x[2] && x[4]) joint24 += px; + if (x[4] && x[5]) joint45 += px; + if (x[4] && x[6]) joint46 += px; + if (x[4] && x[11]) joint_4_11 += px; + } + DiscreteFactor::Values all1 = allPosbValues.back(); + + + // check separator marginal P(S0) + auto c = (*bayesTree)[0]; + DiscreteFactorGraph separatorMarginal0 = + c->separatorMarginal(EliminateDiscrete); + EXPECT_DOUBLES_EQUAL(joint_8_12, separatorMarginal0(all1), 1e-9); + + // // check separator marginal P(S9), should be P(14) + // c = (*bayesTree)[9]; + // DiscreteFactorGraph separatorMarginal9 = + // c->separatorMarginal(EliminateDiscrete); + // EXPECT_DOUBLES_EQUAL(marginals[14], separatorMarginal9(all1), 1e-9); + + // // check separator marginal of root, should be empty + // c = (*bayesTree)[11]; + // DiscreteFactorGraph separatorMarginal11 = + // c->separatorMarginal(EliminateDiscrete); + // EXPECT_LONGS_EQUAL(0, separatorMarginal11.size()); + + // // check shortcut P(S9||R) to root + // c = (*bayesTree)[9]; + // DiscreteBayesNet shortcut = c->shortcut(R, EliminateDiscrete); + // EXPECT_LONGS_EQUAL(0, shortcut.size()); + + // // check shortcut P(S8||R) to root + // c = (*bayesTree)[8]; + // shortcut = c->shortcut(R, EliminateDiscrete); + // EXPECT_DOUBLES_EQUAL(joint_12_14 / marginals[14], evaluate(shortcut, all1), + // 1e-9); + + // // check shortcut P(S2||R) to root + // c = (*bayesTree)[2]; + // shortcut = c->shortcut(R, EliminateDiscrete); + // EXPECT_DOUBLES_EQUAL(joint_9_12_14 / marginals[14], evaluate(shortcut, + // all1), + // 1e-9); + + // // check shortcut P(S0||R) to root + // c = (*bayesTree)[0]; + // shortcut = c->shortcut(R, EliminateDiscrete); + // EXPECT_DOUBLES_EQUAL(joint_8_12_14 / marginals[14], evaluate(shortcut, + // all1), + // 1e-9); + + // // calculate all shortcuts to root + // DiscreteBayesTree::Nodes cliques = bayesTree->nodes(); + // for (auto c : cliques) { + // DiscreteBayesNet shortcut = c->shortcut(R, EliminateDiscrete); + // if (debug) { + // c->printSignature(); + // shortcut.print("shortcut:"); + // } + // } + + // // Check all marginals + // DiscreteFactor::shared_ptr marginalFactor; + // for (size_t i = 0; i < 15; i++) { + // marginalFactor = bayesTree->marginalFactor(i, EliminateDiscrete); + // double actual = (*marginalFactor)(all1); + // EXPECT_DOUBLES_EQUAL(marginals[i], actual, 1e-9); + // } + + // DiscreteBayesNet::shared_ptr actualJoint; + + // Check joint P(8,2) TODO: not disjoint ! + // actualJoint = bayesTree->jointBayesNet(8, 2, EliminateDiscrete); + // EXPECT_DOUBLES_EQUAL(joint82, evaluate(*actualJoint,all1), 1e-9); + + // Check joint P(1,2) TODO: not disjoint ! + // actualJoint = bayesTree->jointBayesNet(1, 2, EliminateDiscrete); + // EXPECT_DOUBLES_EQUAL(joint12, evaluate(*actualJoint,all1), 1e-9); + + // Check joint P(2,4) + // actualJoint = bayesTree->jointBayesNet(2, 4, EliminateDiscrete); + // EXPECT_DOUBLES_EQUAL(joint24, evaluate(*actualJoint, all1), 1e-9); + + // Check joint P(4,5) TODO: not disjoint ! + // actualJoint = bayesTree->jointBayesNet(4, 5, EliminateDiscrete); + // EXPECT_DOUBLES_EQUAL(joint46, evaluate(*actualJoint,all1), 1e-9); + + // Check joint P(4,6) TODO: not disjoint ! + // actualJoint = bayesTree->jointBayesNet(4, 6, EliminateDiscrete); + // EXPECT_DOUBLES_EQUAL(joint46, evaluate(*actualJoint,all1), 1e-9); + + // Check joint P(4,11) + // actualJoint = bayesTree->jointBayesNet(4, 11, EliminateDiscrete); + // EXPECT_DOUBLES_EQUAL(joint_4_11, evaluate(*actualJoint, all1), 1e-9); +} /* ************************************************************************* */ int main() { @@ -263,4 +247,3 @@ int main() { return TestRegistry::runAllTests(tr); } /* ************************************************************************* */ - From eb1a2b8fb3a6b3656da0acd1efc982f5fe6cc3c3 Mon Sep 17 00:00:00 2001 From: yetongumich Date: Sun, 12 Jul 2020 14:31:29 -0400 Subject: [PATCH 197/869] modified test --- tests/testNonlinearOptimizer.cpp | 7 ++++--- 1 file changed, 4 insertions(+), 3 deletions(-) diff --git a/tests/testNonlinearOptimizer.cpp b/tests/testNonlinearOptimizer.cpp index 5d4c3f844..a549dc726 100644 --- a/tests/testNonlinearOptimizer.cpp +++ b/tests/testNonlinearOptimizer.cpp @@ -459,11 +459,12 @@ TEST(NonlinearOptimizer, RobustMeanCalculation) { init.insert(0, 100.0); expected.insert(0, 3.33333333); - LevenbergMarquardtParams params; + DoglegParams params_dl; + params_dl.setRelativeErrorTol(1e-10); auto gn_result = GaussNewtonOptimizer(fg, init).optimize(); - auto lm_result = LevenbergMarquardtOptimizer(fg, init, params).optimize(); - auto dl_result = DoglegOptimizer(fg, init).optimize(); + auto lm_result = LevenbergMarquardtOptimizer(fg, init).optimize(); + auto dl_result = DoglegOptimizer(fg, init, params_dl).optimize(); EXPECT(assert_equal(expected, gn_result, tol)); EXPECT(assert_equal(expected, lm_result, tol)); From 3f4bf163e73a5f04cb8291e40fc1892ab80bb83e Mon Sep 17 00:00:00 2001 From: Frank dellaert Date: Sun, 12 Jul 2020 14:59:17 -0400 Subject: [PATCH 198/869] Checked in pdf for easy reference --- gtsam/discrete/tests/testDiscreteBayesTree.pdf | Bin 0 -> 10622 bytes 1 file changed, 0 insertions(+), 0 deletions(-) create mode 100644 gtsam/discrete/tests/testDiscreteBayesTree.pdf diff --git a/gtsam/discrete/tests/testDiscreteBayesTree.pdf b/gtsam/discrete/tests/testDiscreteBayesTree.pdf new file mode 100644 index 0000000000000000000000000000000000000000..e8167d455477f97aadb2101d26120a6c145891f5 GIT binary patch literal 10622 zcma)i2RK~a^S>5?=p|~bPPEvu87l@l5hq-FA~Taz0X!;D zXB&5006&7Hg#!Qpc;xIH-Jx*A(-Gnhy$iL3SwV5c#c|x+;ZTSZ&i#ym6xG-nfg2&) z-^s*TB<~T)Dken$La#-jq59a?RRcmTBJ!>$$b6K!d|;-Pw=p{v+e6>N@FAQ%os>(Q zfqj%}cROMy(b81iEU78^rDfB%`o=TH61qzh+iwJxu-#)j@8bv2^d%3uNhi(p3b-6+ zCPpTBv|k#nq)v=g58W;`G8yd*a7*kPO@rfd6~<}dHtf8siRb}(rJ>!5%~!9Yc_D0^ zwaiD@AJCzTKbJZ2X|wA4X^rV8&L=Wape4sriH;|NALi@}9r87N)yF2&dHRY7?(N<# zc{AsyKi80*JZ4&Uaj~<9({y{3d-5CH_w@Vn=HBQ)<0}<0_ZnFmk8$I*w~k`%cwo~Z zGo2FkHACiGURroYJ$)qtm}4t;$y#qZcy*QPG>xD6y_4-&jVz=U`xZgQ*%;VLivU&`1}PK||UGDx>Q9u{jm6CK^L<*ef=hu#&~d?MMFK0N61HO}zUJ&=~I zQ(c27RxUr^!&h|0#L@BZ9bSE#;C(jPl;qa1&OH9OoWFy~TICU0^n>N0_8!tDb(^^L zQ6<`>wqX%AqIE!!!LCCYu$Rb&C@!u|JFlUyBY<_)m~dE`QT0%8~vExZX+ zAFzh4`VJ?)w<`oW7Mt@pqw+*QdO}0Is1w1+QhG&*zoQ(QF&duh}O4`A5 ziXXedCD!QVCdr})CAW2IhEbzb1s}PZ8E>wvc60;DQ=ZAmwcTvG$?COS#J1uQ3@563b2~v#|h8Mf<{^7lySTh6}mgo7&Asw zs$HAGxO`q7B{vzGdlEi^7uls`En=nPtHkrkQrLkeXnNT^3Xy4Z4}AwbsvdfBalZYSCHT-%@((y{Wv=^{RXZJEnRT-GHFC zFMCL-xfmV0*>V;h_B84436?Jh>hv!w5GO7$3~TM#T=!^GYdW+F%1=a04rkZrd1+OjkJTJz=V{Ag-9U zbuKC(D@nkP#MCPx`jEme7{;V;Z|KTTt&#h}B;iQW)^&W$GuMu$a!rB5r_bNDD(FS> zeqga(y~`HCuJos@(mYjQ|O03%skp*OOSb`dMX?iL1lGln~KStlaEifwy{h@mK{Ayf{@b_qBR#0a1=YcrdLu@KKix(-Z>@-tJTOci==dV7S zGgCyl)$nx_;qAplsAw#@$x^8ndsf=`2%%}tD#zjKDeH?<8(^nl0l1{1jF*_hQk|0l z)MY*(W*(N3+h5#r4FetDX$H=ajozs_CF^?jKnnZzr$USl)}|7g!IWDQ!Xt0URVl?v z{LE9~4_;S8Pp!YG9~yZom%nF!t$Of1Y93zT)j(=5!p(i6h$-Cc+OrpKJD-pb6)*TxgamkH{R26h_y?62XO`SK0`}BFIfCQa!+#Qz{sV?y6xJ?HsQsao% zj!!I$p3rp?Tc6SZ4ylxT8^k1)<#uo5IXs%JlqIiZj*SBtuu3uJF6tOZzZ2{os+~UE zTi=t&oqBd12kLC~GglzKA+roJwIH8}*LlMJ+e)Z*1g<9D`q+#~~MhFrRz|SuX z-~;jjOs=?P5TYR1-2lkc`Xi6Z!(kpSe-rP=99Ps|>(fTe42L+oxgh7V^!`Ow1h~UJ zpubu&2(G(OPdiJfmb^5Q_;dAIP&b$d+!E>rKx$I!Zz~f*wEvafg@23nU+EpGsvo}t zKmZ|LKB0f)`%OV_KW*K2pM;O+90!~d1niQy71LNuM);g$3?uRzg7YN%w6e`P$PK6M z*`LhfNE^r{X<6O1BGK#%qvpUUCtTR}hdTGj8vs{Ylu7^d`lV{FQp$;Fnk-a}Ptz0AV|(XcI|yT1{=~&Zd6bo52_@i%jbQV&UM+Ha~VdEc=|28@(@y?G_-3UQh|g1 zBCbePE;kqqNqBg-czHl>G}4OlLyu)1YRICL6bq&i`m^VJOW2(W*!M6?;yIkXq{KPx zA29`~J+tEb@D18tO1%uv>sx&AB6g5Pn;bvO#1z_Fp)vr#9Wxetap8IKm_~qERnHxF z-{k@1mB3OBo3H-?M?s5@khR$}C;Se+n2gRDqE$=HgLBB=`l( zeutzc*r&eCf0<`&e}cz7&=dNirw9!5?U3pE(yD;d2+xxGgAS#D6W z;@@v-Oi-vLLSIcV#S5|!<>Z3#gUCOm*Ju9;-O%jWn)hSKF}ho2vQzbAzh`p`!XYy z(d^Yqe5rN?PQEmrQgDJLWj`?1TqXNS*@_5rI94nCTq;_OpXLQl7#4G2CM1lDG03eS;$(Jl?PSu}Qci zi^zHONH12}fc@-73U7_N#%D-_xk)EsOmewW?~Y`50!Eh2bprbkUDTG9J8DVubNMWF zF)u09^7Voh)3P6b>-9TgOsarr9n`C`bo)S~HiUEoFvr*$SxiYU?c0_@Mp~3LOk>g~ zpK6(?*lW6s1(A`pyp_8l&0NlU<}My2^L1$Io4aAVWFrOtdUBJW)ecjgM_Gh{m($W& z_o&shkK*^P=MS0EQ*7w*`FC;I`Q+&*mnatcDK5`4PHJdkA_dd?Uu;a0`&E13*FBQeCdOwQ*1vV!8}i53D_fN}D?Ge8Fj1FQ(D$-&qQnsgHnfR}Hb1+PKS_I_ERB zb*~67116)k;BBCsW$n=y%Nzw9)^EX3pS8>$uL4Jvxs(d|I$m%2Uerz8DT()u*$r{D z&t3r2RhBuaWhl4@H~7Nwg55@5-zS#fp37VDaAV0@$D|#GRM70Td)S26&i8Z}Q-(1s zojyuo#4A9(fytNkq}x`VJsD&)Vj>LY+K$){0%LL1hU}AgSl83(OyNkx+m%x(k%ClR z%s6h7yU~qaOJwM=p~n>K$h?7$&5NnoVIdFJ4UCOxRPX5BniBFoeZI+h`KHG5urQ`e z*Qw>{_-0X6%&R2G7P<{)%y9ey*Q+Xnuh&0*s@^P(;;7ipoQjpF5jI#S? zR1B?=`ZiATHQcl}J)R;G2Iq>q0fE%>2J{D=TB$LNN_*Lt*q5vss4#gi^ zGP6|Pj%hEXz~qeTdCi+Xuk$!@73#Ji9Q2?`7R9$BZFQo-mfVeCz$s}54VB9~roGDFS$m<7J5XKdqO2}qTGfUSg6 z;agHCg`GtQeVx}Q>Mu~4k6NEwFj~?nE|VB+2da+NJ9~Yh6BIk_`y?w6CrHgou1{`! zUL60LiA&w-VOjqD^1V@+ug4p)8IiBMi|)yPN70I6{+u<^#cvUn-y%T&jdCyej6`hz z_64RmY5~fHG4}hYd)+>xH79dSS)Qz6nwHugM(r=l4JsBW9L>?IEha}#&-wNTqo$sgMW+LK%f?xHmSZVdQdrsz(qe*F&pJ@%ab(%FsYbUZ%HzOiOu(-J+ zmUQ&w-1WU>W2uePF>3c|kyC*WeeuGUc(%3tC0x zD6f>HJKGRJxAo|{4EYqs4b3g@^E!ij1`g!ukUie02wiBJx0@WhNULs|H?CltXdAd~ za`3I&=CY@9ojSF~i7`veI0X}7@{q&QypNmrz|6tdRpaihfr6=(YxIM#lytZb=oreg z8!@*-AOqvO(LQprH&oR|(P!2p7%c2v=vizU?pxBEOGvw4dmCo_j{9OJL4@j}MYro7Ow8Zve63*b-G^HJfCt6{#UaKg z_vqbZz;nb0m}q<-yH`gKLxifdEZ^Ajr!iyq^dwn1mK%FIr;y^C>1QN|wR0{S=%qk()0_Q_nguVMAd)WnNpc{r zRyM9@Zgt&f^qqxGPF!&o=m&|Y(j)?i=nUG69Gol`%WNzbX>9kn_&BKt*JKGFhkn5r z)W^q-drQ34mb?$SPk)9JL)J1%7*a$bTzKE?r409RGy3r85N=Z_$FTqK`xdPA_<6qr zuagJHLHao4e#sa)wB*DDCRDT6p*3^P_ff?Gio;-FGmtG9Wd`4A2z4JqJ8v4ezayY1 z={^H9)3 zHX(DNsDvHgFZ3U^g+=F2vN@J*ru4`A%+8E>k#@W)({=P%dxczhdwdZKXop9bHmT8rbD>Tzm)#lzAxAH>mQcw$`3a!%0 z9;YPsdoMdJ%PhlQ2b=Vkm|q5q^_iOUls~jCg&T4|OYc-oPPJmLP@8%%MSp61TDgZi z6f5um-{b5{DP_`V<^i?7Y?pb~mqyixYF*D+-*wYh&~Y77bZ!DUw=IdvNX<1Nr`Xd# zEZpm<+%_SMv(A+T`2|cy{Vcm{$tl^R_VeBz8A^q5eLIE9*o&C7Pov+)6@l8{(O7o* zv^VBrW2HR+4pCHm(O8PLlYT1~-hX7Ngvt&(7g3^@V>f=mWN5_x#0Tyq70Pv>*9^f; zG-8>A_$oJR!f^2vHnFvQi^i7AovIfwjE2U@%YqehxhP(3IId$0V8+dYP@@a>7A;(| z`RDI;(o@Wijay3tv@m4Ix}X7xOU0M;4lv1&YTo_qslj7=uld2z2df<7v4e%UrMvGliZ|xhoi-& ziG(=Xg{$z5-jhkn3u883>?({7h4mLUpjl|Ue?1J7ywDK2ky<+r(U=%JB-$H21BRCn z$N&y0vcUbXQ^N*{+aPKvHkMdC`EgGzyY$pbiiz_}NWWRHmmfwstd{FePY->0tsNL< zyIFYr{Eqhevbl+o4FUFH&t!V>;UQyOtkGhdlAq67yv#XasAo7jnBwm9nHhV&_@V-5 zxQVSQK$r<*ZJ3Edg4JP7nsqqh@K9l?mYcn`M7V%Hbzj3;9bcdx#H}5VRq=9rHT;m~ zXs9PEYw;F{z~UP)poxw!1hW+YYSzF`p$0@vA>82$1^IBVw&fA^-c5zFW+w&pO?FXV>m>ZnU zT_@w(kE)6E=97b;#V0jeUYE!B$3F4+d@o=>!d%2P-g^;T{2Xf~xnEBpdbY1Peo2vI zr|kO8IrawBH~P+KahIl^IG@lkayz1hSIPN$&BlmTx!5I=Rc{qCOJ7rO?C3ewa!Rx> z)zMlvwbx5vnOFN;ak(ruMFr|NjA zIu{jQCv)L>yWMd_)k{xm#)9i&g&M=z9DhxywUu*Y{4-7^Q%qtRYsnqOwI$0^8sAf` z_mM^3X*K|Xj=F^ zoDjAkQMP;2@uETCK~=PblzZ+E@ur0&(p$5;1#$s|OA z-z$7c)II?kc<5BBR_dZFIo_J8&W!uN_$BF;6Qy2r~YxZcDS4WGQQ zoC~Zu2nnWrtH=Z(;Uw6b=Qfm`eUPGUqOS1dMr7<{=`k0Rm30Sql4s& z)8hsb>Vc_qFp~|EdtsG>vN4;r;}h02bBwmHy=yxr3g;FkdgeMN6w9A>USk4IoCoF& zPNJE`+ZXQ?7|JI#KpWT}r5zY4x37MifRuOO?lT?Y^mZD}zP#l-mZoiFuG+;M{<&PO z&O}^UT-B8GxNm=nyH-1kMg8eI88%KagK3W5OH!O*m6qE;XRLm-ib4$yG=?x zJa)DgXIB4)hVfavdSHO%qBhZ(Z4X;NRg)AystgjjcA9#Uh;DUP zlx=YZ4cavB-2g`#9GW0QA^@Es#uNkHjVXq3NA0NoNaHw809yP8@qK16PXkkY19QTm zhYc3G|I`#Qb~4s1v7%ryYeII5Wy05mG0A6>9GZpFOlAopW@HHz`ASiK;!N!O;Y|L) z;!G?1WJjlSf;)!jIaM)_iea5|)Y-=oE0i&kbQ^dR z6Nj5*hUnjTA5)Gj?GJ@;MFvV3I*cAxkvr9*R&p^^%FY{72MS7J$sS<37H8M!X&5^M zl}Q;Yk8ugvti5CwJmG3sh)GpW>VJHRLa)1w`zJ7fJe2+k4DbsA1%4gOgOJDT|2n@0 z{dEriUkBKTBk|w(w8`**^J4%Z%4ZREP}e4eaqT-xXWo>l=mBe$Kg#1_=0eFhv6CZO z^Ga184RLDy%wXXb=hDF^%(^U>9%Rkq;=rHasK<9@5?g;gSKcc6K}I!^4>S#9J5$I zW*~!!$a>RGa6SE&d16Q_{qzXxtY{bevB+l=*&H470 z%|%Lhy|?;;!p-<)Le^|N@vUBin?)o0xEk2uqFn+yDtAOmqxfZEyEB7hsjFjrl)-Jwo;0HGfpkPU@j4dmJo-UI~$kci3O5fmhd z^veT(;5JC!AH#WAxL=_~ItYvg`Rkjb`@$#aV2S{5dCCP;(NluZ1ii&fi95$wbQ_yHR^!Li!w!?1n|Hs0k?r#dkVe7s+OHtnYN6 z;fISji)bju;f!tzrN1?vJIwUNqjqtFJS zll{lMzuXOBZIICKX_2tyKb`O&hQDiPZ4E`@h6n`E2ngUo+#r*`p@5*jU_cz?+beq^ zph+GO0)|Bl{SRCI3dMh0A{gm5KcLM2WlNJdRp)lVjo{;q*1lB>jGjBvuL{yR&vFaI zP+C}I(@@~u4AngJxjJiTR{L`{Vw|vV%5;91r!B+yPg+hNsVEyy5l8Wz0@BEbK3=S> zIoTvW=G-acN?jJOVS9(aXhW3TPi>q9iaB6Hk!<88J_oieoeR*Yx226_TH{bY8KR0a zraZPENl(SL3N95RpZ&UNSSHamnRI=6T2P*eIzGvYvmBcwT#X$s)6Gz$`JtgNVQ!^F zi24f|leK~|rK(qOf-Z5$a5MP9a!61Z1en88}5mX`Wa62UOj7)T0MU^f%>QGK z-&ixEWDMzI2uJ-#Z1@2$|Ann1<@=}WBC&P1t5qx8Ss}yKRebx6o_ipn_P;qV`0pbi zR$}F0iKt0qvxL~eVE_;}NPrs%V6%01cX7MJgQyHZP;KB47h5|^H*Of*hW$svkwH|f zx!b{8Sfk5`ZPx@#2lYt;o5X|OE@T(>KEC~2( zsrTVfYaAc|%!>p3eE|gc`FZ&P)_|WhVIe+**^n2&`4iq_&+86lq_i&uhV8?f@j?&&a6gYz+fkIqOw8b#sTn-LE_XF`giz+>%*VT@L5} E0IK=vy8r+H literal 0 HcmV?d00001 From 968b207135bede702bcedd1f6398642fcc7547f6 Mon Sep 17 00:00:00 2001 From: Frank dellaert Date: Sun, 12 Jul 2020 14:59:43 -0400 Subject: [PATCH 199/869] added printSignature and evaluate --- gtsam/discrete/DiscreteBayesTree.cpp | 10 ++++ gtsam/discrete/DiscreteBayesTree.h | 85 ++++++++++++++++------------ gtsam/discrete/DiscreteConditional.h | 9 +++ gtsam/inference/Conditional.h | 3 +- 4 files changed, 71 insertions(+), 36 deletions(-) diff --git a/gtsam/discrete/DiscreteBayesTree.cpp b/gtsam/discrete/DiscreteBayesTree.cpp index 8fcc34e25..990d10dbe 100644 --- a/gtsam/discrete/DiscreteBayesTree.cpp +++ b/gtsam/discrete/DiscreteBayesTree.cpp @@ -45,6 +45,16 @@ namespace gtsam { return Base::equals(other, tol); } + /* ************************************************************************* */ + double DiscreteBayesTree::evaluate( + const DiscreteConditional::Values& values) const { + double result = 1.0; + for (const auto& root : roots_) { + result *= root->evaluate(values); + } + return result; + } + } // \namespace gtsam diff --git a/gtsam/discrete/DiscreteBayesTree.h b/gtsam/discrete/DiscreteBayesTree.h index aa8f4657c..3d6e016fd 100644 --- a/gtsam/discrete/DiscreteBayesTree.h +++ b/gtsam/discrete/DiscreteBayesTree.h @@ -11,7 +11,8 @@ /** * @file DiscreteBayesTree.h - * @brief Discrete Bayes Tree, the result of eliminating a DiscreteJunctionTree + * @brief Discrete Bayes Tree, the result of eliminating a + * DiscreteJunctionTree * @brief DiscreteBayesTree * @author Frank Dellaert * @author Richard Roberts @@ -22,48 +23,62 @@ #include #include #include +#include #include +#include + namespace gtsam { - // Forward declarations - class DiscreteConditional; - class VectorValues; +// Forward declarations +class DiscreteConditional; +class VectorValues; - /* ************************************************************************* */ - /** A clique in a DiscreteBayesTree */ - class GTSAM_EXPORT DiscreteBayesTreeClique : - public BayesTreeCliqueBase - { - public: - typedef DiscreteBayesTreeClique This; - typedef BayesTreeCliqueBase Base; - typedef boost::shared_ptr shared_ptr; - typedef boost::weak_ptr weak_ptr; - DiscreteBayesTreeClique() {} - DiscreteBayesTreeClique(const boost::shared_ptr& conditional) : Base(conditional) {} +/* ************************************************************************* */ +/** A clique in a DiscreteBayesTree */ +class GTSAM_EXPORT DiscreteBayesTreeClique + : public BayesTreeCliqueBase { + public: + typedef DiscreteBayesTreeClique This; + typedef BayesTreeCliqueBase + Base; + typedef boost::shared_ptr shared_ptr; + typedef boost::weak_ptr weak_ptr; + DiscreteBayesTreeClique() {} + DiscreteBayesTreeClique( + const boost::shared_ptr& conditional) + : Base(conditional) {} - //** evaluate conditional probability of subtree for given Values */ - double evaluate(const DiscreteConditional::Values & values) const; - }; + /// print index signature only + void printSignature( + const std::string& s = "Clique: ", + const KeyFormatter& formatter = DefaultKeyFormatter) const { + conditional_->printSignature(s, formatter); + } - /* ************************************************************************* */ - /** A Bayes tree representing a Discrete density */ - class GTSAM_EXPORT DiscreteBayesTree : - public BayesTree - { - private: - typedef BayesTree Base; + //** evaluate conditional probability of subtree for given Values */ + double evaluate(const DiscreteConditional::Values& values) const; +}; - public: - typedef DiscreteBayesTree This; - typedef boost::shared_ptr shared_ptr; +/* ************************************************************************* */ +/** A Bayes tree representing a Discrete density */ +class GTSAM_EXPORT DiscreteBayesTree + : public BayesTree { + private: + typedef BayesTree Base; - /** Default constructor, creates an empty Bayes tree */ - DiscreteBayesTree() {} + public: + typedef DiscreteBayesTree This; + typedef boost::shared_ptr shared_ptr; - /** Check equality */ - bool equals(const This& other, double tol = 1e-9) const; - }; + /** Default constructor, creates an empty Bayes tree */ + DiscreteBayesTree() {} -} + /** Check equality */ + bool equals(const This& other, double tol = 1e-9) const; + + //** evaluate probability for given Values */ + double evaluate(const DiscreteConditional::Values& values) const; +}; + +} // namespace gtsam diff --git a/gtsam/discrete/DiscreteConditional.h b/gtsam/discrete/DiscreteConditional.h index 3da8d0a82..225e6e1d3 100644 --- a/gtsam/discrete/DiscreteConditional.h +++ b/gtsam/discrete/DiscreteConditional.h @@ -24,6 +24,8 @@ #include #include +#include + namespace gtsam { /** @@ -92,6 +94,13 @@ public: /// @name Standard Interface /// @{ + /// print index signature only + void printSignature( + const std::string& s = "Discrete Conditional: ", + const KeyFormatter& formatter = DefaultKeyFormatter) const { + static_cast(this)->print(s, formatter); + } + /// Evaluate, just look up in AlgebraicDecisonTree virtual double operator()(const Values& values) const { return Potentials::operator()(values); diff --git a/gtsam/inference/Conditional.h b/gtsam/inference/Conditional.h index 1d486030c..295122879 100644 --- a/gtsam/inference/Conditional.h +++ b/gtsam/inference/Conditional.h @@ -65,6 +65,8 @@ namespace gtsam { Conditional(size_t nrFrontals) : nrFrontals_(nrFrontals) {} /// @} + + public: /// @name Testable /// @{ @@ -76,7 +78,6 @@ namespace gtsam { /// @} - public: /// @name Standard Interface /// @{ From ae808d039cda45df8334d1857773c9c06c2943a0 Mon Sep 17 00:00:00 2001 From: Frank dellaert Date: Sun, 12 Jul 2020 15:00:34 -0400 Subject: [PATCH 200/869] Fixed link issue --- gtsam/discrete/tests/testDiscreteFactorGraph.cpp | 1 + 1 file changed, 1 insertion(+) diff --git a/gtsam/discrete/tests/testDiscreteFactorGraph.cpp b/gtsam/discrete/tests/testDiscreteFactorGraph.cpp index 0fbf44097..7a0e1eaf7 100644 --- a/gtsam/discrete/tests/testDiscreteFactorGraph.cpp +++ b/gtsam/discrete/tests/testDiscreteFactorGraph.cpp @@ -19,6 +19,7 @@ #include #include #include +#include #include From d456dddc6f1860f76b3ff8a7be555d55a430fb6d Mon Sep 17 00:00:00 2001 From: Frank dellaert Date: Sun, 12 Jul 2020 15:00:54 -0400 Subject: [PATCH 201/869] Cleaned up formatting --- gtsam/inference/BayesTreeCliqueBase-inst.h | 54 ++++++++++++---------- 1 file changed, 29 insertions(+), 25 deletions(-) diff --git a/gtsam/inference/BayesTreeCliqueBase-inst.h b/gtsam/inference/BayesTreeCliqueBase-inst.h index e762786f5..a02fe274e 100644 --- a/gtsam/inference/BayesTreeCliqueBase-inst.h +++ b/gtsam/inference/BayesTreeCliqueBase-inst.h @@ -136,57 +136,61 @@ namespace gtsam { } } - /* ************************************************************************* */ + /* *********************************************************************** */ // separator marginal, uses separator marginal of parent recursively // P(C) = P(F|S) P(S) - /* ************************************************************************* */ - template + /* *********************************************************************** */ + template typename BayesTreeCliqueBase::FactorGraphType - BayesTreeCliqueBase::separatorMarginal(Eliminate function) const - { + BayesTreeCliqueBase::separatorMarginal( + Eliminate function) const { gttic(BayesTreeCliqueBase_separatorMarginal); // Check if the Separator marginal was already calculated - if (!cachedSeparatorMarginal_) - { + if (!cachedSeparatorMarginal_) { gttic(BayesTreeCliqueBase_separatorMarginal_cachemiss); + // If this is the root, there is no separator - if (parent_.expired() /*(if we're the root)*/) - { + if (parent_.expired() /*(if we're the root)*/) { // we are root, return empty FactorGraphType empty; cachedSeparatorMarginal_ = empty; - } - else - { + } else { + // Flatten recursion in timing outline + gttoc(BayesTreeCliqueBase_separatorMarginal_cachemiss); + gttoc(BayesTreeCliqueBase_separatorMarginal); + // Obtain P(S) = \int P(Cp) = \int P(Fp|Sp) P(Sp) // initialize P(Cp) with the parent separator marginal derived_ptr parent(parent_.lock()); - gttoc(BayesTreeCliqueBase_separatorMarginal_cachemiss); // Flatten recursion in timing outline - gttoc(BayesTreeCliqueBase_separatorMarginal); - FactorGraphType p_Cp(parent->separatorMarginal(function)); // P(Sp) + FactorGraphType p_Cp(parent->separatorMarginal(function)); // P(Sp) + gttic(BayesTreeCliqueBase_separatorMarginal); gttic(BayesTreeCliqueBase_separatorMarginal_cachemiss); + // now add the parent conditional - p_Cp += parent->conditional_; // P(Fp|Sp) + p_Cp += parent->conditional_; // P(Fp|Sp) // The variables we want to keepSet are exactly the ones in S - KeyVector indicesS(this->conditional()->beginParents(), this->conditional()->endParents()); - cachedSeparatorMarginal_ = *p_Cp.marginalMultifrontalBayesNet(Ordering(indicesS), function); + KeyVector indicesS(this->conditional()->beginParents(), + this->conditional()->endParents()); + auto separatorMarginal = + p_Cp.marginalMultifrontalBayesNet(Ordering(indicesS), function); + cachedSeparatorMarginal_.reset(*separatorMarginal); } } // return the shortcut P(S||B) - return *cachedSeparatorMarginal_; // return the cached version + return *cachedSeparatorMarginal_; // return the cached version } - /* ************************************************************************* */ - // marginal2, uses separator marginal of parent recursively + /* *********************************************************************** */ + // marginal2, uses separator marginal of parent // P(C) = P(F|S) P(S) - /* ************************************************************************* */ - template + /* *********************************************************************** */ + template typename BayesTreeCliqueBase::FactorGraphType - BayesTreeCliqueBase::marginal2(Eliminate function) const - { + BayesTreeCliqueBase::marginal2( + Eliminate function) const { gttic(BayesTreeCliqueBase_marginal2); // initialize with separator marginal P(S) FactorGraphType p_C = this->separatorMarginal(function); From 468c7aee0cd9b5933178b7304a6acce34eeb8692 Mon Sep 17 00:00:00 2001 From: Frank dellaert Date: Sun, 12 Jul 2020 15:01:00 -0400 Subject: [PATCH 202/869] Fixed tests --- .../discrete/tests/testDiscreteBayesTree.cpp | 191 ++++++++---------- 1 file changed, 81 insertions(+), 110 deletions(-) diff --git a/gtsam/discrete/tests/testDiscreteBayesTree.cpp b/gtsam/discrete/tests/testDiscreteBayesTree.cpp index f58fd2b19..150a41c24 100644 --- a/gtsam/discrete/tests/testDiscreteBayesTree.cpp +++ b/gtsam/discrete/tests/testDiscreteBayesTree.cpp @@ -33,41 +33,6 @@ using namespace gtsam; static bool debug = false; -// /** -// * Custom clique class to debug shortcuts -// */ -// struct Clique : public BayesTreeCliqueBase { -// typedef BayesTreeCliqueBase Base; -// typedef boost::shared_ptr shared_ptr; - -// // Constructors -// Clique() {} -// explicit Clique(const DiscreteConditional::shared_ptr& conditional) -// : Base(conditional) {} -// Clique(const std::pair& -// result) -// : Base(result) {} - -// /// print index signature only -// void printSignature( -// const std::string& s = "Clique: ", -// const KeyFormatter& indexFormatter = DefaultKeyFormatter) const { -// ((IndexConditionalOrdered::shared_ptr)conditional_) -// ->print(s, indexFormatter); -// } - -// /// evaluate value of sub-tree -// double evaluate(const DiscreteConditional::Values& values) { -// double result = (*(this->conditional_))(values); -// // evaluate all children and multiply into result -// for (boost::shared_ptr c : children_) result *= -// c->evaluate(values); return result; -// } -// }; - -// typedef BayesTreeOrdered DiscreteBayesTree; - /* ************************************************************************* */ TEST_UNSAFE(DiscreteBayesTree, thinTree) { @@ -124,24 +89,24 @@ TEST_UNSAFE(DiscreteBayesTree, thinTree) { for (size_t i = 0; i < allPosbValues.size(); ++i) { DiscreteFactor::Values x = allPosbValues[i]; double expected = bayesNet.evaluate(x); - double actual = R->evaluate(x); + double actual = bayesTree->evaluate(x); DOUBLES_EQUAL(expected, actual, 1e-9); } - // Calculate all some marginals + // Calculate all some marginals for Values==all1 Vector marginals = zero(15); double joint_12_14 = 0, joint_9_12_14 = 0, joint_8_12_14 = 0, joint_8_12 = 0, joint82 = 0, joint12 = 0, joint24 = 0, joint45 = 0, joint46 = 0, - joint_4_11 = 0; + joint_4_11 = 0, joint_11_13 = 0, joint_11_13_14 = 0, + joint_11_12_13_14 = 0, joint_9_11_12_13 = 0, joint_8_11_12_13 = 0; for (size_t i = 0; i < allPosbValues.size(); ++i) { DiscreteFactor::Values x = allPosbValues[i]; - double px = R->evaluate(x); + double px = bayesTree->evaluate(x); for (size_t i = 0; i < 15; i++) if (x[i]) marginals[i] += px; - // calculate shortcut 8 and 0 if (x[12] && x[14]) joint_12_14 += px; - if (x[9] && x[12] & x[14]) joint_9_12_14 += px; - if (x[8] && x[12] & x[14]) joint_8_12_14 += px; + if (x[9] && x[12] && x[14]) joint_9_12_14 += px; + if (x[8] && x[12] && x[14]) joint_8_12_14 += px; if (x[8] && x[12]) joint_8_12 += px; if (x[8] && x[2]) joint82 += px; if (x[1] && x[2]) joint12 += px; @@ -149,96 +114,102 @@ TEST_UNSAFE(DiscreteBayesTree, thinTree) { if (x[4] && x[5]) joint45 += px; if (x[4] && x[6]) joint46 += px; if (x[4] && x[11]) joint_4_11 += px; + if (x[11] && x[13]) { + joint_11_13 += px; + if (x[8] && x[12]) joint_8_11_12_13 += px; + if (x[9] && x[12]) joint_9_11_12_13 += px; + if (x[14]) { + joint_11_13_14 += px; + if (x[12]) { + joint_11_12_13_14 += px; + } + } + } } DiscreteFactor::Values all1 = allPosbValues.back(); - // check separator marginal P(S0) auto c = (*bayesTree)[0]; DiscreteFactorGraph separatorMarginal0 = c->separatorMarginal(EliminateDiscrete); - EXPECT_DOUBLES_EQUAL(joint_8_12, separatorMarginal0(all1), 1e-9); + DOUBLES_EQUAL(joint_8_12, separatorMarginal0(all1), 1e-9); - // // check separator marginal P(S9), should be P(14) - // c = (*bayesTree)[9]; - // DiscreteFactorGraph separatorMarginal9 = - // c->separatorMarginal(EliminateDiscrete); - // EXPECT_DOUBLES_EQUAL(marginals[14], separatorMarginal9(all1), 1e-9); + // check separator marginal P(S9), should be P(14) + c = (*bayesTree)[9]; + DiscreteFactorGraph separatorMarginal9 = + c->separatorMarginal(EliminateDiscrete); + DOUBLES_EQUAL(marginals[14], separatorMarginal9(all1), 1e-9); - // // check separator marginal of root, should be empty - // c = (*bayesTree)[11]; - // DiscreteFactorGraph separatorMarginal11 = - // c->separatorMarginal(EliminateDiscrete); - // EXPECT_LONGS_EQUAL(0, separatorMarginal11.size()); + // check separator marginal of root, should be empty + c = (*bayesTree)[11]; + DiscreteFactorGraph separatorMarginal11 = + c->separatorMarginal(EliminateDiscrete); + LONGS_EQUAL(0, separatorMarginal11.size()); - // // check shortcut P(S9||R) to root - // c = (*bayesTree)[9]; - // DiscreteBayesNet shortcut = c->shortcut(R, EliminateDiscrete); - // EXPECT_LONGS_EQUAL(0, shortcut.size()); + // check shortcut P(S9||R) to root + c = (*bayesTree)[9]; + DiscreteBayesNet shortcut = c->shortcut(R, EliminateDiscrete); + LONGS_EQUAL(1, shortcut.size()); + DOUBLES_EQUAL(joint_11_13_14 / joint_11_13, shortcut.evaluate(all1), 1e-9); - // // check shortcut P(S8||R) to root - // c = (*bayesTree)[8]; - // shortcut = c->shortcut(R, EliminateDiscrete); - // EXPECT_DOUBLES_EQUAL(joint_12_14 / marginals[14], evaluate(shortcut, all1), - // 1e-9); + // check shortcut P(S8||R) to root + c = (*bayesTree)[8]; + shortcut = c->shortcut(R, EliminateDiscrete); + DOUBLES_EQUAL(joint_11_12_13_14 / joint_11_13, shortcut.evaluate(all1), 1e-9); - // // check shortcut P(S2||R) to root - // c = (*bayesTree)[2]; - // shortcut = c->shortcut(R, EliminateDiscrete); - // EXPECT_DOUBLES_EQUAL(joint_9_12_14 / marginals[14], evaluate(shortcut, - // all1), - // 1e-9); + // check shortcut P(S2||R) to root + c = (*bayesTree)[2]; + shortcut = c->shortcut(R, EliminateDiscrete); + DOUBLES_EQUAL(joint_9_11_12_13 / joint_11_13, shortcut.evaluate(all1), 1e-9); - // // check shortcut P(S0||R) to root - // c = (*bayesTree)[0]; - // shortcut = c->shortcut(R, EliminateDiscrete); - // EXPECT_DOUBLES_EQUAL(joint_8_12_14 / marginals[14], evaluate(shortcut, - // all1), - // 1e-9); + // check shortcut P(S0||R) to root + c = (*bayesTree)[0]; + shortcut = c->shortcut(R, EliminateDiscrete); + DOUBLES_EQUAL(joint_8_11_12_13 / joint_11_13, shortcut.evaluate(all1), 1e-9); - // // calculate all shortcuts to root - // DiscreteBayesTree::Nodes cliques = bayesTree->nodes(); - // for (auto c : cliques) { - // DiscreteBayesNet shortcut = c->shortcut(R, EliminateDiscrete); - // if (debug) { - // c->printSignature(); - // shortcut.print("shortcut:"); - // } - // } + // calculate all shortcuts to root + DiscreteBayesTree::Nodes cliques = bayesTree->nodes(); + for (auto c : cliques) { + DiscreteBayesNet shortcut = c.second->shortcut(R, EliminateDiscrete); + if (debug) { + c.second->conditional_->printSignature(); + shortcut.print("shortcut:"); + } + } - // // Check all marginals - // DiscreteFactor::shared_ptr marginalFactor; - // for (size_t i = 0; i < 15; i++) { - // marginalFactor = bayesTree->marginalFactor(i, EliminateDiscrete); - // double actual = (*marginalFactor)(all1); - // EXPECT_DOUBLES_EQUAL(marginals[i], actual, 1e-9); - // } + // Check all marginals + DiscreteFactor::shared_ptr marginalFactor; + for (size_t i = 0; i < 15; i++) { + marginalFactor = bayesTree->marginalFactor(i, EliminateDiscrete); + double actual = (*marginalFactor)(all1); + DOUBLES_EQUAL(marginals[i], actual, 1e-9); + } - // DiscreteBayesNet::shared_ptr actualJoint; + DiscreteBayesNet::shared_ptr actualJoint; - // Check joint P(8,2) TODO: not disjoint ! - // actualJoint = bayesTree->jointBayesNet(8, 2, EliminateDiscrete); - // EXPECT_DOUBLES_EQUAL(joint82, evaluate(*actualJoint,all1), 1e-9); + // Check joint P(8, 2) + actualJoint = bayesTree->jointBayesNet(8, 2, EliminateDiscrete); + DOUBLES_EQUAL(joint82, actualJoint->evaluate(all1), 1e-9); - // Check joint P(1,2) TODO: not disjoint ! - // actualJoint = bayesTree->jointBayesNet(1, 2, EliminateDiscrete); - // EXPECT_DOUBLES_EQUAL(joint12, evaluate(*actualJoint,all1), 1e-9); + // Check joint P(1, 2) + actualJoint = bayesTree->jointBayesNet(1, 2, EliminateDiscrete); + DOUBLES_EQUAL(joint12, actualJoint->evaluate(all1), 1e-9); - // Check joint P(2,4) - // actualJoint = bayesTree->jointBayesNet(2, 4, EliminateDiscrete); - // EXPECT_DOUBLES_EQUAL(joint24, evaluate(*actualJoint, all1), 1e-9); + // Check joint P(2, 4) + actualJoint = bayesTree->jointBayesNet(2, 4, EliminateDiscrete); + DOUBLES_EQUAL(joint24, actualJoint->evaluate(all1), 1e-9); - // Check joint P(4,5) TODO: not disjoint ! - // actualJoint = bayesTree->jointBayesNet(4, 5, EliminateDiscrete); - // EXPECT_DOUBLES_EQUAL(joint46, evaluate(*actualJoint,all1), 1e-9); + // Check joint P(4, 5) + actualJoint = bayesTree->jointBayesNet(4, 5, EliminateDiscrete); + DOUBLES_EQUAL(joint45, actualJoint->evaluate(all1), 1e-9); - // Check joint P(4,6) TODO: not disjoint ! - // actualJoint = bayesTree->jointBayesNet(4, 6, EliminateDiscrete); - // EXPECT_DOUBLES_EQUAL(joint46, evaluate(*actualJoint,all1), 1e-9); + // Check joint P(4, 6) + actualJoint = bayesTree->jointBayesNet(4, 6, EliminateDiscrete); + DOUBLES_EQUAL(joint46, actualJoint->evaluate(all1), 1e-9); - // Check joint P(4,11) - // actualJoint = bayesTree->jointBayesNet(4, 11, EliminateDiscrete); - // EXPECT_DOUBLES_EQUAL(joint_4_11, evaluate(*actualJoint, all1), 1e-9); + // Check joint P(4, 11) + actualJoint = bayesTree->jointBayesNet(4, 11, EliminateDiscrete); + DOUBLES_EQUAL(joint_4_11, actualJoint->evaluate(all1), 1e-9); } /* ************************************************************************* */ From 362b64499a8abdbe6584f1746a5c6d1754020c3b Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Sun, 12 Jul 2020 19:03:05 -0400 Subject: [PATCH 203/869] perform equality comparison on root of class hierarchy --- gtsam/navigation/CombinedImuFactor.cpp | 2 +- gtsam/navigation/CombinedImuFactor.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/gtsam/navigation/CombinedImuFactor.cpp b/gtsam/navigation/CombinedImuFactor.cpp index 7f58f7e64..d7b4b7bf1 100644 --- a/gtsam/navigation/CombinedImuFactor.cpp +++ b/gtsam/navigation/CombinedImuFactor.cpp @@ -44,7 +44,7 @@ void PreintegrationCombinedParams::print(const string& s) const { } //------------------------------------------------------------------------------ -bool PreintegrationCombinedParams::equals(const PreintegrationParams& other, +bool PreintegrationCombinedParams::equals(const PreintegratedRotationParams& other, double tol) const { auto e = dynamic_cast(&other); return e != nullptr && PreintegrationParams::equals(other, tol) && diff --git a/gtsam/navigation/CombinedImuFactor.h b/gtsam/navigation/CombinedImuFactor.h index 8b6dcd3f2..a89568433 100644 --- a/gtsam/navigation/CombinedImuFactor.h +++ b/gtsam/navigation/CombinedImuFactor.h @@ -88,7 +88,7 @@ struct GTSAM_EXPORT PreintegrationCombinedParams : PreintegrationParams { } void print(const std::string& s="") const; - bool equals(const PreintegrationParams& other, double tol) const; + bool equals(const PreintegratedRotationParams& other, double tol) const; void setBiasAccCovariance(const Matrix3& cov) { biasAccCovariance=cov; } void setBiasOmegaCovariance(const Matrix3& cov) { biasOmegaCovariance=cov; } From c68ab6b3bedf9576416b816089482c1a2e14ce50 Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Sun, 12 Jul 2020 19:54:23 -0400 Subject: [PATCH 204/869] correct vector init --- gtsam/discrete/tests/testDiscreteBayesTree.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/gtsam/discrete/tests/testDiscreteBayesTree.cpp b/gtsam/discrete/tests/testDiscreteBayesTree.cpp index 150a41c24..9950c014e 100644 --- a/gtsam/discrete/tests/testDiscreteBayesTree.cpp +++ b/gtsam/discrete/tests/testDiscreteBayesTree.cpp @@ -35,7 +35,7 @@ static bool debug = false; /* ************************************************************************* */ -TEST_UNSAFE(DiscreteBayesTree, thinTree) { +TEST_UNSAFE(DiscreteBayesTree, ThinTree) { const int nrNodes = 15; const size_t nrStates = 2; @@ -94,7 +94,7 @@ TEST_UNSAFE(DiscreteBayesTree, thinTree) { } // Calculate all some marginals for Values==all1 - Vector marginals = zero(15); + Vector marginals = Vector::Zero(15); double joint_12_14 = 0, joint_9_12_14 = 0, joint_8_12_14 = 0, joint_8_12 = 0, joint82 = 0, joint12 = 0, joint24 = 0, joint45 = 0, joint46 = 0, joint_4_11 = 0, joint_11_13 = 0, joint_11_13_14 = 0, From c67779fdce5f0897ce36c85b1b2ea65896513862 Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Sun, 12 Jul 2020 19:54:42 -0400 Subject: [PATCH 205/869] delete extra pdf file --- gtsam/discrete/tests/testDiscreteBayesTree.pdf | Bin 10622 -> 0 bytes 1 file changed, 0 insertions(+), 0 deletions(-) delete mode 100644 gtsam/discrete/tests/testDiscreteBayesTree.pdf diff --git a/gtsam/discrete/tests/testDiscreteBayesTree.pdf b/gtsam/discrete/tests/testDiscreteBayesTree.pdf deleted file mode 100644 index e8167d455477f97aadb2101d26120a6c145891f5..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 10622 zcma)i2RK~a^S>5?=p|~bPPEvu87l@l5hq-FA~Taz0X!;D zXB&5006&7Hg#!Qpc;xIH-Jx*A(-Gnhy$iL3SwV5c#c|x+;ZTSZ&i#ym6xG-nfg2&) z-^s*TB<~T)Dken$La#-jq59a?RRcmTBJ!>$$b6K!d|;-Pw=p{v+e6>N@FAQ%os>(Q zfqj%}cROMy(b81iEU78^rDfB%`o=TH61qzh+iwJxu-#)j@8bv2^d%3uNhi(p3b-6+ zCPpTBv|k#nq)v=g58W;`G8yd*a7*kPO@rfd6~<}dHtf8siRb}(rJ>!5%~!9Yc_D0^ zwaiD@AJCzTKbJZ2X|wA4X^rV8&L=Wape4sriH;|NALi@}9r87N)yF2&dHRY7?(N<# zc{AsyKi80*JZ4&Uaj~<9({y{3d-5CH_w@Vn=HBQ)<0}<0_ZnFmk8$I*w~k`%cwo~Z zGo2FkHACiGURroYJ$)qtm}4t;$y#qZcy*QPG>xD6y_4-&jVz=U`xZgQ*%;VLivU&`1}PK||UGDx>Q9u{jm6CK^L<*ef=hu#&~d?MMFK0N61HO}zUJ&=~I zQ(c27RxUr^!&h|0#L@BZ9bSE#;C(jPl;qa1&OH9OoWFy~TICU0^n>N0_8!tDb(^^L zQ6<`>wqX%AqIE!!!LCCYu$Rb&C@!u|JFlUyBY<_)m~dE`QT0%8~vExZX+ zAFzh4`VJ?)w<`oW7Mt@pqw+*QdO}0Is1w1+QhG&*zoQ(QF&duh}O4`A5 ziXXedCD!QVCdr})CAW2IhEbzb1s}PZ8E>wvc60;DQ=ZAmwcTvG$?COS#J1uQ3@563b2~v#|h8Mf<{^7lySTh6}mgo7&Asw zs$HAGxO`q7B{vzGdlEi^7uls`En=nPtHkrkQrLkeXnNT^3Xy4Z4}AwbsvdfBalZYSCHT-%@((y{Wv=^{RXZJEnRT-GHFC zFMCL-xfmV0*>V;h_B84436?Jh>hv!w5GO7$3~TM#T=!^GYdW+F%1=a04rkZrd1+OjkJTJz=V{Ag-9U zbuKC(D@nkP#MCPx`jEme7{;V;Z|KTTt&#h}B;iQW)^&W$GuMu$a!rB5r_bNDD(FS> zeqga(y~`HCuJos@(mYjQ|O03%skp*OOSb`dMX?iL1lGln~KStlaEifwy{h@mK{Ayf{@b_qBR#0a1=YcrdLu@KKix(-Z>@-tJTOci==dV7S zGgCyl)$nx_;qAplsAw#@$x^8ndsf=`2%%}tD#zjKDeH?<8(^nl0l1{1jF*_hQk|0l z)MY*(W*(N3+h5#r4FetDX$H=ajozs_CF^?jKnnZzr$USl)}|7g!IWDQ!Xt0URVl?v z{LE9~4_;S8Pp!YG9~yZom%nF!t$Of1Y93zT)j(=5!p(i6h$-Cc+OrpKJD-pb6)*TxgamkH{R26h_y?62XO`SK0`}BFIfCQa!+#Qz{sV?y6xJ?HsQsao% zj!!I$p3rp?Tc6SZ4ylxT8^k1)<#uo5IXs%JlqIiZj*SBtuu3uJF6tOZzZ2{os+~UE zTi=t&oqBd12kLC~GglzKA+roJwIH8}*LlMJ+e)Z*1g<9D`q+#~~MhFrRz|SuX z-~;jjOs=?P5TYR1-2lkc`Xi6Z!(kpSe-rP=99Ps|>(fTe42L+oxgh7V^!`Ow1h~UJ zpubu&2(G(OPdiJfmb^5Q_;dAIP&b$d+!E>rKx$I!Zz~f*wEvafg@23nU+EpGsvo}t zKmZ|LKB0f)`%OV_KW*K2pM;O+90!~d1niQy71LNuM);g$3?uRzg7YN%w6e`P$PK6M z*`LhfNE^r{X<6O1BGK#%qvpUUCtTR}hdTGj8vs{Ylu7^d`lV{FQp$;Fnk-a}Ptz0AV|(XcI|yT1{=~&Zd6bo52_@i%jbQV&UM+Ha~VdEc=|28@(@y?G_-3UQh|g1 zBCbePE;kqqNqBg-czHl>G}4OlLyu)1YRICL6bq&i`m^VJOW2(W*!M6?;yIkXq{KPx zA29`~J+tEb@D18tO1%uv>sx&AB6g5Pn;bvO#1z_Fp)vr#9Wxetap8IKm_~qERnHxF z-{k@1mB3OBo3H-?M?s5@khR$}C;Se+n2gRDqE$=HgLBB=`l( zeutzc*r&eCf0<`&e}cz7&=dNirw9!5?U3pE(yD;d2+xxGgAS#D6W z;@@v-Oi-vLLSIcV#S5|!<>Z3#gUCOm*Ju9;-O%jWn)hSKF}ho2vQzbAzh`p`!XYy z(d^Yqe5rN?PQEmrQgDJLWj`?1TqXNS*@_5rI94nCTq;_OpXLQl7#4G2CM1lDG03eS;$(Jl?PSu}Qci zi^zHONH12}fc@-73U7_N#%D-_xk)EsOmewW?~Y`50!Eh2bprbkUDTG9J8DVubNMWF zF)u09^7Voh)3P6b>-9TgOsarr9n`C`bo)S~HiUEoFvr*$SxiYU?c0_@Mp~3LOk>g~ zpK6(?*lW6s1(A`pyp_8l&0NlU<}My2^L1$Io4aAVWFrOtdUBJW)ecjgM_Gh{m($W& z_o&shkK*^P=MS0EQ*7w*`FC;I`Q+&*mnatcDK5`4PHJdkA_dd?Uu;a0`&E13*FBQeCdOwQ*1vV!8}i53D_fN}D?Ge8Fj1FQ(D$-&qQnsgHnfR}Hb1+PKS_I_ERB zb*~67116)k;BBCsW$n=y%Nzw9)^EX3pS8>$uL4Jvxs(d|I$m%2Uerz8DT()u*$r{D z&t3r2RhBuaWhl4@H~7Nwg55@5-zS#fp37VDaAV0@$D|#GRM70Td)S26&i8Z}Q-(1s zojyuo#4A9(fytNkq}x`VJsD&)Vj>LY+K$){0%LL1hU}AgSl83(OyNkx+m%x(k%ClR z%s6h7yU~qaOJwM=p~n>K$h?7$&5NnoVIdFJ4UCOxRPX5BniBFoeZI+h`KHG5urQ`e z*Qw>{_-0X6%&R2G7P<{)%y9ey*Q+Xnuh&0*s@^P(;;7ipoQjpF5jI#S? zR1B?=`ZiATHQcl}J)R;G2Iq>q0fE%>2J{D=TB$LNN_*Lt*q5vss4#gi^ zGP6|Pj%hEXz~qeTdCi+Xuk$!@73#Ji9Q2?`7R9$BZFQo-mfVeCz$s}54VB9~roGDFS$m<7J5XKdqO2}qTGfUSg6 z;agHCg`GtQeVx}Q>Mu~4k6NEwFj~?nE|VB+2da+NJ9~Yh6BIk_`y?w6CrHgou1{`! zUL60LiA&w-VOjqD^1V@+ug4p)8IiBMi|)yPN70I6{+u<^#cvUn-y%T&jdCyej6`hz z_64RmY5~fHG4}hYd)+>xH79dSS)Qz6nwHugM(r=l4JsBW9L>?IEha}#&-wNTqo$sgMW+LK%f?xHmSZVdQdrsz(qe*F&pJ@%ab(%FsYbUZ%HzOiOu(-J+ zmUQ&w-1WU>W2uePF>3c|kyC*WeeuGUc(%3tC0x zD6f>HJKGRJxAo|{4EYqs4b3g@^E!ij1`g!ukUie02wiBJx0@WhNULs|H?CltXdAd~ za`3I&=CY@9ojSF~i7`veI0X}7@{q&QypNmrz|6tdRpaihfr6=(YxIM#lytZb=oreg z8!@*-AOqvO(LQprH&oR|(P!2p7%c2v=vizU?pxBEOGvw4dmCo_j{9OJL4@j}MYro7Ow8Zve63*b-G^HJfCt6{#UaKg z_vqbZz;nb0m}q<-yH`gKLxifdEZ^Ajr!iyq^dwn1mK%FIr;y^C>1QN|wR0{S=%qk()0_Q_nguVMAd)WnNpc{r zRyM9@Zgt&f^qqxGPF!&o=m&|Y(j)?i=nUG69Gol`%WNzbX>9kn_&BKt*JKGFhkn5r z)W^q-drQ34mb?$SPk)9JL)J1%7*a$bTzKE?r409RGy3r85N=Z_$FTqK`xdPA_<6qr zuagJHLHao4e#sa)wB*DDCRDT6p*3^P_ff?Gio;-FGmtG9Wd`4A2z4JqJ8v4ezayY1 z={^H9)3 zHX(DNsDvHgFZ3U^g+=F2vN@J*ru4`A%+8E>k#@W)({=P%dxczhdwdZKXop9bHmT8rbD>Tzm)#lzAxAH>mQcw$`3a!%0 z9;YPsdoMdJ%PhlQ2b=Vkm|q5q^_iOUls~jCg&T4|OYc-oPPJmLP@8%%MSp61TDgZi z6f5um-{b5{DP_`V<^i?7Y?pb~mqyixYF*D+-*wYh&~Y77bZ!DUw=IdvNX<1Nr`Xd# zEZpm<+%_SMv(A+T`2|cy{Vcm{$tl^R_VeBz8A^q5eLIE9*o&C7Pov+)6@l8{(O7o* zv^VBrW2HR+4pCHm(O8PLlYT1~-hX7Ngvt&(7g3^@V>f=mWN5_x#0Tyq70Pv>*9^f; zG-8>A_$oJR!f^2vHnFvQi^i7AovIfwjE2U@%YqehxhP(3IId$0V8+dYP@@a>7A;(| z`RDI;(o@Wijay3tv@m4Ix}X7xOU0M;4lv1&YTo_qslj7=uld2z2df<7v4e%UrMvGliZ|xhoi-& ziG(=Xg{$z5-jhkn3u883>?({7h4mLUpjl|Ue?1J7ywDK2ky<+r(U=%JB-$H21BRCn z$N&y0vcUbXQ^N*{+aPKvHkMdC`EgGzyY$pbiiz_}NWWRHmmfwstd{FePY->0tsNL< zyIFYr{Eqhevbl+o4FUFH&t!V>;UQyOtkGhdlAq67yv#XasAo7jnBwm9nHhV&_@V-5 zxQVSQK$r<*ZJ3Edg4JP7nsqqh@K9l?mYcn`M7V%Hbzj3;9bcdx#H}5VRq=9rHT;m~ zXs9PEYw;F{z~UP)poxw!1hW+YYSzF`p$0@vA>82$1^IBVw&fA^-c5zFW+w&pO?FXV>m>ZnU zT_@w(kE)6E=97b;#V0jeUYE!B$3F4+d@o=>!d%2P-g^;T{2Xf~xnEBpdbY1Peo2vI zr|kO8IrawBH~P+KahIl^IG@lkayz1hSIPN$&BlmTx!5I=Rc{qCOJ7rO?C3ewa!Rx> z)zMlvwbx5vnOFN;ak(ruMFr|NjA zIu{jQCv)L>yWMd_)k{xm#)9i&g&M=z9DhxywUu*Y{4-7^Q%qtRYsnqOwI$0^8sAf` z_mM^3X*K|Xj=F^ zoDjAkQMP;2@uETCK~=PblzZ+E@ur0&(p$5;1#$s|OA z-z$7c)II?kc<5BBR_dZFIo_J8&W!uN_$BF;6Qy2r~YxZcDS4WGQQ zoC~Zu2nnWrtH=Z(;Uw6b=Qfm`eUPGUqOS1dMr7<{=`k0Rm30Sql4s& z)8hsb>Vc_qFp~|EdtsG>vN4;r;}h02bBwmHy=yxr3g;FkdgeMN6w9A>USk4IoCoF& zPNJE`+ZXQ?7|JI#KpWT}r5zY4x37MifRuOO?lT?Y^mZD}zP#l-mZoiFuG+;M{<&PO z&O}^UT-B8GxNm=nyH-1kMg8eI88%KagK3W5OH!O*m6qE;XRLm-ib4$yG=?x zJa)DgXIB4)hVfavdSHO%qBhZ(Z4X;NRg)AystgjjcA9#Uh;DUP zlx=YZ4cavB-2g`#9GW0QA^@Es#uNkHjVXq3NA0NoNaHw809yP8@qK16PXkkY19QTm zhYc3G|I`#Qb~4s1v7%ryYeII5Wy05mG0A6>9GZpFOlAopW@HHz`ASiK;!N!O;Y|L) z;!G?1WJjlSf;)!jIaM)_iea5|)Y-=oE0i&kbQ^dR z6Nj5*hUnjTA5)Gj?GJ@;MFvV3I*cAxkvr9*R&p^^%FY{72MS7J$sS<37H8M!X&5^M zl}Q;Yk8ugvti5CwJmG3sh)GpW>VJHRLa)1w`zJ7fJe2+k4DbsA1%4gOgOJDT|2n@0 z{dEriUkBKTBk|w(w8`**^J4%Z%4ZREP}e4eaqT-xXWo>l=mBe$Kg#1_=0eFhv6CZO z^Ga184RLDy%wXXb=hDF^%(^U>9%Rkq;=rHasK<9@5?g;gSKcc6K}I!^4>S#9J5$I zW*~!!$a>RGa6SE&d16Q_{qzXxtY{bevB+l=*&H470 z%|%Lhy|?;;!p-<)Le^|N@vUBin?)o0xEk2uqFn+yDtAOmqxfZEyEB7hsjFjrl)-Jwo;0HGfpkPU@j4dmJo-UI~$kci3O5fmhd z^veT(;5JC!AH#WAxL=_~ItYvg`Rkjb`@$#aV2S{5dCCP;(NluZ1ii&fi95$wbQ_yHR^!Li!w!?1n|Hs0k?r#dkVe7s+OHtnYN6 z;fISji)bju;f!tzrN1?vJIwUNqjqtFJS zll{lMzuXOBZIICKX_2tyKb`O&hQDiPZ4E`@h6n`E2ngUo+#r*`p@5*jU_cz?+beq^ zph+GO0)|Bl{SRCI3dMh0A{gm5KcLM2WlNJdRp)lVjo{;q*1lB>jGjBvuL{yR&vFaI zP+C}I(@@~u4AngJxjJiTR{L`{Vw|vV%5;91r!B+yPg+hNsVEyy5l8Wz0@BEbK3=S> zIoTvW=G-acN?jJOVS9(aXhW3TPi>q9iaB6Hk!<88J_oieoeR*Yx226_TH{bY8KR0a zraZPENl(SL3N95RpZ&UNSSHamnRI=6T2P*eIzGvYvmBcwT#X$s)6Gz$`JtgNVQ!^F zi24f|leK~|rK(qOf-Z5$a5MP9a!61Z1en88}5mX`Wa62UOj7)T0MU^f%>QGK z-&ixEWDMzI2uJ-#Z1@2$|Ann1<@=}WBC&P1t5qx8Ss}yKRebx6o_ipn_P;qV`0pbi zR$}F0iKt0qvxL~eVE_;}NPrs%V6%01cX7MJgQyHZP;KB47h5|^H*Of*hW$svkwH|f zx!b{8Sfk5`ZPx@#2lYt;o5X|OE@T(>KEC~2( zsrTVfYaAc|%!>p3eE|gc`FZ&P)_|WhVIe+**^n2&`4iq_&+86lq_i&uhV8?f@j?&&a6gYz+fkIqOw8b#sTn-LE_XF`giz+>%*VT@L5} E0IK=vy8r+H From 80b42dcbefeae96b53a5598b3a470734c5e5df68 Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Sun, 12 Jul 2020 20:55:13 -0400 Subject: [PATCH 206/869] Revert "delete extra pdf file" This reverts commit c67779fdce5f0897ce36c85b1b2ea65896513862. --- gtsam/discrete/tests/testDiscreteBayesTree.pdf | Bin 0 -> 10622 bytes 1 file changed, 0 insertions(+), 0 deletions(-) create mode 100644 gtsam/discrete/tests/testDiscreteBayesTree.pdf diff --git a/gtsam/discrete/tests/testDiscreteBayesTree.pdf b/gtsam/discrete/tests/testDiscreteBayesTree.pdf new file mode 100644 index 0000000000000000000000000000000000000000..e8167d455477f97aadb2101d26120a6c145891f5 GIT binary patch literal 10622 zcma)i2RK~a^S>5?=p|~bPPEvu87l@l5hq-FA~Taz0X!;D zXB&5006&7Hg#!Qpc;xIH-Jx*A(-Gnhy$iL3SwV5c#c|x+;ZTSZ&i#ym6xG-nfg2&) z-^s*TB<~T)Dken$La#-jq59a?RRcmTBJ!>$$b6K!d|;-Pw=p{v+e6>N@FAQ%os>(Q zfqj%}cROMy(b81iEU78^rDfB%`o=TH61qzh+iwJxu-#)j@8bv2^d%3uNhi(p3b-6+ zCPpTBv|k#nq)v=g58W;`G8yd*a7*kPO@rfd6~<}dHtf8siRb}(rJ>!5%~!9Yc_D0^ zwaiD@AJCzTKbJZ2X|wA4X^rV8&L=Wape4sriH;|NALi@}9r87N)yF2&dHRY7?(N<# zc{AsyKi80*JZ4&Uaj~<9({y{3d-5CH_w@Vn=HBQ)<0}<0_ZnFmk8$I*w~k`%cwo~Z zGo2FkHACiGURroYJ$)qtm}4t;$y#qZcy*QPG>xD6y_4-&jVz=U`xZgQ*%;VLivU&`1}PK||UGDx>Q9u{jm6CK^L<*ef=hu#&~d?MMFK0N61HO}zUJ&=~I zQ(c27RxUr^!&h|0#L@BZ9bSE#;C(jPl;qa1&OH9OoWFy~TICU0^n>N0_8!tDb(^^L zQ6<`>wqX%AqIE!!!LCCYu$Rb&C@!u|JFlUyBY<_)m~dE`QT0%8~vExZX+ zAFzh4`VJ?)w<`oW7Mt@pqw+*QdO}0Is1w1+QhG&*zoQ(QF&duh}O4`A5 ziXXedCD!QVCdr})CAW2IhEbzb1s}PZ8E>wvc60;DQ=ZAmwcTvG$?COS#J1uQ3@563b2~v#|h8Mf<{^7lySTh6}mgo7&Asw zs$HAGxO`q7B{vzGdlEi^7uls`En=nPtHkrkQrLkeXnNT^3Xy4Z4}AwbsvdfBalZYSCHT-%@((y{Wv=^{RXZJEnRT-GHFC zFMCL-xfmV0*>V;h_B84436?Jh>hv!w5GO7$3~TM#T=!^GYdW+F%1=a04rkZrd1+OjkJTJz=V{Ag-9U zbuKC(D@nkP#MCPx`jEme7{;V;Z|KTTt&#h}B;iQW)^&W$GuMu$a!rB5r_bNDD(FS> zeqga(y~`HCuJos@(mYjQ|O03%skp*OOSb`dMX?iL1lGln~KStlaEifwy{h@mK{Ayf{@b_qBR#0a1=YcrdLu@KKix(-Z>@-tJTOci==dV7S zGgCyl)$nx_;qAplsAw#@$x^8ndsf=`2%%}tD#zjKDeH?<8(^nl0l1{1jF*_hQk|0l z)MY*(W*(N3+h5#r4FetDX$H=ajozs_CF^?jKnnZzr$USl)}|7g!IWDQ!Xt0URVl?v z{LE9~4_;S8Pp!YG9~yZom%nF!t$Of1Y93zT)j(=5!p(i6h$-Cc+OrpKJD-pb6)*TxgamkH{R26h_y?62XO`SK0`}BFIfCQa!+#Qz{sV?y6xJ?HsQsao% zj!!I$p3rp?Tc6SZ4ylxT8^k1)<#uo5IXs%JlqIiZj*SBtuu3uJF6tOZzZ2{os+~UE zTi=t&oqBd12kLC~GglzKA+roJwIH8}*LlMJ+e)Z*1g<9D`q+#~~MhFrRz|SuX z-~;jjOs=?P5TYR1-2lkc`Xi6Z!(kpSe-rP=99Ps|>(fTe42L+oxgh7V^!`Ow1h~UJ zpubu&2(G(OPdiJfmb^5Q_;dAIP&b$d+!E>rKx$I!Zz~f*wEvafg@23nU+EpGsvo}t zKmZ|LKB0f)`%OV_KW*K2pM;O+90!~d1niQy71LNuM);g$3?uRzg7YN%w6e`P$PK6M z*`LhfNE^r{X<6O1BGK#%qvpUUCtTR}hdTGj8vs{Ylu7^d`lV{FQp$;Fnk-a}Ptz0AV|(XcI|yT1{=~&Zd6bo52_@i%jbQV&UM+Ha~VdEc=|28@(@y?G_-3UQh|g1 zBCbePE;kqqNqBg-czHl>G}4OlLyu)1YRICL6bq&i`m^VJOW2(W*!M6?;yIkXq{KPx zA29`~J+tEb@D18tO1%uv>sx&AB6g5Pn;bvO#1z_Fp)vr#9Wxetap8IKm_~qERnHxF z-{k@1mB3OBo3H-?M?s5@khR$}C;Se+n2gRDqE$=HgLBB=`l( zeutzc*r&eCf0<`&e}cz7&=dNirw9!5?U3pE(yD;d2+xxGgAS#D6W z;@@v-Oi-vLLSIcV#S5|!<>Z3#gUCOm*Ju9;-O%jWn)hSKF}ho2vQzbAzh`p`!XYy z(d^Yqe5rN?PQEmrQgDJLWj`?1TqXNS*@_5rI94nCTq;_OpXLQl7#4G2CM1lDG03eS;$(Jl?PSu}Qci zi^zHONH12}fc@-73U7_N#%D-_xk)EsOmewW?~Y`50!Eh2bprbkUDTG9J8DVubNMWF zF)u09^7Voh)3P6b>-9TgOsarr9n`C`bo)S~HiUEoFvr*$SxiYU?c0_@Mp~3LOk>g~ zpK6(?*lW6s1(A`pyp_8l&0NlU<}My2^L1$Io4aAVWFrOtdUBJW)ecjgM_Gh{m($W& z_o&shkK*^P=MS0EQ*7w*`FC;I`Q+&*mnatcDK5`4PHJdkA_dd?Uu;a0`&E13*FBQeCdOwQ*1vV!8}i53D_fN}D?Ge8Fj1FQ(D$-&qQnsgHnfR}Hb1+PKS_I_ERB zb*~67116)k;BBCsW$n=y%Nzw9)^EX3pS8>$uL4Jvxs(d|I$m%2Uerz8DT()u*$r{D z&t3r2RhBuaWhl4@H~7Nwg55@5-zS#fp37VDaAV0@$D|#GRM70Td)S26&i8Z}Q-(1s zojyuo#4A9(fytNkq}x`VJsD&)Vj>LY+K$){0%LL1hU}AgSl83(OyNkx+m%x(k%ClR z%s6h7yU~qaOJwM=p~n>K$h?7$&5NnoVIdFJ4UCOxRPX5BniBFoeZI+h`KHG5urQ`e z*Qw>{_-0X6%&R2G7P<{)%y9ey*Q+Xnuh&0*s@^P(;;7ipoQjpF5jI#S? zR1B?=`ZiATHQcl}J)R;G2Iq>q0fE%>2J{D=TB$LNN_*Lt*q5vss4#gi^ zGP6|Pj%hEXz~qeTdCi+Xuk$!@73#Ji9Q2?`7R9$BZFQo-mfVeCz$s}54VB9~roGDFS$m<7J5XKdqO2}qTGfUSg6 z;agHCg`GtQeVx}Q>Mu~4k6NEwFj~?nE|VB+2da+NJ9~Yh6BIk_`y?w6CrHgou1{`! zUL60LiA&w-VOjqD^1V@+ug4p)8IiBMi|)yPN70I6{+u<^#cvUn-y%T&jdCyej6`hz z_64RmY5~fHG4}hYd)+>xH79dSS)Qz6nwHugM(r=l4JsBW9L>?IEha}#&-wNTqo$sgMW+LK%f?xHmSZVdQdrsz(qe*F&pJ@%ab(%FsYbUZ%HzOiOu(-J+ zmUQ&w-1WU>W2uePF>3c|kyC*WeeuGUc(%3tC0x zD6f>HJKGRJxAo|{4EYqs4b3g@^E!ij1`g!ukUie02wiBJx0@WhNULs|H?CltXdAd~ za`3I&=CY@9ojSF~i7`veI0X}7@{q&QypNmrz|6tdRpaihfr6=(YxIM#lytZb=oreg z8!@*-AOqvO(LQprH&oR|(P!2p7%c2v=vizU?pxBEOGvw4dmCo_j{9OJL4@j}MYro7Ow8Zve63*b-G^HJfCt6{#UaKg z_vqbZz;nb0m}q<-yH`gKLxifdEZ^Ajr!iyq^dwn1mK%FIr;y^C>1QN|wR0{S=%qk()0_Q_nguVMAd)WnNpc{r zRyM9@Zgt&f^qqxGPF!&o=m&|Y(j)?i=nUG69Gol`%WNzbX>9kn_&BKt*JKGFhkn5r z)W^q-drQ34mb?$SPk)9JL)J1%7*a$bTzKE?r409RGy3r85N=Z_$FTqK`xdPA_<6qr zuagJHLHao4e#sa)wB*DDCRDT6p*3^P_ff?Gio;-FGmtG9Wd`4A2z4JqJ8v4ezayY1 z={^H9)3 zHX(DNsDvHgFZ3U^g+=F2vN@J*ru4`A%+8E>k#@W)({=P%dxczhdwdZKXop9bHmT8rbD>Tzm)#lzAxAH>mQcw$`3a!%0 z9;YPsdoMdJ%PhlQ2b=Vkm|q5q^_iOUls~jCg&T4|OYc-oPPJmLP@8%%MSp61TDgZi z6f5um-{b5{DP_`V<^i?7Y?pb~mqyixYF*D+-*wYh&~Y77bZ!DUw=IdvNX<1Nr`Xd# zEZpm<+%_SMv(A+T`2|cy{Vcm{$tl^R_VeBz8A^q5eLIE9*o&C7Pov+)6@l8{(O7o* zv^VBrW2HR+4pCHm(O8PLlYT1~-hX7Ngvt&(7g3^@V>f=mWN5_x#0Tyq70Pv>*9^f; zG-8>A_$oJR!f^2vHnFvQi^i7AovIfwjE2U@%YqehxhP(3IId$0V8+dYP@@a>7A;(| z`RDI;(o@Wijay3tv@m4Ix}X7xOU0M;4lv1&YTo_qslj7=uld2z2df<7v4e%UrMvGliZ|xhoi-& ziG(=Xg{$z5-jhkn3u883>?({7h4mLUpjl|Ue?1J7ywDK2ky<+r(U=%JB-$H21BRCn z$N&y0vcUbXQ^N*{+aPKvHkMdC`EgGzyY$pbiiz_}NWWRHmmfwstd{FePY->0tsNL< zyIFYr{Eqhevbl+o4FUFH&t!V>;UQyOtkGhdlAq67yv#XasAo7jnBwm9nHhV&_@V-5 zxQVSQK$r<*ZJ3Edg4JP7nsqqh@K9l?mYcn`M7V%Hbzj3;9bcdx#H}5VRq=9rHT;m~ zXs9PEYw;F{z~UP)poxw!1hW+YYSzF`p$0@vA>82$1^IBVw&fA^-c5zFW+w&pO?FXV>m>ZnU zT_@w(kE)6E=97b;#V0jeUYE!B$3F4+d@o=>!d%2P-g^;T{2Xf~xnEBpdbY1Peo2vI zr|kO8IrawBH~P+KahIl^IG@lkayz1hSIPN$&BlmTx!5I=Rc{qCOJ7rO?C3ewa!Rx> z)zMlvwbx5vnOFN;ak(ruMFr|NjA zIu{jQCv)L>yWMd_)k{xm#)9i&g&M=z9DhxywUu*Y{4-7^Q%qtRYsnqOwI$0^8sAf` z_mM^3X*K|Xj=F^ zoDjAkQMP;2@uETCK~=PblzZ+E@ur0&(p$5;1#$s|OA z-z$7c)II?kc<5BBR_dZFIo_J8&W!uN_$BF;6Qy2r~YxZcDS4WGQQ zoC~Zu2nnWrtH=Z(;Uw6b=Qfm`eUPGUqOS1dMr7<{=`k0Rm30Sql4s& z)8hsb>Vc_qFp~|EdtsG>vN4;r;}h02bBwmHy=yxr3g;FkdgeMN6w9A>USk4IoCoF& zPNJE`+ZXQ?7|JI#KpWT}r5zY4x37MifRuOO?lT?Y^mZD}zP#l-mZoiFuG+;M{<&PO z&O}^UT-B8GxNm=nyH-1kMg8eI88%KagK3W5OH!O*m6qE;XRLm-ib4$yG=?x zJa)DgXIB4)hVfavdSHO%qBhZ(Z4X;NRg)AystgjjcA9#Uh;DUP zlx=YZ4cavB-2g`#9GW0QA^@Es#uNkHjVXq3NA0NoNaHw809yP8@qK16PXkkY19QTm zhYc3G|I`#Qb~4s1v7%ryYeII5Wy05mG0A6>9GZpFOlAopW@HHz`ASiK;!N!O;Y|L) z;!G?1WJjlSf;)!jIaM)_iea5|)Y-=oE0i&kbQ^dR z6Nj5*hUnjTA5)Gj?GJ@;MFvV3I*cAxkvr9*R&p^^%FY{72MS7J$sS<37H8M!X&5^M zl}Q;Yk8ugvti5CwJmG3sh)GpW>VJHRLa)1w`zJ7fJe2+k4DbsA1%4gOgOJDT|2n@0 z{dEriUkBKTBk|w(w8`**^J4%Z%4ZREP}e4eaqT-xXWo>l=mBe$Kg#1_=0eFhv6CZO z^Ga184RLDy%wXXb=hDF^%(^U>9%Rkq;=rHasK<9@5?g;gSKcc6K}I!^4>S#9J5$I zW*~!!$a>RGa6SE&d16Q_{qzXxtY{bevB+l=*&H470 z%|%Lhy|?;;!p-<)Le^|N@vUBin?)o0xEk2uqFn+yDtAOmqxfZEyEB7hsjFjrl)-Jwo;0HGfpkPU@j4dmJo-UI~$kci3O5fmhd z^veT(;5JC!AH#WAxL=_~ItYvg`Rkjb`@$#aV2S{5dCCP;(NluZ1ii&fi95$wbQ_yHR^!Li!w!?1n|Hs0k?r#dkVe7s+OHtnYN6 z;fISji)bju;f!tzrN1?vJIwUNqjqtFJS zll{lMzuXOBZIICKX_2tyKb`O&hQDiPZ4E`@h6n`E2ngUo+#r*`p@5*jU_cz?+beq^ zph+GO0)|Bl{SRCI3dMh0A{gm5KcLM2WlNJdRp)lVjo{;q*1lB>jGjBvuL{yR&vFaI zP+C}I(@@~u4AngJxjJiTR{L`{Vw|vV%5;91r!B+yPg+hNsVEyy5l8Wz0@BEbK3=S> zIoTvW=G-acN?jJOVS9(aXhW3TPi>q9iaB6Hk!<88J_oieoeR*Yx226_TH{bY8KR0a zraZPENl(SL3N95RpZ&UNSSHamnRI=6T2P*eIzGvYvmBcwT#X$s)6Gz$`JtgNVQ!^F zi24f|leK~|rK(qOf-Z5$a5MP9a!61Z1en88}5mX`Wa62UOj7)T0MU^f%>QGK z-&ixEWDMzI2uJ-#Z1@2$|Ann1<@=}WBC&P1t5qx8Ss}yKRebx6o_ipn_P;qV`0pbi zR$}F0iKt0qvxL~eVE_;}NPrs%V6%01cX7MJgQyHZP;KB47h5|^H*Of*hW$svkwH|f zx!b{8Sfk5`ZPx@#2lYt;o5X|OE@T(>KEC~2( zsrTVfYaAc|%!>p3eE|gc`FZ&P)_|WhVIe+**^n2&`4iq_&+86lq_i&uhV8?f@j?&&a6gYz+fkIqOw8b#sTn-LE_XF`giz+>%*VT@L5} E0IK=vy8r+H literal 0 HcmV?d00001 From 7db7455c12fb9b1c06e9ffc3bc47e27ed489eff1 Mon Sep 17 00:00:00 2001 From: yetongumich Date: Sun, 12 Jul 2020 23:05:24 -0400 Subject: [PATCH 207/869] deprecate error in noisemodel, use loss instead; revise virtual with override --- gtsam/linear/NoiseModel.cpp | 36 +++--- gtsam/linear/NoiseModel.h | 172 +++++++++++++++------------- gtsam/nonlinear/NonlinearFactor.cpp | 2 +- 3 files changed, 113 insertions(+), 97 deletions(-) diff --git a/gtsam/linear/NoiseModel.cpp b/gtsam/linear/NoiseModel.cpp index ec4fd08fd..f5ec95696 100644 --- a/gtsam/linear/NoiseModel.cpp +++ b/gtsam/linear/NoiseModel.cpp @@ -74,6 +74,13 @@ Vector Base::sigmas() const { throw("Base::sigmas: sigmas() not implemented for this noise model"); } +/* ************************************************************************* */ +double Base::squaredMahalanobisDistance(const Vector& v) const { + // Note: for Diagonal, which does ediv_, will be correct for constraints + Vector w = whiten(v); + return w.dot(w); +} + /* ************************************************************************* */ Gaussian::shared_ptr Gaussian::SqrtInformation(const Matrix& R, bool smart) { size_t m = R.rows(), n = R.cols(); @@ -164,13 +171,6 @@ Vector Gaussian::unwhiten(const Vector& v) const { return backSubstituteUpper(thisR(), v); } -/* ************************************************************************* */ -double Gaussian::squaredMahalanobisDistance(const Vector& v) const { - // Note: for Diagonal, which does ediv_, will be correct for constraints - Vector w = whiten(v); - return w.dot(w); -} - /* ************************************************************************* */ Matrix Gaussian::Whiten(const Matrix& H) const { return thisR() * H; @@ -376,6 +376,7 @@ Vector Constrained::whiten(const Vector& v) const { return c; } +#ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V4 /* ************************************************************************* */ double Constrained::error(const Vector& v) const { Vector w = Diagonal::whiten(v); // get noisemodel for constrained elements @@ -384,6 +385,16 @@ double Constrained::error(const Vector& v) const { w[i] = v[i] * sqrt(mu_[i]); // TODO: may want to store sqrt rather than rebuild return 0.5 * w.dot(w); } +#endif + +/* ************************************************************************* */ +double Constrained::squaredMahalanobisDistance(const Vector& v) const { + Vector w = Diagonal::whiten(v); // get noisemodel for constrained elements + for (size_t i=0; ireweight(A1,A2,A3,b); } -Robust::shared_ptr Robust::Create(const RobustModel::shared_ptr& robust, - const noiseModel::Base::shared_ptr noise) { - SharedGaussian gaussian; - if (!(gaussian = boost::dynamic_pointer_cast(noise))) - { - throw std::invalid_argument("The noise model inside robust must be Gaussian"); - }; - return shared_ptr(new Robust(robust, gaussian)); +Robust::shared_ptr Robust::Create( +const RobustModel::shared_ptr &robust, const NoiseModel::shared_ptr noise){ + return shared_ptr(new Robust(robust,noise)); } /* ************************************************************************* */ diff --git a/gtsam/linear/NoiseModel.h b/gtsam/linear/NoiseModel.h index 449a70cf3..7494e0501 100644 --- a/gtsam/linear/NoiseModel.h +++ b/gtsam/linear/NoiseModel.h @@ -90,13 +90,26 @@ namespace gtsam { /// Unwhiten an error vector. virtual Vector unwhiten(const Vector& v) const = 0; + /// Squared Mahalanobis distance v'*R'*R*v = + virtual double squaredMahalanobisDistance(const Vector& v) const; + + /// Mahalanobis distance + virtual double mahalanobisDistance(const Vector& v) const { + return std::sqrt(squaredMahalanobisDistance(v)); + } + + /// loss function, input is Mahalanobis distance + virtual double loss(const double squared_distance) const { + return 0.5 * squared_distance; + } + +#ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V4 /// calculate the error value given measurement error vector virtual double error(const Vector& v) const = 0; -#ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V4 virtual double distance(const Vector& v) { return error(v) * 2; - } + } #endif virtual void WhitenSystem(std::vector& A, Vector& b) const = 0; @@ -207,42 +220,30 @@ namespace gtsam { */ static shared_ptr Covariance(const Matrix& covariance, bool smart = true); - virtual void print(const std::string& name) const; - virtual bool equals(const Base& expected, double tol=1e-9) const; - virtual Vector sigmas() const; - virtual Vector whiten(const Vector& v) const; - virtual Vector unwhiten(const Vector& v) const; - - /** - * Squared Mahalanobis distance v'*R'*R*v = - */ - virtual double squaredMahalanobisDistance(const Vector& v) const; - - /** - * Mahalanobis distance - */ - virtual double mahalanobisDistance(const Vector& v) const { - return std::sqrt(squaredMahalanobisDistance(v)); - } + void print(const std::string& name) const override; + bool equals(const Base& expected, double tol=1e-9) const override; + Vector sigmas() const override; + Vector whiten(const Vector& v) const override; + Vector unwhiten(const Vector& v) const override; #ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V4 virtual double Mahalanobis(const Vector& v) const { return squaredMahalanobisDistance(v); } -#endif /** * error value 0.5 * v'*R'*R*v */ - inline virtual double error(const Vector& v) const { + inline double error(const Vector& v) const override { return 0.5 * squaredMahalanobisDistance(v); } +#endif /** * Multiply a derivative with R (derivative of whiten) * Equivalent to whitening each column of the input matrix. */ - virtual Matrix Whiten(const Matrix& H) const; + Matrix Whiten(const Matrix& H) const override; /** * In-place version @@ -257,10 +258,10 @@ namespace gtsam { /** * Whiten a system, in place as well */ - virtual void WhitenSystem(std::vector& A, Vector& b) const; - virtual void WhitenSystem(Matrix& A, Vector& b) const; - virtual void WhitenSystem(Matrix& A1, Matrix& A2, Vector& b) const; - virtual void WhitenSystem(Matrix& A1, Matrix& A2, Matrix& A3, Vector& b) const; + void WhitenSystem(std::vector& A, Vector& b) const override; + void WhitenSystem(Matrix& A, Vector& b) const override; + void WhitenSystem(Matrix& A1, Matrix& A2, Vector& b) const override; + void WhitenSystem(Matrix& A1, Matrix& A2, Matrix& A3, Vector& b) const override; /** * Apply appropriately weighted QR factorization to the system [A b] @@ -345,13 +346,13 @@ namespace gtsam { return Variances(precisions.array().inverse(), smart); } - virtual void print(const std::string& name) const; - virtual Vector sigmas() const { return sigmas_; } - virtual Vector whiten(const Vector& v) const; - virtual Vector unwhiten(const Vector& v) const; - virtual Matrix Whiten(const Matrix& H) const; - virtual void WhitenInPlace(Matrix& H) const; - virtual void WhitenInPlace(Eigen::Block H) const; + void print(const std::string& name) const override; + Vector sigmas() const override { return sigmas_; } + Vector whiten(const Vector& v) const override; + Vector unwhiten(const Vector& v) const override; + Matrix Whiten(const Matrix& H) const override; + void WhitenInPlace(Matrix& H) const override; + void WhitenInPlace(Eigen::Block H) const override; /** * Return standard deviations (sqrt of diagonal) @@ -373,7 +374,7 @@ namespace gtsam { /** * Return R itself, but note that Whiten(H) is cheaper than R*H */ - virtual Matrix R() const { + Matrix R() const override { return invsigmas().asDiagonal(); } @@ -427,10 +428,10 @@ namespace gtsam { typedef boost::shared_ptr shared_ptr; - virtual ~Constrained() {} + ~Constrained() {} /// true if a constrained noise mode, saves slow/clumsy dynamic casting - virtual bool isConstrained() const { return true; } + bool isConstrained() const override { return true; } /// Return true if a particular dimension is free or constrained bool constrained(size_t i) const; @@ -482,12 +483,16 @@ namespace gtsam { return MixedVariances(precisions.array().inverse()); } +#ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V4 /** * The error function for a constrained noisemodel, * for non-constrained versions, uses sigmas, otherwise * uses the penalty function with mu */ - virtual double error(const Vector& v) const; + double error(const Vector& v) const override; +#endif + + double squaredMahalanobisDistance(const Vector& v) const override; /** Fully constrained variations */ static shared_ptr All(size_t dim) { @@ -504,16 +509,16 @@ namespace gtsam { return shared_ptr(new Constrained(Vector::Constant(dim, mu), Vector::Constant(dim,0))); } - virtual void print(const std::string& name) const; + void print(const std::string& name) const override; /// Calculates error vector with weights applied - virtual Vector whiten(const Vector& v) const; + Vector whiten(const Vector& v) const override; /// Whitening functions will perform partial whitening on rows /// with a non-zero sigma. Other rows remain untouched. - virtual Matrix Whiten(const Matrix& H) const; - virtual void WhitenInPlace(Matrix& H) const; - virtual void WhitenInPlace(Eigen::Block H) const; + Matrix Whiten(const Matrix& H) const override; + void WhitenInPlace(Matrix& H) const override; + void WhitenInPlace(Eigen::Block H) const override; /** * Apply QR factorization to the system [A b], taking into account constraints @@ -524,7 +529,7 @@ namespace gtsam { * @param Ab is the m*(n+1) augmented system matrix [A b] * @return diagonal noise model can be all zeros, mixed, or not-constrained */ - virtual Diagonal::shared_ptr QR(Matrix& Ab) const; + Diagonal::shared_ptr QR(Matrix& Ab) const override; /** * Returns a Unit version of a constrained noisemodel in which @@ -586,14 +591,14 @@ namespace gtsam { return Variance(dim, 1.0/precision, smart); } - virtual void print(const std::string& name) const; - virtual double squaredMahalanobisDistance(const Vector& v) const; - virtual Vector whiten(const Vector& v) const; - virtual Vector unwhiten(const Vector& v) const; - virtual Matrix Whiten(const Matrix& H) const; - virtual void WhitenInPlace(Matrix& H) const; - virtual void whitenInPlace(Vector& v) const; - virtual void WhitenInPlace(Eigen::Block H) const; + void print(const std::string& name) const override; + double squaredMahalanobisDistance(const Vector& v) const override; + Vector whiten(const Vector& v) const override; + Vector unwhiten(const Vector& v) const override; + Matrix Whiten(const Matrix& H) const override; + void WhitenInPlace(Matrix& H) const override; + void whitenInPlace(Vector& v) const override; + void WhitenInPlace(Eigen::Block H) const override; /** * Return standard deviation @@ -626,7 +631,7 @@ namespace gtsam { typedef boost::shared_ptr shared_ptr; - virtual ~Unit() {} + ~Unit() {} /** * Create a unit covariance noise model @@ -636,19 +641,19 @@ namespace gtsam { } /// true if a unit noise model, saves slow/clumsy dynamic casting - virtual bool isUnit() const { return true; } + bool isUnit() const override { return true; } - virtual void print(const std::string& name) const; - virtual double squaredMahalanobisDistance(const Vector& v) const {return v.dot(v); } - virtual Vector whiten(const Vector& v) const { return v; } - virtual Vector unwhiten(const Vector& v) const { return v; } - virtual Matrix Whiten(const Matrix& H) const { return H; } - virtual void WhitenInPlace(Matrix& /*H*/) const {} - virtual void WhitenInPlace(Eigen::Block /*H*/) const {} - virtual void whitenInPlace(Vector& /*v*/) const {} - virtual void unwhitenInPlace(Vector& /*v*/) const {} - virtual void whitenInPlace(Eigen::Block& /*v*/) const {} - virtual void unwhitenInPlace(Eigen::Block& /*v*/) const {} + void print(const std::string& name) const override; + double squaredMahalanobisDistance(const Vector& v) const override {return v.dot(v); } + Vector whiten(const Vector& v) const override { return v; } + Vector unwhiten(const Vector& v) const override { return v; } + Matrix Whiten(const Matrix& H) const override { return H; } + void WhitenInPlace(Matrix& /*H*/) const override {} + void WhitenInPlace(Eigen::Block /*H*/) const override {} + void whitenInPlace(Vector& /*v*/) const override {} + void unwhitenInPlace(Vector& /*v*/) const override {} + void whitenInPlace(Eigen::Block& /*v*/) const override {} + void unwhitenInPlace(Eigen::Block& /*v*/) const override {} private: /** Serialization function */ @@ -682,7 +687,7 @@ namespace gtsam { protected: typedef mEstimator::Base RobustModel; - typedef noiseModel::Gaussian NoiseModel; + typedef noiseModel::Base NoiseModel; const RobustModel::shared_ptr robust_; ///< robust error function used const NoiseModel::shared_ptr noise_; ///< noise model used @@ -697,10 +702,10 @@ namespace gtsam { : Base(noise->dim()), robust_(robust), noise_(noise) {} /// Destructor - virtual ~Robust() {} + ~Robust() {} - virtual void print(const std::string& name) const; - virtual bool equals(const Base& expected, double tol=1e-9) const; + void print(const std::string& name) const override; + bool equals(const Base& expected, double tol=1e-9) const override; /// Return the contained robust error function const RobustModel::shared_ptr& robust() const { return robust_; } @@ -709,37 +714,42 @@ namespace gtsam { const NoiseModel::shared_ptr& noise() const { return noise_; } // TODO: functions below are dummy but necessary for the noiseModel::Base - inline virtual Vector whiten(const Vector& v) const + inline Vector whiten(const Vector& v) const override { Vector r = v; this->WhitenSystem(r); return r; } - inline virtual Matrix Whiten(const Matrix& A) const + inline Matrix Whiten(const Matrix& A) const override { Vector b; Matrix B=A; this->WhitenSystem(B,b); return B; } - inline virtual Vector unwhiten(const Vector& /*v*/) const + inline Vector unwhiten(const Vector& /*v*/) const override { throw std::invalid_argument("unwhiten is not currently supported for robust noise models."); } #ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V4 - inline virtual double distance(const Vector& v) { + inline double distance(const Vector& v) override { return robust_->loss(this->unweightedWhiten(v).norm()); } -#endif // Fold the use of the m-estimator loss(...) function into error(...) - inline virtual double error(const Vector& v) const + inline double error(const Vector& v) const override { return robust_->loss(noise_->mahalanobisDistance(v)); } +#endif + + double loss(const double squared_distance) const override { + return robust_->loss(std::sqrt(squared_distance)); + } + // TODO: these are really robust iterated re-weighting support functions virtual void WhitenSystem(Vector& b) const; - virtual void WhitenSystem(std::vector& A, Vector& b) const; - virtual void WhitenSystem(Matrix& A, Vector& b) const; - virtual void WhitenSystem(Matrix& A1, Matrix& A2, Vector& b) const; - virtual void WhitenSystem(Matrix& A1, Matrix& A2, Matrix& A3, Vector& b) const; + void WhitenSystem(std::vector& A, Vector& b) const override; + void WhitenSystem(Matrix& A, Vector& b) const override; + void WhitenSystem(Matrix& A1, Matrix& A2, Vector& b) const override; + void WhitenSystem(Matrix& A1, Matrix& A2, Matrix& A3, Vector& b) const override; - virtual Vector unweightedWhiten(const Vector& v) const { + Vector unweightedWhiten(const Vector& v) const override { return noise_->unweightedWhiten(v); } - virtual double weight(const Vector& v) const { + double weight(const Vector& v) const override { // Todo(mikebosse): make the robust weight function input a vector. return robust_->weight(v.norm()); } static shared_ptr Create( - const RobustModel::shared_ptr &robust, const noiseModel::Base::shared_ptr noise); + const RobustModel::shared_ptr &robust, const NoiseModel::shared_ptr noise); private: /** Serialization function */ diff --git a/gtsam/nonlinear/NonlinearFactor.cpp b/gtsam/nonlinear/NonlinearFactor.cpp index 40fc1c427..1cfcba274 100644 --- a/gtsam/nonlinear/NonlinearFactor.cpp +++ b/gtsam/nonlinear/NonlinearFactor.cpp @@ -121,7 +121,7 @@ double NoiseModelFactor::error(const Values& c) const { const Vector b = unwhitenedError(c); check(noiseModel_, b.size()); if (noiseModel_) - return noiseModel_->error(b); + return noiseModel_->loss(noiseModel_->squaredMahalanobisDistance(b)); else return 0.5 * b.squaredNorm(); } else { From ec993497f322df8b8c3dbbbfeef80d59c397405c Mon Sep 17 00:00:00 2001 From: yetongumich Date: Sun, 12 Jul 2020 23:09:13 -0400 Subject: [PATCH 208/869] deprecate error in noisemodel, use loss instead; revise virtual with override --- gtsam/linear/JacobianFactor.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/gtsam/linear/JacobianFactor.cpp b/gtsam/linear/JacobianFactor.cpp index be9b17052..b8a08be9e 100644 --- a/gtsam/linear/JacobianFactor.cpp +++ b/gtsam/linear/JacobianFactor.cpp @@ -515,7 +515,7 @@ Vector JacobianFactor::error_vector(const VectorValues& c) const { double JacobianFactor::error(const VectorValues& c) const { Vector e = unweighted_error(c); // Use the noise model distance function to get the correct error if available. - if (model_) return model_->error(e); + if (model_) return 0.5 * model_->squaredMahalanobisDistance(e); return 0.5 * e.dot(e); } From ec69c7a2a9db299f9ba692a4879d656c243db35f Mon Sep 17 00:00:00 2001 From: Frank dellaert Date: Sun, 12 Jul 2020 16:03:48 -0400 Subject: [PATCH 209/869] Extra tests on frontal keys --- gtsam/discrete/tests/testDiscreteBayesTree.cpp | 6 ++++++ 1 file changed, 6 insertions(+) diff --git a/gtsam/discrete/tests/testDiscreteBayesTree.cpp b/gtsam/discrete/tests/testDiscreteBayesTree.cpp index 9950c014e..6823d3c04 100644 --- a/gtsam/discrete/tests/testDiscreteBayesTree.cpp +++ b/gtsam/discrete/tests/testDiscreteBayesTree.cpp @@ -80,6 +80,12 @@ TEST_UNSAFE(DiscreteBayesTree, ThinTree) { bayesTree->saveGraph("/tmp/discreteBayesTree.dot"); } + // Check frontals and parents + for (size_t i : {13, 14, 9, 3, 2, 8, 1, 0, 10, 5, 4}) { + auto clique_i = (*bayesTree)[i]; + EXPECT_LONGS_EQUAL(i, *(clique_i->conditional_->beginFrontals())); + } + auto R = bayesTree->roots().front(); // Check whether BN and BT give the same answer on all configurations From 8666a15f2e388651e9ab50de59423989a5fec189 Mon Sep 17 00:00:00 2001 From: Frank dellaert Date: Sun, 12 Jul 2020 16:04:01 -0400 Subject: [PATCH 210/869] Some more refactoring of marginals --- .../discrete/tests/testDiscreteBayesTree.cpp | 58 ++++++++++--------- 1 file changed, 32 insertions(+), 26 deletions(-) diff --git a/gtsam/discrete/tests/testDiscreteBayesTree.cpp b/gtsam/discrete/tests/testDiscreteBayesTree.cpp index 6823d3c04..11a88af59 100644 --- a/gtsam/discrete/tests/testDiscreteBayesTree.cpp +++ b/gtsam/discrete/tests/testDiscreteBayesTree.cpp @@ -110,16 +110,22 @@ TEST_UNSAFE(DiscreteBayesTree, ThinTree) { double px = bayesTree->evaluate(x); for (size_t i = 0; i < 15; i++) if (x[i]) marginals[i] += px; - if (x[12] && x[14]) joint_12_14 += px; - if (x[9] && x[12] && x[14]) joint_9_12_14 += px; - if (x[8] && x[12] && x[14]) joint_8_12_14 += px; + if (x[12] && x[14]) { + joint_12_14 += px; + if (x[9]) joint_9_12_14 += px; + if (x[8]) joint_8_12_14 += px; + } if (x[8] && x[12]) joint_8_12 += px; - if (x[8] && x[2]) joint82 += px; - if (x[1] && x[2]) joint12 += px; - if (x[2] && x[4]) joint24 += px; - if (x[4] && x[5]) joint45 += px; - if (x[4] && x[6]) joint46 += px; - if (x[4] && x[11]) joint_4_11 += px; + if (x[2]) { + if (x[8]) joint82 += px; + if (x[1]) joint12 += px; + } + if (x[4]) { + if (x[2]) joint24 += px; + if (x[5]) joint45 += px; + if (x[6]) joint46 += px; + if (x[11]) joint_4_11 += px; + } if (x[11] && x[13]) { joint_11_13 += px; if (x[8] && x[12]) joint_8_11_12_13 += px; @@ -135,50 +141,50 @@ TEST_UNSAFE(DiscreteBayesTree, ThinTree) { DiscreteFactor::Values all1 = allPosbValues.back(); // check separator marginal P(S0) - auto c = (*bayesTree)[0]; + auto clique = (*bayesTree)[0]; DiscreteFactorGraph separatorMarginal0 = - c->separatorMarginal(EliminateDiscrete); + clique->separatorMarginal(EliminateDiscrete); DOUBLES_EQUAL(joint_8_12, separatorMarginal0(all1), 1e-9); // check separator marginal P(S9), should be P(14) - c = (*bayesTree)[9]; + clique = (*bayesTree)[9]; DiscreteFactorGraph separatorMarginal9 = - c->separatorMarginal(EliminateDiscrete); + clique->separatorMarginal(EliminateDiscrete); DOUBLES_EQUAL(marginals[14], separatorMarginal9(all1), 1e-9); // check separator marginal of root, should be empty - c = (*bayesTree)[11]; + clique = (*bayesTree)[11]; DiscreteFactorGraph separatorMarginal11 = - c->separatorMarginal(EliminateDiscrete); + clique->separatorMarginal(EliminateDiscrete); LONGS_EQUAL(0, separatorMarginal11.size()); // check shortcut P(S9||R) to root - c = (*bayesTree)[9]; - DiscreteBayesNet shortcut = c->shortcut(R, EliminateDiscrete); + clique = (*bayesTree)[9]; + DiscreteBayesNet shortcut = clique->shortcut(R, EliminateDiscrete); LONGS_EQUAL(1, shortcut.size()); DOUBLES_EQUAL(joint_11_13_14 / joint_11_13, shortcut.evaluate(all1), 1e-9); // check shortcut P(S8||R) to root - c = (*bayesTree)[8]; - shortcut = c->shortcut(R, EliminateDiscrete); + clique = (*bayesTree)[8]; + shortcut = clique->shortcut(R, EliminateDiscrete); DOUBLES_EQUAL(joint_11_12_13_14 / joint_11_13, shortcut.evaluate(all1), 1e-9); // check shortcut P(S2||R) to root - c = (*bayesTree)[2]; - shortcut = c->shortcut(R, EliminateDiscrete); + clique = (*bayesTree)[2]; + shortcut = clique->shortcut(R, EliminateDiscrete); DOUBLES_EQUAL(joint_9_11_12_13 / joint_11_13, shortcut.evaluate(all1), 1e-9); // check shortcut P(S0||R) to root - c = (*bayesTree)[0]; - shortcut = c->shortcut(R, EliminateDiscrete); + clique = (*bayesTree)[0]; + shortcut = clique->shortcut(R, EliminateDiscrete); DOUBLES_EQUAL(joint_8_11_12_13 / joint_11_13, shortcut.evaluate(all1), 1e-9); // calculate all shortcuts to root DiscreteBayesTree::Nodes cliques = bayesTree->nodes(); - for (auto c : cliques) { - DiscreteBayesNet shortcut = c.second->shortcut(R, EliminateDiscrete); + for (auto clique : cliques) { + DiscreteBayesNet shortcut = clique.second->shortcut(R, EliminateDiscrete); if (debug) { - c.second->conditional_->printSignature(); + clique.second->conditional_->printSignature(); shortcut.print("shortcut:"); } } From 9c5bba753cc8d9a1c21b8d14cd24f08bb1688239 Mon Sep 17 00:00:00 2001 From: Frank dellaert Date: Sun, 12 Jul 2020 12:28:43 -0400 Subject: [PATCH 211/869] Fix confusion between parents and frontals --- gtsam/discrete/DiscreteConditional.h | 16 +++++++++ gtsam/discrete/tests/testDiscreteBayesNet.cpp | 36 ++++++++++++++++++- .../tests/testDiscreteConditional.cpp | 5 +++ 3 files changed, 56 insertions(+), 1 deletion(-) diff --git a/gtsam/discrete/DiscreteConditional.h b/gtsam/discrete/DiscreteConditional.h index 225e6e1d3..b1e9da754 100644 --- a/gtsam/discrete/DiscreteConditional.h +++ b/gtsam/discrete/DiscreteConditional.h @@ -90,6 +90,22 @@ public: /// GTSAM-style equals bool equals(const DiscreteFactor& other, double tol = 1e-9) const; + /// @} + /// @name Parent keys are stored *first* in a DiscreteConditional, so re-jigger: + /// @{ + + /** Iterator pointing to first frontal key. */ + typename DecisionTreeFactor::const_iterator beginFrontals() const { return endParents(); } + + /** Iterator pointing past the last frontal key. */ + typename DecisionTreeFactor::const_iterator endFrontals() const { return end(); } + + /** Iterator pointing to the first parent key. */ + typename DecisionTreeFactor::const_iterator beginParents() const { return begin(); } + + /** Iterator pointing past the last parent key. */ + typename DecisionTreeFactor::const_iterator endParents() const { return end() - nrFrontals_; } + /// @} /// @name Standard Interface /// @{ diff --git a/gtsam/discrete/tests/testDiscreteBayesNet.cpp b/gtsam/discrete/tests/testDiscreteBayesNet.cpp index 5ed662332..c3f8aacf1 100644 --- a/gtsam/discrete/tests/testDiscreteBayesNet.cpp +++ b/gtsam/discrete/tests/testDiscreteBayesNet.cpp @@ -18,8 +18,10 @@ #include #include -#include +#include #include +#include +#include #include @@ -29,10 +31,42 @@ using namespace boost::assign; #include +#include +#include using namespace std; using namespace gtsam; +/* ************************************************************************* */ +TEST(DiscreteBayesNet, bayesNet) { + DiscreteBayesNet bayesNet; + DiscreteKey Parent(0, 2), Child(1, 2); + + auto prior = boost::make_shared(Parent % "6/4"); + CHECK(assert_equal(Potentials::ADT({Parent}, "0.6 0.4"), + (Potentials::ADT)*prior)); + bayesNet.push_back(prior); + + auto conditional = + boost::make_shared(Child | Parent = "7/3 8/2"); + EXPECT_LONGS_EQUAL(1, *(conditional->beginFrontals())); + Potentials::ADT expected(Child & Parent, "0.7 0.8 0.3 0.2"); + CHECK(assert_equal(expected, (Potentials::ADT)*conditional)); + bayesNet.push_back(conditional); + + DiscreteFactorGraph fg(bayesNet); + LONGS_EQUAL(2, fg.back()->size()); + + // Check the marginals + const double expectedMarginal[2]{0.4, 0.6 * 0.3 + 0.4 * 0.2}; + DiscreteMarginals marginals(fg); + for (size_t j = 0; j < 2; j++) { + Vector FT = marginals.marginalProbabilities(DiscreteKey(j, 2)); + EXPECT_DOUBLES_EQUAL(expectedMarginal[j], FT[1], 1e-3); + EXPECT_DOUBLES_EQUAL(FT[0], 1.0 - FT[1], 1e-9); + } +} + /* ************************************************************************* */ TEST(DiscreteBayesNet, Asia) { diff --git a/gtsam/discrete/tests/testDiscreteConditional.cpp b/gtsam/discrete/tests/testDiscreteConditional.cpp index 888bf76df..577edecb3 100644 --- a/gtsam/discrete/tests/testDiscreteConditional.cpp +++ b/gtsam/discrete/tests/testDiscreteConditional.cpp @@ -36,6 +36,11 @@ TEST( DiscreteConditional, constructors) DiscreteConditional::shared_ptr expected1 = // boost::make_shared(X | Y = "1/1 2/3 1/4"); EXPECT(expected1); + EXPECT_LONGS_EQUAL(0, *(expected1->beginFrontals())); + EXPECT_LONGS_EQUAL(2, *(expected1->beginParents())); + EXPECT(expected1->endParents() == expected1->beginFrontals()); + EXPECT(expected1->endFrontals() == expected1->end()); + DecisionTreeFactor f1(X & Y, "0.5 0.4 0.2 0.5 0.6 0.8"); DiscreteConditional actual1(1, f1); EXPECT(assert_equal(*expected1, actual1, 1e-9)); From 1ffddf72e1e3ef3a6b60ba35f35f09817bf26f1c Mon Sep 17 00:00:00 2001 From: Frank dellaert Date: Sun, 12 Jul 2020 16:50:55 -0400 Subject: [PATCH 212/869] Added code to re-jigger Signature cpt so that frontal keys are always first, consistent with how the DiscreteElimination function works. --- gtsam/discrete/DiscreteConditional.cpp | 7 ++-- gtsam/discrete/DiscreteConditional.h | 16 -------- gtsam/discrete/Signature.cpp | 18 +++++---- gtsam/discrete/Signature.h | 4 +- .../tests/testAlgebraicDecisionTree.cpp | 7 ++-- .../tests/testDiscreteConditional.cpp | 4 +- gtsam/discrete/tests/testSignature.cpp | 38 ++++++++++--------- 7 files changed, 42 insertions(+), 52 deletions(-) diff --git a/gtsam/discrete/DiscreteConditional.cpp b/gtsam/discrete/DiscreteConditional.cpp index 2ab3054a8..b5b5c0dbc 100644 --- a/gtsam/discrete/DiscreteConditional.cpp +++ b/gtsam/discrete/DiscreteConditional.cpp @@ -61,10 +61,9 @@ DiscreteConditional::DiscreteConditional(const DecisionTreeFactor& joint, } /* ******************************************************************************** */ -DiscreteConditional::DiscreteConditional(const Signature& signature) : - BaseFactor(signature.discreteKeysParentsFirst(), signature.cpt()), BaseConditional( - 1) { -} +DiscreteConditional::DiscreteConditional(const Signature& signature) + : BaseFactor(signature.discreteKeys(), signature.cpt()), + BaseConditional(1) {} /* ******************************************************************************** */ void DiscreteConditional::print(const std::string& s, diff --git a/gtsam/discrete/DiscreteConditional.h b/gtsam/discrete/DiscreteConditional.h index b1e9da754..225e6e1d3 100644 --- a/gtsam/discrete/DiscreteConditional.h +++ b/gtsam/discrete/DiscreteConditional.h @@ -90,22 +90,6 @@ public: /// GTSAM-style equals bool equals(const DiscreteFactor& other, double tol = 1e-9) const; - /// @} - /// @name Parent keys are stored *first* in a DiscreteConditional, so re-jigger: - /// @{ - - /** Iterator pointing to first frontal key. */ - typename DecisionTreeFactor::const_iterator beginFrontals() const { return endParents(); } - - /** Iterator pointing past the last frontal key. */ - typename DecisionTreeFactor::const_iterator endFrontals() const { return end(); } - - /** Iterator pointing to the first parent key. */ - typename DecisionTreeFactor::const_iterator beginParents() const { return begin(); } - - /** Iterator pointing past the last parent key. */ - typename DecisionTreeFactor::const_iterator endParents() const { return end() - nrFrontals_; } - /// @} /// @name Standard Interface /// @{ diff --git a/gtsam/discrete/Signature.cpp b/gtsam/discrete/Signature.cpp index 89e763703..94b160a29 100644 --- a/gtsam/discrete/Signature.cpp +++ b/gtsam/discrete/Signature.cpp @@ -122,28 +122,30 @@ namespace gtsam { key_(key) { } - DiscreteKeys Signature::discreteKeysParentsFirst() const { + DiscreteKeys Signature::discreteKeys() const { DiscreteKeys keys; - for(const DiscreteKey& key: parents_) - keys.push_back(key); keys.push_back(key_); + for (const DiscreteKey& key : parents_) keys.push_back(key); return keys; } KeyVector Signature::indices() const { KeyVector js; js.push_back(key_.first); - for(const DiscreteKey& key: parents_) - js.push_back(key.first); + for (const DiscreteKey& key : parents_) js.push_back(key.first); return js; } vector Signature::cpt() const { vector cpt; if (table_) { - for(const Row& row: *table_) - for(const double& x: row) - cpt.push_back(x); + const size_t nrStates = table_->at(0).size(); + for (size_t j = 0; j < nrStates; j++) { + for (const Row& row : *table_) { + assert(row.size() == nrStates); + cpt.push_back(row[j]); + } + } } return cpt; } diff --git a/gtsam/discrete/Signature.h b/gtsam/discrete/Signature.h index 587cd6b30..6c59b5bff 100644 --- a/gtsam/discrete/Signature.h +++ b/gtsam/discrete/Signature.h @@ -86,8 +86,8 @@ namespace gtsam { return parents_; } - /** All keys, with variable key last */ - DiscreteKeys discreteKeysParentsFirst() const; + /** All keys, with variable key first */ + DiscreteKeys discreteKeys() const; /** All key indices, with variable key first */ KeyVector indices() const; diff --git a/gtsam/discrete/tests/testAlgebraicDecisionTree.cpp b/gtsam/discrete/tests/testAlgebraicDecisionTree.cpp index 753af16d8..0261ef833 100644 --- a/gtsam/discrete/tests/testAlgebraicDecisionTree.cpp +++ b/gtsam/discrete/tests/testAlgebraicDecisionTree.cpp @@ -132,7 +132,7 @@ TEST(ADT, example3) /** Convert Signature into CPT */ ADT create(const Signature& signature) { - ADT p(signature.discreteKeysParentsFirst(), signature.cpt()); + ADT p(signature.discreteKeys(), signature.cpt()); static size_t count = 0; const DiscreteKey& key = signature.key(); string dotfile = (boost::format("CPT-%03d-%d") % ++count % key.first).str(); @@ -181,19 +181,20 @@ TEST(ADT, joint) dot(joint, "Asia-ASTLBEX"); joint = apply(joint, pD, &mul); dot(joint, "Asia-ASTLBEXD"); - EXPECT_LONGS_EQUAL(346, (long)muls); + EXPECT_LONGS_EQUAL(346, muls); gttoc_(asiaJoint); tictoc_getNode(asiaJointNode, asiaJoint); elapsed = asiaJointNode->secs() + asiaJointNode->wall(); tictoc_reset_(); printCounts("Asia joint"); + // Form P(A,S,T,L) = P(A) P(S) P(T|A) P(L|S) ADT pASTL = pA; pASTL = apply(pASTL, pS, &mul); pASTL = apply(pASTL, pT, &mul); pASTL = apply(pASTL, pL, &mul); - // test combine + // test combine to check that P(A) = \sum_{S,T,L} P(A,S,T,L) ADT fAa = pASTL.combine(L, &add_).combine(T, &add_).combine(S, &add_); EXPECT(assert_equal(pA, fAa)); ADT fAb = pASTL.combine(S, &add_).combine(T, &add_).combine(L, &add_); diff --git a/gtsam/discrete/tests/testDiscreteConditional.cpp b/gtsam/discrete/tests/testDiscreteConditional.cpp index 577edecb3..749186d14 100644 --- a/gtsam/discrete/tests/testDiscreteConditional.cpp +++ b/gtsam/discrete/tests/testDiscreteConditional.cpp @@ -38,8 +38,8 @@ TEST( DiscreteConditional, constructors) EXPECT(expected1); EXPECT_LONGS_EQUAL(0, *(expected1->beginFrontals())); EXPECT_LONGS_EQUAL(2, *(expected1->beginParents())); - EXPECT(expected1->endParents() == expected1->beginFrontals()); - EXPECT(expected1->endFrontals() == expected1->end()); + EXPECT(expected1->endParents() == expected1->end()); + EXPECT(expected1->endFrontals() == expected1->beginParents()); DecisionTreeFactor f1(X & Y, "0.5 0.4 0.2 0.5 0.6 0.8"); DiscreteConditional actual1(1, f1); diff --git a/gtsam/discrete/tests/testSignature.cpp b/gtsam/discrete/tests/testSignature.cpp index de47a00f3..830fc32fc 100644 --- a/gtsam/discrete/tests/testSignature.cpp +++ b/gtsam/discrete/tests/testSignature.cpp @@ -11,36 +11,37 @@ /** * @file testSignature - * @brief Tests focusing on the details of Signatures to evaluate boost compliance + * @brief Tests focusing on the details of Signatures to evaluate boost + * compliance * @author Alex Cunningham * @date Sept 19th 2011 */ -#include #include - #include #include +#include + using namespace std; using namespace gtsam; using namespace boost::assign; -DiscreteKey X(0,2), Y(1,3), Z(2,2); +DiscreteKey X(0, 2), Y(1, 3), Z(2, 2); /* ************************************************************************* */ TEST(testSignature, simple_conditional) { Signature sig(X | Y = "1/1 2/3 1/4"); DiscreteKey actKey = sig.key(); - LONGS_EQUAL((long)X.first, (long)actKey.first); + LONGS_EQUAL(X.first, actKey.first); - DiscreteKeys actKeys = sig.discreteKeysParentsFirst(); - LONGS_EQUAL(2, (long)actKeys.size()); - LONGS_EQUAL((long)Y.first, (long)actKeys.front().first); - LONGS_EQUAL((long)X.first, (long)actKeys.back().first); + DiscreteKeys actKeys = sig.discreteKeys(); + LONGS_EQUAL(2, actKeys.size()); + LONGS_EQUAL(X.first, actKeys.front().first); + LONGS_EQUAL(Y.first, actKeys.back().first); vector actCpt = sig.cpt(); - EXPECT_LONGS_EQUAL(6, (long)actCpt.size()); + EXPECT_LONGS_EQUAL(6, actCpt.size()); } /* ************************************************************************* */ @@ -54,17 +55,20 @@ TEST(testSignature, simple_conditional_nonparser) { Signature sig(X | Y = table); DiscreteKey actKey = sig.key(); - EXPECT_LONGS_EQUAL((long)X.first, (long)actKey.first); + EXPECT_LONGS_EQUAL(X.first, actKey.first); - DiscreteKeys actKeys = sig.discreteKeysParentsFirst(); - LONGS_EQUAL(2, (long)actKeys.size()); - LONGS_EQUAL((long)Y.first, (long)actKeys.front().first); - LONGS_EQUAL((long)X.first, (long)actKeys.back().first); + DiscreteKeys actKeys = sig.discreteKeys(); + LONGS_EQUAL(2, actKeys.size()); + LONGS_EQUAL(X.first, actKeys.front().first); + LONGS_EQUAL(Y.first, actKeys.back().first); vector actCpt = sig.cpt(); - EXPECT_LONGS_EQUAL(6, (long)actCpt.size()); + EXPECT_LONGS_EQUAL(6, actCpt.size()); } /* ************************************************************************* */ -int main() { TestResult tr; return TestRegistry::runAllTests(tr); } +int main() { + TestResult tr; + return TestRegistry::runAllTests(tr); +} /* ************************************************************************* */ From 7dba3023d6f6057762ff80ec05d3e716c976e59b Mon Sep 17 00:00:00 2001 From: Frank dellaert Date: Sat, 11 Jul 2020 13:16:08 -0400 Subject: [PATCH 213/869] New discrete example --- examples/DiscreteBayesNetExample.cpp | 82 ++++++++++++++++++++++++++++ examples/DiscreteBayesNet_FG.cpp | 2 +- 2 files changed, 83 insertions(+), 1 deletion(-) create mode 100644 examples/DiscreteBayesNetExample.cpp diff --git a/examples/DiscreteBayesNetExample.cpp b/examples/DiscreteBayesNetExample.cpp new file mode 100644 index 000000000..3531fd723 --- /dev/null +++ b/examples/DiscreteBayesNetExample.cpp @@ -0,0 +1,82 @@ +/* ---------------------------------------------------------------------------- + + * GTSAM Copyright 2010, Georgia Tech Research Corporation, + * Atlanta, Georgia 30332-0415 + * All Rights Reserved + * Authors: Frank Dellaert, et al. (see THANKS for the full author list) + + * See LICENSE for the license information + + * -------------------------------------------------------------------------- */ + +/** + * @file DiscreteBayesNetExample.cpp + * @brief Discrete Bayes Net example with famous Asia Bayes Network + * @author Frank Dellaert + * @date JULY 10, 2020 + */ + +#include +#include + +#include + +using namespace std; +using namespace gtsam; + +int main(int argc, char **argv) { + DiscreteBayesNet asia; + DiscreteKey Asia(0, 2), Smoking(4, 2), Tuberculosis(3, 2), LungCancer(6, 2), + Bronchitis(7, 2), Either(5, 2), XRay(2, 2), Dyspnea(1, 2); + asia.add(Asia % "99/1"); + asia.add(Smoking % "50/50"); + + asia.add(Tuberculosis | Asia = "99/1 95/5"); + asia.add(LungCancer | Smoking = "99/1 90/10"); + asia.add(Bronchitis | Smoking = "70/30 40/60"); + + asia.add((Either | Tuberculosis, LungCancer) = "F T T T"); + + asia.add(XRay | Either = "95/5 2/98"); + asia.add((Dyspnea | Either, Bronchitis) = "9/1 2/8 3/7 1/9"); + + // print + vector pretty = {"Asia", "Dyspnea", "XRay", "Tuberculosis", + "Smoking", "Either", "LungCancer", "Bronchitis"}; + auto formatter = [pretty](Key key) { return pretty[key]; }; + asia.print("Asia", formatter); + + // Convert to factor graph + DiscreteFactorGraph fg(asia); + + // Create solver and eliminate + Ordering ordering; + ordering += Key(0), Key(1), Key(2), Key(3), Key(4), Key(5), Key(6), Key(7); + DiscreteBayesNet::shared_ptr chordal = fg.eliminateSequential(ordering); + + // solve + DiscreteFactor::sharedValues mpe = chordal->optimize(); + GTSAM_PRINT(*mpe); + + // We can also build a Bayes tree (directed junction tree). + // The elimination order above will do fine: + auto bayesTree = fg.eliminateMultifrontal(ordering); + bayesTree->print("bayesTree", formatter); + + // add evidence, we were in Asia and we have dyspnea + fg.add(Asia, "0 1"); + fg.add(Dyspnea, "0 1"); + + // solve again, now with evidence + DiscreteBayesNet::shared_ptr chordal2 = fg.eliminateSequential(ordering); + DiscreteFactor::sharedValues mpe2 = chordal2->optimize(); + GTSAM_PRINT(*mpe2); + + // We can also sample from it + cout << "\n10 samples:" << endl; + for (size_t i = 0; i < 10; i++) { + DiscreteFactor::sharedValues sample = chordal2->sample(); + GTSAM_PRINT(*sample); + } + return 0; +} diff --git a/examples/DiscreteBayesNet_FG.cpp b/examples/DiscreteBayesNet_FG.cpp index 9802b5984..121df4bef 100644 --- a/examples/DiscreteBayesNet_FG.cpp +++ b/examples/DiscreteBayesNet_FG.cpp @@ -10,7 +10,7 @@ * -------------------------------------------------------------------------- */ /** - * @file DiscreteBayesNet_graph.cpp + * @file DiscreteBayesNet_FG.cpp * @brief Discrete Bayes Net example using Factor Graphs * @author Abhijit * @date Jun 4, 2012 From 550dc377e3703fd13e2ec5f7a121a3067b5ac2e1 Mon Sep 17 00:00:00 2001 From: Frank dellaert Date: Sat, 11 Jul 2020 13:16:35 -0400 Subject: [PATCH 214/869] Better print --- gtsam/discrete/DiscreteConditional.cpp | 20 ++++++++++++++++---- 1 file changed, 16 insertions(+), 4 deletions(-) diff --git a/gtsam/discrete/DiscreteConditional.cpp b/gtsam/discrete/DiscreteConditional.cpp index b5b5c0dbc..acd0cefee 100644 --- a/gtsam/discrete/DiscreteConditional.cpp +++ b/gtsam/discrete/DiscreteConditional.cpp @@ -27,6 +27,7 @@ #include #include #include +#include #include using namespace std; @@ -66,10 +67,21 @@ DiscreteConditional::DiscreteConditional(const Signature& signature) BaseConditional(1) {} /* ******************************************************************************** */ -void DiscreteConditional::print(const std::string& s, - const KeyFormatter& formatter) const { - std::cout << s << std::endl; - Potentials::print(s); +void DiscreteConditional::print(const string& s, + const KeyFormatter& formatter) const { + cout << s << " P( "; + for (const_iterator it = beginFrontals(); it != endFrontals(); ++it) { + cout << formatter(*it) << " "; + } + if (nrParents()) { + cout << "| "; + for (const_iterator it = beginParents(); it != endParents(); ++it) { + cout << formatter(*it) << " "; + } + } + cout << ")"; + Potentials::print(""); + cout << endl; } /* ******************************************************************************** */ From 4c7ba2a98f7012199b9c3bbf16f03b2fe946cd93 Mon Sep 17 00:00:00 2001 From: Frank dellaert Date: Sat, 11 Jul 2020 13:18:48 -0400 Subject: [PATCH 215/869] Cleaned up tests --- gtsam/discrete/tests/testDiscreteBayesNet.cpp | 90 +++++++++---------- .../tests/testDiscreteConditional.cpp | 71 +++++++-------- .../discrete/tests/testDiscreteMarginals.cpp | 42 +++++---- gtsam/discrete/tests/testSignature.cpp | 6 ++ 4 files changed, 100 insertions(+), 109 deletions(-) diff --git a/gtsam/discrete/tests/testDiscreteBayesNet.cpp b/gtsam/discrete/tests/testDiscreteBayesNet.cpp index c3f8aacf1..2b440e5a0 100644 --- a/gtsam/discrete/tests/testDiscreteBayesNet.cpp +++ b/gtsam/discrete/tests/testDiscreteBayesNet.cpp @@ -25,8 +25,9 @@ #include -#include + #include +#include using namespace boost::assign; @@ -68,94 +69,84 @@ TEST(DiscreteBayesNet, bayesNet) { } /* ************************************************************************* */ -TEST(DiscreteBayesNet, Asia) -{ +TEST(DiscreteBayesNet, Asia) { DiscreteBayesNet asia; -// DiscreteKey A("Asia"), S("Smoking"), T("Tuberculosis"), L("LungCancer"), B( -// "Bronchitis"), E("Either"), X("XRay"), D("Dyspnoea"); - DiscreteKey A(0,2), S(4,2), T(3,2), L(6,2), B(7,2), E(5,2), X(2,2), D(1,2); + DiscreteKey Asia(0, 2), Smoking(4, 2), Tuberculosis(3, 2), LungCancer(6, 2), + Bronchitis(7, 2), Either(5, 2), XRay(2, 2), Dyspnea(1, 2); - // TODO: make a version that doesn't use the parser - asia.add(A % "99/1"); - asia.add(S % "50/50"); + asia.add(Asia % "99/1"); + asia.add(Smoking % "50/50"); - asia.add(T | A = "99/1 95/5"); - asia.add(L | S = "99/1 90/10"); - asia.add(B | S = "70/30 40/60"); + asia.add(Tuberculosis | Asia = "99/1 95/5"); + asia.add(LungCancer | Smoking = "99/1 90/10"); + asia.add(Bronchitis | Smoking = "70/30 40/60"); - asia.add((E | T, L) = "F T T T"); + asia.add((Either | Tuberculosis, LungCancer) = "F T T T"); - asia.add(X | E = "95/5 2/98"); - // next lines are same as asia.add((D | E, B) = "9/1 2/8 3/7 1/9"); - DiscreteConditional::shared_ptr actual = - boost::make_shared((D | E, B) = "9/1 2/8 3/7 1/9"); - asia.push_back(actual); - // GTSAM_PRINT(asia); + asia.add(XRay | Either = "95/5 2/98"); + asia.add((Dyspnea | Either, Bronchitis) = "9/1 2/8 3/7 1/9"); // Convert to factor graph DiscreteFactorGraph fg(asia); -// GTSAM_PRINT(fg); - LONGS_EQUAL(3,fg.back()->size()); - Potentials::ADT expected(B & D & E, "0.9 0.3 0.1 0.7 0.2 0.1 0.8 0.9"); - CHECK(assert_equal(expected,(Potentials::ADT)*actual)); + LONGS_EQUAL(3, fg.back()->size()); + + // Check the marginals we know (of the parent-less nodes) + DiscreteMarginals marginals(fg); + Vector2 va(0.99, 0.01), vs(0.5, 0.5); + EXPECT(assert_equal(va, marginals.marginalProbabilities(Asia))); + EXPECT(assert_equal(vs, marginals.marginalProbabilities(Smoking))); // Create solver and eliminate Ordering ordering; - ordering += Key(0),Key(1),Key(2),Key(3),Key(4),Key(5),Key(6),Key(7); + ordering += Key(0), Key(1), Key(2), Key(3), Key(4), Key(5), Key(6), Key(7); DiscreteBayesNet::shared_ptr chordal = fg.eliminateSequential(ordering); -// GTSAM_PRINT(*chordal); - DiscreteConditional expected2(B % "11/9"); - CHECK(assert_equal(expected2,*chordal->back())); + DiscreteConditional expected2(Bronchitis % "11/9"); + EXPECT(assert_equal(expected2, *chordal->back())); // solve DiscreteFactor::sharedValues actualMPE = chordal->optimize(); DiscreteFactor::Values expectedMPE; - insert(expectedMPE)(A.first, 0)(D.first, 0)(X.first, 0)(T.first, 0)(S.first, - 0)(E.first, 0)(L.first, 0)(B.first, 0); + insert(expectedMPE)(Asia.first, 0)(Dyspnea.first, 0)(XRay.first, 0)( + Tuberculosis.first, 0)(Smoking.first, 0)(Either.first, 0)( + LungCancer.first, 0)(Bronchitis.first, 0); EXPECT(assert_equal(expectedMPE, *actualMPE)); - // add evidence, we were in Asia and we have Dispnoea - fg.add(A, "0 1"); - fg.add(D, "0 1"); -// fg.product().dot("fg"); + // add evidence, we were in Asia and we have dyspnea + fg.add(Asia, "0 1"); + fg.add(Dyspnea, "0 1"); // solve again, now with evidence DiscreteBayesNet::shared_ptr chordal2 = fg.eliminateSequential(ordering); -// GTSAM_PRINT(*chordal2); DiscreteFactor::sharedValues actualMPE2 = chordal2->optimize(); DiscreteFactor::Values expectedMPE2; - insert(expectedMPE2)(A.first, 1)(D.first, 1)(X.first, 0)(T.first, 0)(S.first, - 1)(E.first, 0)(L.first, 0)(B.first, 1); + insert(expectedMPE2)(Asia.first, 1)(Dyspnea.first, 1)(XRay.first, 0)( + Tuberculosis.first, 0)(Smoking.first, 1)(Either.first, 0)( + LungCancer.first, 0)(Bronchitis.first, 1); EXPECT(assert_equal(expectedMPE2, *actualMPE2)); // now sample from it DiscreteFactor::Values expectedSample; SETDEBUG("DiscreteConditional::sample", false); - insert(expectedSample)(A.first, 1)(D.first, 1)(X.first, 1)(T.first, 0)( - S.first, 1)(E.first, 1)(L.first, 1)(B.first, 0); + insert(expectedSample)(Asia.first, 1)(Dyspnea.first, 1)(XRay.first, 1)( + Tuberculosis.first, 0)(Smoking.first, 1)(Either.first, 1)( + LungCancer.first, 1)(Bronchitis.first, 0); DiscreteFactor::sharedValues actualSample = chordal2->sample(); EXPECT(assert_equal(expectedSample, *actualSample)); } /* ************************************************************************* */ -TEST_UNSAFE(DiscreteBayesNet, Sugar) -{ - DiscreteKey T(0,2), L(1,2), E(2,2), D(3,2), C(8,3), S(7,2); +TEST_UNSAFE(DiscreteBayesNet, Sugar) { + DiscreteKey T(0, 2), L(1, 2), E(2, 2), C(8, 3), S(7, 2); DiscreteBayesNet bn; - // test some mistakes - // add(bn, D); - // add(bn, D | E); - // add(bn, D | E = "blah"); - // try logic bn.add((E | T, L) = "OR"); bn.add((E | T, L) = "AND"); - // // try multivalued - bn.add(C % "1/1/2"); - bn.add(C | S = "1/1/2 5/2/3"); + // try multivalued + bn.add(C % "1/1/2"); + bn.add(C | S = "1/1/2 5/2/3"); } /* ************************************************************************* */ @@ -164,4 +155,3 @@ int main() { return TestRegistry::runAllTests(tr); } /* ************************************************************************* */ - diff --git a/gtsam/discrete/tests/testDiscreteConditional.cpp b/gtsam/discrete/tests/testDiscreteConditional.cpp index 749186d14..3ac3ffc9e 100644 --- a/gtsam/discrete/tests/testDiscreteConditional.cpp +++ b/gtsam/discrete/tests/testDiscreteConditional.cpp @@ -16,9 +16,9 @@ * @date Feb 14, 2011 */ -#include #include #include +#include using namespace boost::assign; #include @@ -48,71 +48,68 @@ TEST( DiscreteConditional, constructors) DecisionTreeFactor f2(X & Y & Z, "0.2 0.5 0.3 0.6 0.4 0.7 0.25 0.55 0.35 0.65 0.45 0.75"); DiscreteConditional actual2(1, f2); - DecisionTreeFactor::shared_ptr actual2factor = actual2.toFactor(); -// EXPECT(assert_equal(f2, *actual2factor, 1e-9)); + EXPECT(assert_equal(f2 / *f2.sum(1), *actual2.toFactor(), 1e-9)); } /* ************************************************************************* */ -TEST( DiscreteConditional, constructors_alt_interface) -{ - DiscreteKey X(0, 2), Y(2, 3), Z(1, 2); // watch ordering ! +TEST(DiscreteConditional, constructors_alt_interface) { + DiscreteKey X(0, 2), Y(2, 3), Z(1, 2); // watch ordering ! Signature::Table table; Signature::Row r1, r2, r3; - r1 += 1.0, 1.0; r2 += 2.0, 3.0; r3 += 1.0, 4.0; + r1 += 1.0, 1.0; + r2 += 2.0, 3.0; + r3 += 1.0, 4.0; table += r1, r2, r3; - DiscreteConditional::shared_ptr expected1 = // - boost::make_shared(X | Y = table); - EXPECT(expected1); + auto actual1 = boost::make_shared(X | Y = table); + EXPECT(actual1); DecisionTreeFactor f1(X & Y, "0.5 0.4 0.2 0.5 0.6 0.8"); - DiscreteConditional actual1(1, f1); - EXPECT(assert_equal(*expected1, actual1, 1e-9)); + DiscreteConditional expected1(1, f1); + EXPECT(assert_equal(expected1, *actual1, 1e-9)); - DecisionTreeFactor f2(X & Y & Z, - "0.2 0.5 0.3 0.6 0.4 0.7 0.25 0.55 0.35 0.65 0.45 0.75"); + DecisionTreeFactor f2( + X & Y & Z, "0.2 0.5 0.3 0.6 0.4 0.7 0.25 0.55 0.35 0.65 0.45 0.75"); DiscreteConditional actual2(1, f2); - DecisionTreeFactor::shared_ptr actual2factor = actual2.toFactor(); -// EXPECT(assert_equal(f2, *actual2factor, 1e-9)); + EXPECT(assert_equal(f2 / *f2.sum(1), *actual2.toFactor(), 1e-9)); } /* ************************************************************************* */ -TEST( DiscreteConditional, constructors2) -{ +TEST(DiscreteConditional, constructors2) { // Declare keys and ordering - DiscreteKey C(0,2), B(1,2); - DecisionTreeFactor expected(C & B, "0.8 0.75 0.2 0.25"); + DiscreteKey C(0, 2), B(1, 2); + DecisionTreeFactor actual(C & B, "0.8 0.75 0.2 0.25"); Signature signature((C | B) = "4/1 3/1"); - DiscreteConditional actual(signature); - DecisionTreeFactor::shared_ptr actualFactor = actual.toFactor(); - EXPECT(assert_equal(expected, *actualFactor)); + DiscreteConditional expected(signature); + DecisionTreeFactor::shared_ptr expectedFactor = expected.toFactor(); + EXPECT(assert_equal(*expectedFactor, actual)); } /* ************************************************************************* */ -TEST( DiscreteConditional, constructors3) -{ +TEST(DiscreteConditional, constructors3) { // Declare keys and ordering - DiscreteKey C(0,2), B(1,2), A(2,2); - DecisionTreeFactor expected(C & B & A, "0.8 0.5 0.5 0.2 0.2 0.5 0.5 0.8"); + DiscreteKey C(0, 2), B(1, 2), A(2, 2); + DecisionTreeFactor actual(C & B & A, "0.8 0.5 0.5 0.2 0.2 0.5 0.5 0.8"); Signature signature((C | B, A) = "4/1 1/1 1/1 1/4"); - DiscreteConditional actual(signature); - DecisionTreeFactor::shared_ptr actualFactor = actual.toFactor(); - EXPECT(assert_equal(expected, *actualFactor)); + DiscreteConditional expected(signature); + DecisionTreeFactor::shared_ptr expectedFactor = expected.toFactor(); + EXPECT(assert_equal(*expectedFactor, actual)); } /* ************************************************************************* */ -TEST( DiscreteConditional, Combine) { +TEST(DiscreteConditional, Combine) { DiscreteKey A(0, 2), B(1, 2); vector c; c.push_back(boost::make_shared(A | B = "1/2 2/1")); c.push_back(boost::make_shared(B % "1/2")); DecisionTreeFactor factor(A & B, "0.111111 0.444444 0.222222 0.222222"); - DiscreteConditional expected(2, factor); - DiscreteConditional::shared_ptr actual = DiscreteConditional::Combine( - c.begin(), c.end()); - EXPECT(assert_equal(expected, *actual,1e-5)); + DiscreteConditional actual(2, factor); + auto expected = DiscreteConditional::Combine(c.begin(), c.end()); + EXPECT(assert_equal(*expected, actual, 1e-5)); } /* ************************************************************************* */ -int main() { TestResult tr; return TestRegistry::runAllTests(tr); } +int main() { + TestResult tr; + return TestRegistry::runAllTests(tr); +} /* ************************************************************************* */ - diff --git a/gtsam/discrete/tests/testDiscreteMarginals.cpp b/gtsam/discrete/tests/testDiscreteMarginals.cpp index 4e9f956b6..e1eb92af3 100644 --- a/gtsam/discrete/tests/testDiscreteMarginals.cpp +++ b/gtsam/discrete/tests/testDiscreteMarginals.cpp @@ -146,8 +146,7 @@ TEST_UNSAFE( DiscreteMarginals, truss ) { /* ************************************************************************* */ // Second truss example with non-trivial factors -TEST_UNSAFE( DiscreteMarginals, truss2 ) { - +TEST_UNSAFE(DiscreteMarginals, truss2) { const int nrNodes = 5; const size_t nrStates = 2; @@ -160,40 +159,39 @@ TEST_UNSAFE( DiscreteMarginals, truss2 ) { // create graph and add three truss potentials DiscreteFactorGraph graph; - graph.add(key[0] & key[2] & key[4],"1 2 3 4 5 6 7 8"); - graph.add(key[1] & key[3] & key[4],"1 2 3 4 5 6 7 8"); - graph.add(key[2] & key[3] & key[4],"1 2 3 4 5 6 7 8"); + graph.add(key[0] & key[2] & key[4], "1 2 3 4 5 6 7 8"); + graph.add(key[1] & key[3] & key[4], "1 2 3 4 5 6 7 8"); + graph.add(key[2] & key[3] & key[4], "1 2 3 4 5 6 7 8"); // Calculate the marginals by brute force - vector allPosbValues = cartesianProduct( - key[0] & key[1] & key[2] & key[3] & key[4]); + vector allPosbValues = + cartesianProduct(key[0] & key[1] & key[2] & key[3] & key[4]); Vector T = Z_5x1, F = Z_5x1; for (size_t i = 0; i < allPosbValues.size(); ++i) { DiscreteFactor::Values x = allPosbValues[i]; double px = graph(x); - for (size_t j=0;j<5;j++) - if (x[j]) T[j]+=px; else F[j]+=px; - // cout << x[0] << " " << x[1] << " "<< x[2] << " " << x[3] << " " << x[4] << " :\t" << px << endl; + for (size_t j = 0; j < 5; j++) + if (x[j]) + T[j] += px; + else + F[j] += px; } // Check all marginals given by a sequential solver and Marginals -// DiscreteSequentialSolver solver(graph); + // DiscreteSequentialSolver solver(graph); DiscreteMarginals marginals(graph); - for (size_t j=0;j<5;j++) { - double sum = T[j]+F[j]; - T[j]/=sum; - F[j]/=sum; - -// // solver -// Vector actualV = solver.marginalProbabilities(key[j]); -// EXPECT(assert_equal((Vector(2) << F[j], T[j]), actualV)); + for (size_t j = 0; j < 5; j++) { + double sum = T[j] + F[j]; + T[j] /= sum; + F[j] /= sum; // Marginals vector table; - table += F[j],T[j]; - DecisionTreeFactor expectedM(key[j],table); + table += F[j], T[j]; + DecisionTreeFactor expectedM(key[j], table); DiscreteFactor::shared_ptr actualM = marginals(j); - EXPECT(assert_equal(expectedM, *boost::dynamic_pointer_cast(actualM))); + EXPECT(assert_equal( + expectedM, *boost::dynamic_pointer_cast(actualM))); } } diff --git a/gtsam/discrete/tests/testSignature.cpp b/gtsam/discrete/tests/testSignature.cpp index 830fc32fc..049c455f7 100644 --- a/gtsam/discrete/tests/testSignature.cpp +++ b/gtsam/discrete/tests/testSignature.cpp @@ -22,6 +22,7 @@ #include #include +#include using namespace std; using namespace gtsam; @@ -32,6 +33,11 @@ DiscreteKey X(0, 2), Y(1, 3), Z(2, 2); /* ************************************************************************* */ TEST(testSignature, simple_conditional) { Signature sig(X | Y = "1/1 2/3 1/4"); + Signature::Table table = *sig.table(); + vector row[3]{{0.5, 0.5}, {0.4, 0.6}, {0.2, 0.8}}; + CHECK(row[0] == table[0]); + CHECK(row[1] == table[1]); + CHECK(row[2] == table[2]); DiscreteKey actKey = sig.key(); LONGS_EQUAL(X.first, actKey.first); From 33f045729893b4d77ba27a3abbcb9e73a98fc520 Mon Sep 17 00:00:00 2001 From: Frank dellaert Date: Sat, 11 Jul 2020 13:19:48 -0400 Subject: [PATCH 216/869] Use dict notation in print --- gtsam/discrete/Potentials.cpp | 68 ++++++++++++++++++----------------- 1 file changed, 35 insertions(+), 33 deletions(-) diff --git a/gtsam/discrete/Potentials.cpp b/gtsam/discrete/Potentials.cpp index c4cdbe0ef..fe99ea975 100644 --- a/gtsam/discrete/Potentials.cpp +++ b/gtsam/discrete/Potentials.cpp @@ -15,50 +15,52 @@ * @author Frank Dellaert */ -#include #include +#include + #include +#include + using namespace std; namespace gtsam { - // explicit instantiation - template class DecisionTree ; - template class AlgebraicDecisionTree ; +// explicit instantiation +template class DecisionTree; +template class AlgebraicDecisionTree; - /* ************************************************************************* */ - double Potentials::safe_div(const double& a, const double& b) { - // cout << boost::format("%g / %g = %g\n") % a % b % ((a == 0) ? 0 : (a / b)); - // The use for safe_div is when we divide the product factor by the sum factor. - // If the product or sum is zero, we accord zero probability to the event. - return (a == 0 || b == 0) ? 0 : (a / b); - } +/* ************************************************************************* */ +double Potentials::safe_div(const double& a, const double& b) { + // cout << boost::format("%g / %g = %g\n") % a % b % ((a == 0) ? 0 : (a / b)); + // The use for safe_div is when we divide the product factor by the sum + // factor. If the product or sum is zero, we accord zero probability to the + // event. + return (a == 0 || b == 0) ? 0 : (a / b); +} - /* ******************************************************************************** */ - Potentials::Potentials() : - ADT(1.0) { - } +/* ******************************************************************************** + */ +Potentials::Potentials() : ADT(1.0) {} - /* ******************************************************************************** */ - Potentials::Potentials(const DiscreteKeys& keys, const ADT& decisionTree) : - ADT(decisionTree), cardinalities_(keys.cardinalities()) { - } +/* ******************************************************************************** + */ +Potentials::Potentials(const DiscreteKeys& keys, const ADT& decisionTree) + : ADT(decisionTree), cardinalities_(keys.cardinalities()) {} - /* ************************************************************************* */ - bool Potentials::equals(const Potentials& other, double tol) const { - return ADT::equals(other, tol); - } +/* ************************************************************************* */ +bool Potentials::equals(const Potentials& other, double tol) const { + return ADT::equals(other, tol); +} - /* ************************************************************************* */ - void Potentials::print(const string& s, - const KeyFormatter& formatter) const { - cout << s << "\n Cardinalities: "; - for(const DiscreteKey& key: cardinalities_) - cout << formatter(key.first) << "=" << formatter(key.second) << " "; - cout << endl; - ADT::print(" "); - } +/* ************************************************************************* */ +void Potentials::print(const string& s, const KeyFormatter& formatter) const { + cout << s << "\n Cardinalities: {"; + for (const DiscreteKey& key : cardinalities_) + cout << formatter(key.first) << ":" << key.second << ", "; + cout << "}" << endl; + ADT::print(" "); +} // // /* ************************************************************************* */ // template @@ -95,4 +97,4 @@ namespace gtsam { /* ************************************************************************* */ -} // namespace gtsam +} // namespace gtsam From 621e79f06c27c66bd9804e1c462e494cfc2522ac Mon Sep 17 00:00:00 2001 From: Frank dellaert Date: Sun, 12 Jul 2020 17:34:16 -0400 Subject: [PATCH 217/869] Add explicit HMM example --- examples/DiscreteBayesNetExample.cpp | 1 + examples/HMMExample.cpp | 94 ++++++++++++++++++++++++++++ 2 files changed, 95 insertions(+) create mode 100644 examples/HMMExample.cpp diff --git a/examples/DiscreteBayesNetExample.cpp b/examples/DiscreteBayesNetExample.cpp index 3531fd723..629043431 100644 --- a/examples/DiscreteBayesNetExample.cpp +++ b/examples/DiscreteBayesNetExample.cpp @@ -18,6 +18,7 @@ #include #include +#include #include diff --git a/examples/HMMExample.cpp b/examples/HMMExample.cpp new file mode 100644 index 000000000..a56058633 --- /dev/null +++ b/examples/HMMExample.cpp @@ -0,0 +1,94 @@ +/* ---------------------------------------------------------------------------- + + * GTSAM Copyright 2010-2020, Georgia Tech Research Corporation, + * Atlanta, Georgia 30332-0415 + * All Rights Reserved + * Authors: Frank Dellaert, et al. (see THANKS for the full author list) + + * See LICENSE for the license information + + * -------------------------------------------------------------------------- */ + +/** + * @file DiscreteBayesNetExample.cpp + * @brief Hidden Markov Model example, discrete. + * @author Frank Dellaert + * @date July 12, 2020 + */ + +#include +#include +#include + +#include +#include + +using namespace std; +using namespace gtsam; + +int main(int argc, char **argv) { + const int nrNodes = 4; + const size_t nrStates = 3; + + // Define variables as well as ordering + Ordering ordering; + vector keys; + for (int k = 0; k < nrNodes; k++) { + DiscreteKey key_i(k, nrStates); + keys.push_back(key_i); + ordering.emplace_back(k); + } + + // Create HMM as a DiscreteBayesNet + DiscreteBayesNet hmm; + + // Define backbone + const string transition = "8/1/1 1/8/1 1/1/8"; + for (int k = 1; k < nrNodes; k++) { + hmm.add(keys[k] | keys[k - 1] = transition); + } + + // Add some measurements, not needed for all time steps! + hmm.add(keys[0] % "7/2/1"); + hmm.add(keys[1] % "1/9/0"); + hmm.add(keys.back() % "5/4/1"); + + // print + hmm.print("HMM"); + + // Convert to factor graph + DiscreteFactorGraph factorGraph(hmm); + + // Create solver and eliminate + // This will create a DAG ordered with arrow of time reversed + DiscreteBayesNet::shared_ptr chordal = + factorGraph.eliminateSequential(ordering); + chordal->print("Eliminated"); + + // solve + DiscreteFactor::sharedValues mpe = chordal->optimize(); + GTSAM_PRINT(*mpe); + + // We can also sample from it + cout << "\n10 samples:" << endl; + for (size_t k = 0; k < 10; k++) { + DiscreteFactor::sharedValues sample = chordal->sample(); + GTSAM_PRINT(*sample); + } + + // Or compute the marginals. This re-eliminates the FG into a Bayes tree + cout << "\nComputing Node Marginals .." << endl; + DiscreteMarginals marginals(factorGraph); + for (int k = 0; k < nrNodes; k++) { + Vector margProbs = marginals.marginalProbabilities(keys[k]); + stringstream ss; + ss << "marginal " << k; + print(margProbs, ss.str()); + } + + // TODO(frank): put in the glue to have DiscreteMarginals produce *arbitrary* + // joints efficiently, by the Bayes tree shortcut magic. All the code is there + // but it's not yet connected. + + return 0; +} From 947d7377b49b5863891995c410652eb0fc212277 Mon Sep 17 00:00:00 2001 From: Frank dellaert Date: Sun, 12 Jul 2020 23:25:07 -0400 Subject: [PATCH 218/869] Modernized sample function --- gtsam/discrete/DiscreteConditional.cpp | 51 ++++++-------------------- 1 file changed, 12 insertions(+), 39 deletions(-) diff --git a/gtsam/discrete/DiscreteConditional.cpp b/gtsam/discrete/DiscreteConditional.cpp index acd0cefee..ac7c58405 100644 --- a/gtsam/discrete/DiscreteConditional.cpp +++ b/gtsam/discrete/DiscreteConditional.cpp @@ -184,55 +184,28 @@ size_t DiscreteConditional::solve(const Values& parentsValues) const { /* ******************************************************************************** */ size_t DiscreteConditional::sample(const Values& parentsValues) const { - - static mt19937 rng(2); // random number generator - - bool debug = ISDEBUG("DiscreteConditional::sample"); + static mt19937 rng(2); // random number generator // Get the correct conditional density - ADT pFS = choose(parentsValues); // P(F|S=parentsValues) - if (debug) - GTSAM_PRINT(pFS); + ADT pFS = choose(parentsValues); // P(F|S=parentsValues) - // get cumulative distribution function (cdf) - // TODO, only works for one key now, seems horribly slow this way + // TODO(Duy): only works for one key now, seems horribly slow this way assert(nrFrontals() == 1); - Key j = (firstFrontalKey()); - size_t nj = cardinality(j); - vector cdf(nj); + Key key = firstFrontalKey(); + size_t nj = cardinality(key); + vector p(nj); Values frontals; - double sum = 0; for (size_t value = 0; value < nj; value++) { - frontals[j] = value; - double pValueS = pFS(frontals); // P(F=value|S=parentsValues) - sum += pValueS; // accumulate - if (debug) - cout << sum << " "; - if (pValueS == 1) { - if (debug) - cout << "--> " << value << endl; - return value; // shortcut exit + frontals[key] = value; + p[value] = pFS(frontals); // P(F=value|S=parentsValues) + if (p[value] == 1.0) { + return value; // shortcut exit } - cdf[value] = sum; } - - // inspired by http://www.boost.org/doc/libs/1_46_1/doc/html/boost_random/tutorial.html - uniform_real_distribution dist(0, cdf.back()); - size_t sampled = lower_bound(cdf.begin(), cdf.end(), dist(rng)) - cdf.begin(); - if (debug) - cout << "-> " << sampled << endl; - - return sampled; - - return 0; + std::discrete_distribution distribution(p.begin(), p.end()); + return distribution(rng); } -/* ******************************************************************************** */ -//void DiscreteConditional::permuteWithInverse( -// const Permutation& inversePermutation) { -// IndexConditionalOrdered::permuteWithInverse(inversePermutation); -// Potentials::permuteWithInverse(inversePermutation); -//} /* ******************************************************************************** */ }// namespace From 52927c1c5b8a5b3e71ce8184fb6fcb4ca4c7b83b Mon Sep 17 00:00:00 2001 From: yetongumich Date: Mon, 13 Jul 2020 01:45:22 -0400 Subject: [PATCH 219/869] modify testNoiseModel to use loss instead of error --- gtsam/linear/tests/testNoiseModel.cpp | 13 ++++++++----- 1 file changed, 8 insertions(+), 5 deletions(-) diff --git a/gtsam/linear/tests/testNoiseModel.cpp b/gtsam/linear/tests/testNoiseModel.cpp index dd1d46b42..42d68a603 100644 --- a/gtsam/linear/tests/testNoiseModel.cpp +++ b/gtsam/linear/tests/testNoiseModel.cpp @@ -182,8 +182,9 @@ TEST(NoiseModel, ConstrainedMixed ) EXPECT(assert_equal(Vector3(0.5, 1.0, 0.5),d->whiten(infeasible))); EXPECT(assert_equal(Vector3(0.5, 0.0, 0.5),d->whiten(feasible))); - DOUBLES_EQUAL(0.5 * (1000.0 + 0.25 + 0.25),d->error(infeasible),1e-9); - DOUBLES_EQUAL(0.5 * 0.5,d->error(feasible),1e-9); + DOUBLES_EQUAL(0.5 * (1000.0 + 0.25 + 0.25),d->loss(d->squaredMahalanobisDistance(infeasible)),1e-9); + DOUBLES_EQUAL(0.5, d->squaredMahalanobisDistance(feasible),1e-9); + DOUBLES_EQUAL(0.5 * 0.5, d->loss(0.5),1e-9); } /* ************************************************************************* */ @@ -197,8 +198,9 @@ TEST(NoiseModel, ConstrainedAll ) EXPECT(assert_equal(Vector3(1.0, 1.0, 1.0),i->whiten(infeasible))); EXPECT(assert_equal(Vector3(0.0, 0.0, 0.0),i->whiten(feasible))); - DOUBLES_EQUAL(0.5 * 1000.0 * 3.0,i->error(infeasible),1e-9); - DOUBLES_EQUAL(0.0,i->error(feasible),1e-9); + DOUBLES_EQUAL(0.5 * 1000.0 * 3.0,i->loss(i->squaredMahalanobisDistance(infeasible)),1e-9); + DOUBLES_EQUAL(0.0, i->squaredMahalanobisDistance(feasible), 1e-9); + DOUBLES_EQUAL(0.0, i->loss(0.0),1e-9); } /* ************************************************************************* */ @@ -717,7 +719,8 @@ TEST(NoiseModel, lossFunctionAtZero) EQUALITY(cov, gaussian->covariance());\ EXPECT(assert_equal(white, gaussian->whiten(e)));\ EXPECT(assert_equal(e, gaussian->unwhiten(white)));\ - EXPECT_DOUBLES_EQUAL(0.5 * 251, gaussian->error(e), 1e-9);\ + EXPECT_DOUBLES_EQUAL(251.0, gaussian->squaredMahalanobisDistance(e), 1e-9);\ + EXPECT_DOUBLES_EQUAL(0.5 * 251.0, gaussian->loss(251.0), 1e-9);\ Matrix A = R.inverse(); Vector b = e;\ gaussian->WhitenSystem(A, b);\ EXPECT(assert_equal(I, A));\ From 529f6091d30eddc76119a28f674e41a104df45d5 Mon Sep 17 00:00:00 2001 From: yetongumich Date: Mon, 13 Jul 2020 02:01:40 -0400 Subject: [PATCH 220/869] change doc --- doc/robust.pdf | Bin 205572 -> 205563 bytes 1 file changed, 0 insertions(+), 0 deletions(-) diff --git a/doc/robust.pdf b/doc/robust.pdf index 45c023384c723a506f5bb48b2bfcab5aa5b338c3..67b853f44eefdf176e8b73bad1a6fd3da83f93d8 100644 GIT binary patch delta 3753 zcmbt%X*3iL*u61!BKz1fmMoFk%=V)p`_5nz5=M*^Wov{CWgR6&K_U(WE@7MSFbniXqxgVZ$?sLwK?%_M6@ufjwCncFf0Q6zXoDz0Cv{)gkdqB7!;J~ zPJ}_>*RWWm2N4BFp)u~rYp{P3P8*GOC&G#UoIEu>J-tvc7!dqE7Fs(OY)no;rGsD=_y-k5Y z{Zb(CN33W|jm*R53~?VrwdvfDPupGgjQl0V3JJ)A8X2vRl5>%zrz^AaqMqI5Nm~LE z-1^1hY>f@T+eJ#ckygmb>py+Vaa4wW2xt7 zf8q(?c~I@sSnUH?jH3KI6b{D|7!=^??#mOBzv0Ztn13U9uc*eRP@doj_2+yu$En2( zrg=8!uV2bI#}Js72rV_pftBs7Z%!P3)1!*peH*ojey+m{s zMV)Nu9Uk|cQbpY8X${>kNBgRBm%PyO^&9%upvHc%(x@!dB$B};SkbQb>tfQP*E`px zDll^d@vMA*wGA`aTNShBbt_vKfHZ1t;kBGPDC|WA_9uv-8p1EDI~d*^%6o}bnEpg% z-YoF`Xi-DTuxiXJO8hu8E%q!*METO%Dm~BFwIDm4VnIzPj4w>7o7E*@6CuK8iu){ka14!Df2CO=@^TnQ?=b(^x`=P|#LI@{zb z^3)%n?QIKCm8V)K9))r|IX^dl6k7D=6k@dOWpX{gFQ~wKS(SH5!B*-r2ZHdF4rh8GZX0H;`fb&e;ihkd|haVe#Xk{YGb~tzntn`0BvQ^q%L<^V!q~@FOX! zlKaaK&rPJcZ+1V=4Lqfd`2>|mq`yDzPFlHMOKEYzJlS+k0_{`*BlZQ4Y(GG)PUXZ! z7ixAMjogP=b~MsOy-LQ+gsKh8l+Ne_GEX77yX2I+`?MPdgv>~zD3zMA)yUD$ukxV- z%^Fh;)L(KCPtoz!9z4DTA2Wgi{AZRnCI48Jn6(K9cbN=D@>P!~l$`H;RI4j%>=0s2 z$(t9(00|=QT@r37arX&9PGZRN-43zw{z0IBU!I18h|m$xVY1QUtLtki)Fbe@eN=~sip}Y zb^a*rW@PXqc7q0DPP1*1|K*~YDR5ThvZlJ#?B4tHZd%;4Esm(ub<5M^jL1pc z;P-nWckM*b&6D$}D^l5HogbsG%(A9S2DBmENMh0C=Y>xg(eQK+j#*`0{&N`z3 z!DqdGzx9ICzQA3wKbMqXK>2kYJFy+9@2_M!uFM(klaB}b_bAN`;vWR2%VnOP2eoXj zOPo4+|H&hy<9ouu{k{|rvZ=99LQ@FSd-*4=3j0k*Lnqe%$|~pyj~>a%!lO^UzqxKQ z?3}>JaTnKk-PJgbjp}Y;v9HsuEbMlUnQdVq?P_`ovI8@j5!crXQ51!i8)v>SkE@7b z5Zduls4Hzlv0ZivYkUDaMBZsin9x!@@>?Je1m_oot#_ZUW*owq4+j{FJ?9aJuD3{m z&&vO*LPKQAw_C(|{|4yWp*0^3AuGn)2?Y@156c}t+08q&V9~RluTSrNr=LqtQAanY zrF~0IGgfao5*Uh!rO=<-(HArjy9j#nql3jCGS|-v(M6vM5ct_e1E_2oK0k&Ax38xx zOI|G>?kaZY(3#wOqs|K{GfHb$MNJrnCaq4nh8w$V<@^QV9S1dB+g(TACVme*nyK!p zj`U-9dHWYrrl%#colB;t_cY& zGnMDAw3z!#g&5IkIVW~?Z5M0tnPK?QzMN;GHVL7VIpR*e(fwyX`K(^`KWR0A$$J_=O}wxDvXpKZ#{f>lx3Oy*?1gpV#&_(2JV*!gp|AF9@ii@RP4pFr+16g7 zg08f_^w)$rUw>+y1thgwDcnHr(hmb}d!x`P3=3=!fD#rIgt5_mo9Vd z1P6Y6fZ}hY_-HN8sFy?Yg@V+8@-6t0tfzRf#s1xZMm4`8v9m-6jaHAT6rOrvynIw* z&_lPLKU{|mDziAfZ&oBBVHglUCp#@~}J)d=8H% zR1%5=GTO(55i%?)G4`VrBpU>JvPP(;7_{nKAiIgV>C`?SmKf`Ew5m^4>#q`s(r_z+ zT|2!q>1iHYw=8Tkj{zEREWg!?Sc&XQ*8w$hY0UJHUs%%k!aEjzG6KRl|0^CZo`&#} zGjs>G2`<5AJu^o)yzYWh>i+<^3nS>-oQYp+u2l7;=YqLo;H8utHiG*7(iCY$u4MSP z3u72`WZ}t5;U582;k1Am@Uwbk4&kf$JB22Mlgz}+;cZQ;yyy}&Mo6W~3eE!6UiAFV zbY5KHK{MXb%#0jRzgQz1%uiFqiTTPRaMA}m?Lu)8M`6j`kWFn%pG!P=8i2)TAjBn3 zo5T@vG8+pZP}b`0XC_;)(i$H5#cc8Q;=xm`s}W)TAHgn-Rk+gCLQd;P?`6HIu2Cw( zu{X5Iu@08Ha*uzf7+txui~1Q2Rg~}*4UxGWG(3~y>{gVHI}v!2Sn-BKYbIvr{p{iJ zPxOw7(p?OXMBY82Z?m|v_mur@N&iZz-bkbM6{5Fho7Uz{jewAT??IJkMuP%LGx>iI zugrgsnvI;yrT>!cs=jWN`W1FZfb;zKo-B6MsE4N{(+4PW!ph;nUmd5r4`|fgXAM>6 zM#B(L6cnln&FKaM75*P>-1&f{|C(u{#O71 delta 3790 zcmbu?_dgYmqsMW_LH0;y;e>=v&N|$mFbQA?s*?XeZxyDGg1FR=!O()?+SsI={O`Bk2cE57YkqpNc} zayh5Rhm}G#Tm!t z`^%c|y&o$rb8THYlbRXLl8CmheS$@8z_M*?@N7;)dX(AMx5!3k?{BXePk+zyvtii{ zqGG8F0wqWjX!}_^oa-wY&2>{k zkYd4Sv+wLS!iuUdLfKr;Mo`zYN~oKwVP@oK4(yKViJbmtS#CXNTKKBk{p7Z`uNDaaOa$w4)tiBPdffW=?wF#>McXu;tj*;E4J&oqrAtz!sp{7(LO$kU%+@AIe|%K~ z!$fT2OKAn1=P}gxAl1@AC8swhALUmc0(rQV68ep#ea@k{;0IuWmk{^+6G186zrVum zo-ws!6cg@stz0dofiAbo=ge@BRU(BF|=B)VK(V zYtW6P3L+_iuMh22$0MtX!uk!Zdq`v-%)}$i67g<$(#4X7Sm&2krOlkNP;)paa{USI zk)gLUc&zV>z&w?(ddxJUC7|=ho8`@Np}oM{44uSs^_}mLkr=KjnheW5z4V;duj-Zt zro4h{1sI4o!yWY5uJUnlasZ!YLisqiP8m%;h#~>1&QPR)ck!6K0|R%elW9vG$gt;? z2*aPBMIPY|1C`ZA_8gkhm+i660KTf}mFfwXD;f5=8pH8~dx#p{vZsf0h?>zt`cP8$ zzFgH&kZnQv>xKyC1dXZwfPb4N2u8R3Sf=-e>d|eFi!?9P*qoU^8P6Qt@1%N+1D7zK z=EWiQ&KIz}TAB+p_(cuygo(t%dO%BUrep}y* zD@e8c1bmf{O5750P`zrdn+6}+5W!rF8*qBp44?ary+~kBP0UK-YLdHr?Kbd3oZE$9 z2cPus0SEJXBa1m-4CozCaoxGr9%@M^Up2V_^?$ zUuYuOY6Lf{o;5!7*Q%WZPf_eLa%QC`{j?E0WXs7L=SDHEfW~Y%w_c&1X;PF}ZywYX zX$l`Y6!ZcSgk)tF)%B*^XtmlLU&DM@j{A`dfmGnyMZ2!qmd7X77eQh(G=;0Jj_)sV zl{B)7>y^Hs7-H}@ch%Mb7A|jM6j!Y!QwU)XMwHYSO>+&#e-8liMO`Mea%yumKNc4#N*!&ISm^ZHIy4=NC%-GTX9vMoNp{c^0o&-bXrPPF;mFoAVD zTdyJTykdIZ(5Jm=-qJ^HVEe_>5i=9xeQb*-?SPxD{W87FSIp(7_z5&>{jeCk(j(=VE_K3E+C>zn9P zpZYr`Qj}o@Y3U%TAAB5;^V@!f4utw&7^Nmk!e1kQT-h^vsNRD(w7<^3w_o4Zj?R^g zi2oL<1`o}aBFAKw6F)wB)4>zadXv&=SkCvu>*cV2ig+>kP-wwy>SRSz7b8fdpd_Z? zTQvF=LSyB}^(B54sWLnF)8%zEG&TFtr%0_ysmbz{eTLi)tZ)pNbtc?zPgh zI>Ct>LnV$aVpn(j!K+Np@Y{-Eq$G79@f$Dh03H5?&x!>W!c>VP#G2vi<$AZTR026Z zx_p(z;?9vAUmiR8#D}IIH1LbR0JrEkStvY=`e4?*D2SJrKhF?8(g=KJ1wQI2`}9;P z0bUx5BqtIjqe06JkBxip+U`%Owu-OZnbU(lY`$#b;}U(#b0WP-SnP)O2mAYOTh8%ZKr@ zCjL+`IB5p^_&I5@oSXX_)1{^|G-uZ7eyHUY7+u&GQ(G+8CsGJhsePY8v@3K)Q1ior z$p&SmSqrGqiU;BX=~-oo= zw5YfC|5B!}IaZ4)Sl6m!p6@-3c;vOq=;isdS|iQ03R5WWu{G_6Rx^I1UKhWL6oMix zFa27-&L31?9T=P1g54y=R5qs$N?dZQZX;okJkOU>{SP&R^NdboP%S_CDx<~zs_-}s zZEMt3tc(#HC%l|Zeaf_l`64@$N7$dIoDC#XHbg>b+4=(`#COW0d70~ka1)Ush{=!7 zS9fUv z3sVjBAF1}I-SwNc^BRk-)xM0i3Eh2LpX65u`1%M|jyf9`&#TD3v8hr`HBI432QXD+ zfrHqLmBv%I#dFzaUi{!_T63%W2}zc(*->`?O+#_#20C4TQBv&M8<<9?#?3pQOfGz) zW_6>7w9=1ljuq{px(SkZ#H6x|NRDXKK@yCyyiv_yzT4yHM&qpQd+KXH_77ca-#pDq zM!pf^HvX8kLp6yd&fmmn>>9rvsSZh|EK*uSyH@xJZgxwH0+C7Vyb+~b?+eM5WDD=xc49`#f5(_n%? zyIu4B#7MCAMRvSCgssAg$v{j+pH~$BIi#p|_Ep~5R^IWb1b?#ccThP|DbvDEr75x= z{y?m*%6J|z5*r1)J{xpNc1^Rtfl8shZc!-js=|p7q82paz}`5=p;~ z?c$16&suv^1OnM*lx{@7r!g?p<68*TxAWjY^>h8s@QMTL3XR-|_ozrLLzygqwxRPj zpoVN`l#9@x+N>DOC%^l2PiD6-nbvsuC2>h~^lgg;ziI4hE08PmZ6?>PtDFY9Hq5pc zuDqqzEelS&l)O4;{+EV*a*fQf9M@%;wFa3NqQrRH#po2 z`UVj#lPt1-dH5>Ni(jDVfJPLZG59(g0tSaEBTxurCK&{j`k!oE{Z9f2|9|IcVE>nx zaE=TB8QtC&bWS6!`>@y_7Xc{=_Q-9+Ps&o57C!XX*ys8(a!@)8I$J+dKPxj<63ETe MglGHq-v)H}FAO9e_5c6? From 84bb4185298a080670be7235465b9730932e4352 Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Tue, 14 Jul 2020 02:23:19 -0400 Subject: [PATCH 221/869] fix serialization warning for boost::optional --- gtsam/navigation/PreintegratedRotation.h | 8 +++++++- 1 file changed, 7 insertions(+), 1 deletion(-) diff --git a/gtsam/navigation/PreintegratedRotation.h b/gtsam/navigation/PreintegratedRotation.h index 9346f749a..0e0559a32 100644 --- a/gtsam/navigation/PreintegratedRotation.h +++ b/gtsam/navigation/PreintegratedRotation.h @@ -62,8 +62,14 @@ struct GTSAM_EXPORT PreintegratedRotationParams { void serialize(ARCHIVE & ar, const unsigned int /*version*/) { namespace bs = ::boost::serialization; ar & BOOST_SERIALIZATION_NVP(gyroscopeCovariance); - ar & BOOST_SERIALIZATION_NVP(omegaCoriolis); ar & BOOST_SERIALIZATION_NVP(body_P_sensor); + + // Provide support for Eigen::Matrix in boost::optional + bool omegaCoriolisFlag = omegaCoriolis.is_initialized(); + ar & boost::serialization::make_nvp("omegaCoriolisFlag", omegaCoriolisFlag); + if (omegaCoriolisFlag) { + ar & BOOST_SERIALIZATION_NVP(*omegaCoriolis); + } } #ifdef GTSAM_USE_QUATERNIONS From c76ebcf9e7a19ff3908e398d452f369000a1a049 Mon Sep 17 00:00:00 2001 From: Frank dellaert Date: Tue, 14 Jul 2020 08:49:45 -0400 Subject: [PATCH 222/869] Partial Specialization --- gtsam/base/Matrix.h | 6 ++++++ 1 file changed, 6 insertions(+) diff --git a/gtsam/base/Matrix.h b/gtsam/base/Matrix.h index 37ae1dd9a..1c1138438 100644 --- a/gtsam/base/Matrix.h +++ b/gtsam/base/Matrix.h @@ -610,5 +610,11 @@ namespace boost { split_free(ar, m, version); } + // specialized to Matrix for MATLAB wrapper + template + void serialize(Archive& ar, gtsam::Matrix& m, const unsigned int version) { + split_free(ar, m, version); + } + } // namespace serialization } // namespace boost From 4b4a0e532f7089d9cf8ba569ded01dcd19f944b0 Mon Sep 17 00:00:00 2001 From: Frank dellaert Date: Tue, 14 Jul 2020 08:50:20 -0400 Subject: [PATCH 223/869] Add BayesNet-inst.h at end of BayesNet.h --- examples/DiscreteBayesNetExample.cpp | 2 +- examples/HMMExample.cpp | 2 +- gtsam/discrete/tests/testDiscreteBayesTree.cpp | 2 +- gtsam/discrete/tests/testDiscreteFactorGraph.cpp | 2 +- gtsam/inference/BayesNet.h | 4 +++- 5 files changed, 7 insertions(+), 5 deletions(-) diff --git a/examples/DiscreteBayesNetExample.cpp b/examples/DiscreteBayesNetExample.cpp index 629043431..5dca116c3 100644 --- a/examples/DiscreteBayesNetExample.cpp +++ b/examples/DiscreteBayesNetExample.cpp @@ -18,7 +18,7 @@ #include #include -#include +#include #include diff --git a/examples/HMMExample.cpp b/examples/HMMExample.cpp index a56058633..ee861e381 100644 --- a/examples/HMMExample.cpp +++ b/examples/HMMExample.cpp @@ -18,7 +18,7 @@ #include #include -#include +#include #include #include diff --git a/gtsam/discrete/tests/testDiscreteBayesTree.cpp b/gtsam/discrete/tests/testDiscreteBayesTree.cpp index 11a88af59..ecf485036 100644 --- a/gtsam/discrete/tests/testDiscreteBayesTree.cpp +++ b/gtsam/discrete/tests/testDiscreteBayesTree.cpp @@ -19,7 +19,7 @@ #include #include #include -#include +#include #include using namespace boost::assign; diff --git a/gtsam/discrete/tests/testDiscreteFactorGraph.cpp b/gtsam/discrete/tests/testDiscreteFactorGraph.cpp index 7a0e1eaf7..1defd5acf 100644 --- a/gtsam/discrete/tests/testDiscreteFactorGraph.cpp +++ b/gtsam/discrete/tests/testDiscreteFactorGraph.cpp @@ -19,7 +19,7 @@ #include #include #include -#include +#include #include diff --git a/gtsam/inference/BayesNet.h b/gtsam/inference/BayesNet.h index a69fb9b8c..0597ece98 100644 --- a/gtsam/inference/BayesNet.h +++ b/gtsam/inference/BayesNet.h @@ -69,4 +69,6 @@ namespace gtsam { void saveGraph(const std::string &s, const KeyFormatter& keyFormatter = DefaultKeyFormatter) const; }; -} \ No newline at end of file +} + +#include From aca002fc126c521d750b4c0f091669e6f34e1fe7 Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Tue, 14 Jul 2020 13:25:08 -0400 Subject: [PATCH 224/869] correct indentation for Python version --- CMakeLists.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index f6f012118..a520d4d74 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -607,7 +607,7 @@ endif() message(STATUS "Cython toolbox flags ") print_config_flag(${GTSAM_INSTALL_CYTHON_TOOLBOX} "Install Cython toolbox ") if(GTSAM_INSTALL_CYTHON_TOOLBOX) - message(STATUS " Python version : ${GTSAM_PYTHON_VERSION}") + message(STATUS " Python version : ${GTSAM_PYTHON_VERSION}") endif() message(STATUS "===============================================================") From 94bb08ed34ab87e55f88f88f71dafb3c975daab8 Mon Sep 17 00:00:00 2001 From: Mike Sheffler Date: Tue, 14 Jul 2020 13:03:21 -0700 Subject: [PATCH 225/869] Missing BOOST_SERIALIZATION_NVP wrapper macro for an argument to be serialized --- gtsam/geometry/SOn.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/gtsam/geometry/SOn.h b/gtsam/geometry/SOn.h index f44c578cc..a6392c2f9 100644 --- a/gtsam/geometry/SOn.h +++ b/gtsam/geometry/SOn.h @@ -340,7 +340,7 @@ void serialize( const unsigned int file_version ) { Matrix& M = Q.matrix_; - ar& M; + ar& BOOST_SERIALIZATION_NVP(M); } /* From 23db3bb721fc5603e7fb9363029b88e92ac480e6 Mon Sep 17 00:00:00 2001 From: Jose Luis Blanco Claraco Date: Tue, 14 Jul 2020 23:24:47 +0200 Subject: [PATCH 226/869] docker tag and pip3 fixes; add a readme --- docker/README.md | 16 ++++++++++++++++ docker/ubuntu-boost-tbb/build.sh | 3 +++ docker/ubuntu-gtsam-python-vnc/Dockerfile | 6 +++--- docker/ubuntu-gtsam-python/Dockerfile | 4 ++-- docker/ubuntu-gtsam/Dockerfile | 6 +++--- 5 files changed, 27 insertions(+), 8 deletions(-) create mode 100644 docker/README.md create mode 100755 docker/ubuntu-boost-tbb/build.sh diff --git a/docker/README.md b/docker/README.md new file mode 100644 index 000000000..4dec63b94 --- /dev/null +++ b/docker/README.md @@ -0,0 +1,16 @@ +# Instructions + +Build all docker images, in order: + +```bash +(cd ubuntu-boost-tbb && exec build.sh) +(cd ubuntu-gtsam && exec build.sh) +(cd ubuntu-gtsam-python && exec build.sh) +(cd ubuntu-gtsam-python-vnc && exec build.sh) +``` + +Then launch with: + + docker run dellaert/ubuntu-gtsam-python-vnc:bionic + + diff --git a/docker/ubuntu-boost-tbb/build.sh b/docker/ubuntu-boost-tbb/build.sh new file mode 100755 index 000000000..2dac4c3db --- /dev/null +++ b/docker/ubuntu-boost-tbb/build.sh @@ -0,0 +1,3 @@ +# Build command for Docker image +# TODO(dellaert): use docker compose and/or cmake +docker build --no-cache -t dellaert/ubuntu-boost-tbb:bionic . diff --git a/docker/ubuntu-gtsam-python-vnc/Dockerfile b/docker/ubuntu-gtsam-python-vnc/Dockerfile index 26f995c56..61ecd9b9a 100644 --- a/docker/ubuntu-gtsam-python-vnc/Dockerfile +++ b/docker/ubuntu-gtsam-python-vnc/Dockerfile @@ -1,18 +1,18 @@ # This GTSAM image connects to the host X-server via VNC to provide a Graphical User Interface for interaction. # Get the base Ubuntu/GTSAM image from Docker Hub -FROM dellaert/ubuntu-gtsam-python:latest +FROM dellaert/ubuntu-gtsam-python:bionic # Things needed to get a python GUI ENV DEBIAN_FRONTEND noninteractive RUN apt install -y python-tk -RUN pip install matplotlib +RUN python3 -m pip install matplotlib # Install a VNC X-server, Frame buffer, and windows manager RUN apt install -y x11vnc xvfb fluxbox # Finally, install wmctrl needed for bootstrap script -RUN apt install -y wmctrl +RUN apt install -y wmctrl # Copy bootstrap script and make sure it runs COPY bootstrap.sh / diff --git a/docker/ubuntu-gtsam-python/Dockerfile b/docker/ubuntu-gtsam-python/Dockerfile index 71787d480..c733ceb19 100644 --- a/docker/ubuntu-gtsam-python/Dockerfile +++ b/docker/ubuntu-gtsam-python/Dockerfile @@ -1,7 +1,7 @@ # GTSAM Ubuntu image with Python wrapper support. # Get the base Ubuntu/GTSAM image from Docker Hub -FROM dellaert/ubuntu-gtsam:latest +FROM dellaert/ubuntu-gtsam:bionic # Install pip RUN apt-get install -y python3-pip python3-dev @@ -25,7 +25,7 @@ RUN cmake \ RUN make -j4 install && make clean # Needed to run python wrapper: -RUN echo 'export PYTHONPATH=/usr/local/cython/:$PYTHONPATH' >> /root/.bashrc +RUN echo 'export PYTHONPATH=/usr/local/cython/:$PYTHONPATH' >> /root/.bashrc # Run bash CMD ["bash"] diff --git a/docker/ubuntu-gtsam/Dockerfile b/docker/ubuntu-gtsam/Dockerfile index 393443361..187c76314 100644 --- a/docker/ubuntu-gtsam/Dockerfile +++ b/docker/ubuntu-gtsam/Dockerfile @@ -1,10 +1,10 @@ # Ubuntu image with GTSAM installed. Configured with Boost and TBB support. # Get the base Ubuntu image from Docker Hub -FROM dellaert/ubuntu-boost-tbb:latest +FROM dellaert/ubuntu-boost-tbb:bionic # Install git -RUN apt-get update && \ +RUN apt-get update && \ apt-get install -y git # Install compiler @@ -30,7 +30,7 @@ RUN cmake \ RUN make -j4 install && make clean # Needed to link with GTSAM -RUN echo 'export LD_LIBRARY_PATH=/usr/local/lib:LD_LIBRARY_PATH' >> /root/.bashrc +RUN echo 'export LD_LIBRARY_PATH=/usr/local/lib:LD_LIBRARY_PATH' >> /root/.bashrc # Run bash CMD ["bash"] From 17873485db36531a2a360b4bd609139e2c0e7128 Mon Sep 17 00:00:00 2001 From: Jose Luis Blanco Claraco Date: Tue, 14 Jul 2020 23:33:25 +0200 Subject: [PATCH 227/869] complete README --- docker/README.md | 15 ++++++++++----- 1 file changed, 10 insertions(+), 5 deletions(-) diff --git a/docker/README.md b/docker/README.md index 4dec63b94..0c136f94c 100644 --- a/docker/README.md +++ b/docker/README.md @@ -3,14 +3,19 @@ Build all docker images, in order: ```bash -(cd ubuntu-boost-tbb && exec build.sh) -(cd ubuntu-gtsam && exec build.sh) -(cd ubuntu-gtsam-python && exec build.sh) -(cd ubuntu-gtsam-python-vnc && exec build.sh) +(cd ubuntu-boost-tbb && ./build.sh) +(cd ubuntu-gtsam && ./build.sh) +(cd ubuntu-gtsam-python && ./build.sh) +(cd ubuntu-gtsam-python-vnc && ./build.sh) ``` Then launch with: - docker run dellaert/ubuntu-gtsam-python-vnc:bionic + docker run -p 5900:5900 dellaert/ubuntu-gtsam-python-vnc:bionic + +Then open a remote VNC X client, for example: + + sudo apt-get install tigervnc-viewer + xtigervncviewer :5900 From 02e8966d4f33a615a338fc17fa024c7387167bb9 Mon Sep 17 00:00:00 2001 From: acxz <17132214+acxz@users.noreply.github.com> Date: Wed, 15 Jul 2020 23:19:44 -0400 Subject: [PATCH 228/869] set default initialization --- gtsam/nonlinear/AdaptAutoDiff.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/gtsam/nonlinear/AdaptAutoDiff.h b/gtsam/nonlinear/AdaptAutoDiff.h index ff059ef78..682cca29a 100644 --- a/gtsam/nonlinear/AdaptAutoDiff.h +++ b/gtsam/nonlinear/AdaptAutoDiff.h @@ -57,7 +57,7 @@ class AdaptAutoDiff { if (H1 || H2) { // Get derivatives with AutoDiff const double* parameters[] = {v1.data(), v2.data()}; - double rowMajor1[M * N1], rowMajor2[M * N2]; // on the stack + double rowMajor1[M * N1] = {}, rowMajor2[M * N2] = {}; // on the stack double* jacobians[] = {rowMajor1, rowMajor2}; success = AutoDiff::Differentiate( f, parameters, M, result.data(), jacobians); From c1c8b0a1a327892692e2545d8adfda9b3f9b99b8 Mon Sep 17 00:00:00 2001 From: akrishnan86 Date: Mon, 20 Jul 2020 23:32:28 -0700 Subject: [PATCH 229/869] changing MFAS to oops and refactoring --- gtsam/sfm/MFAS.cpp | 138 +++++++++++++++++++++++++++++++++++ gtsam/sfm/MFAS.h | 107 +++++++++++++++++++++++++++ gtsam/sfm/mfas.cpp | 101 ------------------------- gtsam/sfm/mfas.h | 65 ----------------- gtsam/sfm/tests/testMFAS.cpp | 105 ++++++++++---------------- 5 files changed, 282 insertions(+), 234 deletions(-) create mode 100644 gtsam/sfm/MFAS.cpp create mode 100644 gtsam/sfm/MFAS.h delete mode 100644 gtsam/sfm/mfas.cpp delete mode 100644 gtsam/sfm/mfas.h diff --git a/gtsam/sfm/MFAS.cpp b/gtsam/sfm/MFAS.cpp new file mode 100644 index 000000000..76b7f532a --- /dev/null +++ b/gtsam/sfm/MFAS.cpp @@ -0,0 +1,138 @@ +#include + +using namespace gtsam; +using std::pair; +using std::vector; + +MFAS::MFAS(const std::shared_ptr> &nodes, + const std::shared_ptr &relativeTranslations, + const Unit3 &projection_direction) + : nodes_(nodes), relativeTranslations_(relativeTranslations), + relativeTranslationsForWeights_(std::make_shared()) { + // iterate over edges and flip all edges that have negative weights, + // while storing the magnitude of the weights. + for (auto it = relativeTranslations->begin(); + it != relativeTranslations->end(); it++) { + KeyPair edge = it->first; + double weight = it->second.dot(projection_direction); + if (weight < 0.0) { + std::swap(edge.first, edge.second); + weight *= -1; + } + positiveEdgeWeights_[edge] = weight; + } +} + +MFAS::MFAS(const std::shared_ptr> &nodes, + const std::map &edgeWeights) : nodes_(nodes), + relativeTranslations_(std::make_shared()), + relativeTranslationsForWeights_(std::make_shared< + TranslationEdges>()) { + // similar to the above direction constructor, but here weights are + // provided as input. + for (auto it = edgeWeights.begin(); it != edgeWeights.end(); it++) { + KeyPair edge = it->first; + + // When constructed like this, we do not have access to the relative translations. + // So, we store the unswapped edge in the relativeTranslationsForWeights_ map with a default + // Unit3 value. This helps retain the original direction of the edge in the returned result + // of computeOutlierWeights + relativeTranslationsForWeights_->insert({edge, Unit3()}); + + double weight = it->second; + if (weight < 0.0) { + // change the direction of the edge to make weight positive + std::swap(edge.first, edge.second); + weight *= -1; + } + positiveEdgeWeights_[edge] = weight; + } +} + +std::vector MFAS::computeOrdering() { + FastMap in_weights; // sum on weights of incoming edges for a node + FastMap out_weights; // sum on weights of outgoing edges for a node + FastMap > in_neighbors; + FastMap > out_neighbors; + + // populate neighbors and weights + for (auto it = positiveEdgeWeights_.begin(); it != positiveEdgeWeights_.end(); it++) { + const KeyPair &edge = it->first; + in_weights[edge.second] += it->second; + out_weights[edge.first] += it->second; + in_neighbors[edge.second].push_back(edge.first); + out_neighbors[edge.first].push_back(edge.second); + } + + // in each iteration, one node is appended to the ordered list + while (orderedNodes_.size() < nodes_->size()) { + + // finding the node with the max heuristic score + Key choice; + double max_score = 0.0; + + for (const Key &node : *nodes_) { + if (orderedPositions_.find(node) == orderedPositions_.end()) { + // is this a source + if (in_weights[node] < 1e-8) { + choice = node; + break; + } else { + double score = (out_weights[node] + 1) / (in_weights[node] + 1); + if (score > max_score) { + max_score = score; + choice = node; + } + } + } + } + // find its inbrs, adjust their wout_deg + for (auto it = in_neighbors[choice].begin(); + it != in_neighbors[choice].end(); ++it) + out_weights[*it] -= positiveEdgeWeights_[KeyPair(*it, choice)]; + // find its onbrs, adjust their win_deg + for (auto it = out_neighbors[choice].begin(); + it != out_neighbors[choice].end(); ++it) + in_weights[*it] -= positiveEdgeWeights_[KeyPair(choice, *it)]; + + orderedPositions_[choice] = orderedNodes_.size(); + orderedNodes_.push_back(choice); + } + return orderedNodes_; +} + +std::map MFAS::computeOutlierWeights() { + // if ordering has not been computed yet + if (orderedNodes_.size() != nodes_->size()) { + computeOrdering(); + } + // iterate over all edges + // start and end iterators depend on whether we are using relativeTranslations_ or + // relativeTranslationsForWeights_ to store the original edge directions + TranslationEdges::iterator start, end; + if (relativeTranslationsForWeights_->size() == 0) { + start = relativeTranslations_->begin(); + end = relativeTranslations_->end(); + } else { + start = relativeTranslationsForWeights_->begin(); + end = relativeTranslationsForWeights_->end(); + } + + for (auto it = start; it != end; it++) { + // relativeTranslations may have negative weight edges, we make sure all edges + // are along the postive direction by flipping them if they are not. + KeyPair edge = it->first; + if (positiveEdgeWeights_.find(edge) == positiveEdgeWeights_.end()) { + std::swap(edge.first, edge.second); + } + + // if the ordered position of nodes is not consistent with the edge + // direction for consistency second should be greater than first + if (orderedPositions_.at(edge.second) < orderedPositions_.at(edge.first)) { + outlierWeights_[it->first] = std::abs(positiveEdgeWeights_[edge]); + } else { + outlierWeights_[it->first] = 0; + } + } + return outlierWeights_; +} \ No newline at end of file diff --git a/gtsam/sfm/MFAS.h b/gtsam/sfm/MFAS.h new file mode 100644 index 000000000..20213a168 --- /dev/null +++ b/gtsam/sfm/MFAS.h @@ -0,0 +1,107 @@ +/* ---------------------------------------------------------------------------- + + * GTSAM Copyright 2010-2020, Georgia Tech Research Corporation, + * Atlanta, Georgia 30332-0415 + * All Rights Reserved + * Authors: Frank Dellaert, et al. (see THANKS for the full author list) + + * See LICENSE for the license information + + * -------------------------------------------------------------------------- */ + +#ifndef __MFAS_H__ +#define __MFAS_H__ + +#include +#include + +#include +#include +#include + +namespace gtsam { + +// used to represent edges between two nodes in the graph +using KeyPair = std::pair; +using TranslationEdges = std::map; + +/* + The MFAS class to solve a Minimum feedback arc set (MFAS) + problem. We implement the solution from: + Kyle Wilson and Noah Snavely, "Robust Global Translations with 1DSfM", + Proceedings of the European Conference on Computer Vision, ECCV 2014 + + Given a weighted directed graph, the objective in a Minimum feedback arc set + problem is to obtain a graph that does not contain any cycles by removing + edges such that the total weight of removed edges is minimum. +*/ +class MFAS { + public: + /* + * @brief Construct from the nodes in a graph (points in 3D), edges + * that are transation directions in 3D and the direction in + * which edges are to be projected. + * @param nodes Nodes in the graph + * @param relativeTranslations translation directions between nodes + * @param projectionDirection direction in which edges are to be projected + */ + MFAS(const std::shared_ptr> &nodes, + const std::shared_ptr &relativeTranslations, + const Unit3 &projectionDirection); + + /* + * Construct from the nodes in a graph and weighted directed edges + * between the graph. Not recommended for any purpose other than unit testing. + * The computeOutlierWeights method will return an empty output if this constructor + * is used. + * When used in a translation averaging context, these weights are obtained + * by projecting edges in a particular direction. + * @param nodes: Nodes in the graph + * @param edgeWeights: weights of edges in the graph (map from edge to signed double) + */ + MFAS(const std::shared_ptr> &nodes, + const std::map &edgeWeights); + + /* + * @brief Computes the "outlier weights" of the graph. We define the outlier weight + * of a edge to be zero if the edge in an inlier and the magnitude of its edgeWeight + * if it is an outlier. This function can only be used when constructing the + * @return outlierWeights: map from an edge to its outlier weight. + */ + std::map computeOutlierWeights(); + + /* + * Computes the 1D MFAS ordering of nodes in the graph + * @return orderedNodes: vector of nodes in the obtained order + */ + std::vector computeOrdering(); + + private: + // pointer to nodes in the graph + const std::shared_ptr> nodes_; + // pointer to translation edges (translation directions between two node points) + const std::shared_ptr relativeTranslations_; + + // relative translations when the object is initialized without using the actual + // relative translations, but with the weights from projecting in a certain + // direction. This is used for unit testing, but not in practice. + std::shared_ptr relativeTranslationsForWeights_; + + // edges with a direction such that all weights are positive + // i.e, edges that originally had negative weights are flipped + std::map positiveEdgeWeights_; + + // map from edges to their outlier weight + std::map outlierWeights_; + + // nodes arranged in the MFAS order + std::vector orderedNodes_; + + // map from nodes to their position in the MFAS order + // used to speed up computation (lookup) when computing outlierWeights_ + FastMap orderedPositions_; +}; + +} // namespace gtsam + +#endif // __MFAS_H__ diff --git a/gtsam/sfm/mfas.cpp b/gtsam/sfm/mfas.cpp deleted file mode 100644 index 4764f2703..000000000 --- a/gtsam/sfm/mfas.cpp +++ /dev/null @@ -1,101 +0,0 @@ -/* - This file defines functions used to solve a Minimum feedback arc set (MFAS) - problem. This code was forked and modified from Kyle Wilson's repository at - https://github.com/wilsonkl/SfM_Init. - Copyright (c) 2014, Kyle Wilson - All rights reserved. -*/ - -#include - -#include -#include -#include - -using std::map; -using std::pair; -using std::set; -using std::vector; - -namespace gtsam { -namespace mfas { - -void flipNegEdges(vector &edges, vector &weights) { - // now renumber the edges - for (unsigned int i = 0; i < edges.size(); ++i) { - if (weights[i] < 0.0) { - Key tmp = edges[i].second; - edges[i].second = edges[i].first; - edges[i].first = tmp; - weights[i] *= -1; - } - } -} - -void mfasRatio(const std::vector &edges, - const std::vector &weights, const KeyVector &nodes, - FastMap &ordered_positions) { - // initialize data structures - FastMap win_deg; - FastMap wout_deg; - FastMap > > inbrs; - FastMap > > onbrs; - - // stuff data structures - for (unsigned int ii = 0; ii < edges.size(); ++ii) { - int i = edges[ii].first; - int j = edges[ii].second; - double w = weights[ii]; - - win_deg[j] += w; - wout_deg[i] += w; - inbrs[j].push_back(pair(i, w)); - onbrs[i].push_back(pair(j, w)); - } - - unsigned int ordered_count = 0; - while (ordered_count < nodes.size()) { - // choose an unchosen node - Key choice; - double max_score = 0.0; - for (auto node : nodes) { - if (ordered_positions.find(node) == ordered_positions.end()) { - // is this a source - if (win_deg[node] < 1e-8) { - choice = node; - break; - } else { - double score = (wout_deg[node] + 1) / (win_deg[node] + 1); - if (score > max_score) { - max_score = score; - choice = node; - } - } - } - } - // find its inbrs, adjust their wout_deg - for (auto it = inbrs[choice].begin(); it != inbrs[choice].end(); ++it) - wout_deg[it->first] -= it->second; - // find its onbrs, adjust their win_deg - for (auto it = onbrs[choice].begin(); it != onbrs[choice].end(); ++it) - win_deg[it->first] -= it->second; - - ordered_positions[choice] = ordered_count++; - } -} - -void outlierWeights(const std::vector &edges, - const std::vector &weight, - const FastMap &ordered_positions, - FastMap &outlier_weights) { - // find the outlier edges - for (unsigned int i = 0; i < edges.size(); ++i) { - int x0 = ordered_positions.at(edges[i].first); - int x1 = ordered_positions.at(edges[i].second); - if ((x1 - x0) * weight[i] < 0) - outlier_weights[edges[i]] += weight[i] > 0 ? weight[i] : -weight[i]; - } -} - -} // namespace mfas -} // namespace gtsam \ No newline at end of file diff --git a/gtsam/sfm/mfas.h b/gtsam/sfm/mfas.h deleted file mode 100644 index c3d852b92..000000000 --- a/gtsam/sfm/mfas.h +++ /dev/null @@ -1,65 +0,0 @@ -/* - This file defines functions used to solve a Minimum feedback arc set (MFAS) - problem. This code was forked and modified from Kyle Wilson's repository at - https://github.com/wilsonkl/SfM_Init. - Copyright (c) 2014, Kyle Wilson - All rights reserved. - - Given a weighted directed graph, the objective in a Minimum feedback arc set - problem is to obtain a graph that does not contain any cycles by removing - edges such that the total weight of removed edges is minimum. -*/ -#ifndef __MFAS_H__ -#define __MFAS_H__ - -#include - -#include -#include - -namespace gtsam { - -using KeyPair = std::pair; - -namespace mfas { - -/* - * Given a vector of KeyPairs that constitutes edges in a graph and the weights - * corresponding to these edges, this function changes all the weights to - * positive numbers by flipping the direction of the edges that have a negative - * weight. The changes are made in place. - * @param edges reference to vector of KeyPairs - * @param weights weights corresponding to edges - */ -void flipNegEdges(std::vector &edges, std::vector &weights); - -/* - * Computes the MFAS ordering, ie an ordering of the nodes in the graph such - * that the source of any edge appears before its destination in the ordering. - * The weight of edges that are removed to obtain this ordering is minimized. - * @param edges: edges in the graph - * @param weights: weights corresponding to the edges (have to be positive) - * @param nodes: nodes in the graph - * @param ordered_positions: map from node to position in the ordering (0 - * indexed) - */ -void mfasRatio(const std::vector &edges, - const std::vector &weights, const KeyVector &nodes, - FastMap &ordered_positions); - -/* - * Returns the weights of edges that are not consistent with the input ordering. - * @param edges in the graph - * @param weights of the edges in the graph - * @param ordered_positions: ordering (obtained from MFAS solution) - * @param outlier_weights: reference to a map from edges to their "outlier - * weights" - */ -void outlierWeights(const std::vector &edges, - const std::vector &weight, - const FastMap &ordered_positions, - FastMap &outlier_weights); - -} // namespace mfas -} // namespace gtsam -#endif // __MFAS_H__ diff --git a/gtsam/sfm/tests/testMFAS.cpp b/gtsam/sfm/tests/testMFAS.cpp index d5daee1a6..8b0192ade 100644 --- a/gtsam/sfm/tests/testMFAS.cpp +++ b/gtsam/sfm/tests/testMFAS.cpp @@ -1,5 +1,5 @@ -#include - +#include +#include #include using namespace std; @@ -8,75 +8,52 @@ using namespace gtsam; /* We (partially) use the example from the paper on 1dsfm * (https://research.cs.cornell.edu/1dsfm/docs/1DSfM_ECCV14.pdf, Fig 1, Page 5) * for the unit tests here. The only change is that we leave out node 4 and use - * only nodes 0-3. This not only makes the test easier to understand but also + * only nodes 0-3. This makes the test easier to understand and also * avoids an ambiguity in the ground truth ordering that arises due to - * insufficient edges in the geaph. */ + * insufficient edges in the geaph when using the 4th node. */ // edges in the graph - last edge from node 3 to 0 is an outlier vector graph = {make_pair(3, 2), make_pair(0, 1), make_pair(3, 1), make_pair(1, 2), make_pair(0, 2), make_pair(3, 0)}; // nodes in the graph -KeyVector nodes = {Key(0), Key(1), Key(2), Key(3)}; +vector nodes = {Key(0), Key(1), Key(2), Key(3)}; // weights from projecting in direction-1 (bad direction, outlier accepted) vector weights1 = {2, 1.5, 0.5, 0.25, 1, 0.75}; // weights from projecting in direction-2 (good direction, outlier rejected) vector weights2 = {0.5, 0.75, -0.25, 0.75, 1, 0.5}; -// Testing the flipNegEdges function for weights1 -TEST(MFAS, FlipNegEdges) { - vector graph_copy = graph; - vector weights1_positive = weights1; - mfas::flipNegEdges(graph_copy, weights1_positive); - - // resulting graph and edges must be of same size - EXPECT_LONGS_EQUAL(graph_copy.size(), graph.size()); - EXPECT_LONGS_EQUAL(weights1_positive.size(), weights1.size()); - - for (unsigned int i = 0; i < weights1.size(); i++) { - if (weights1[i] < 0) { - // if original weight was negative, edges must be flipped and new weight - // must be positive - EXPECT_DOUBLES_EQUAL(weights1_positive[i], -weights1[i], 1e-6); - EXPECT(graph_copy[i].first == graph[i].second && - graph_copy[i].second == graph[i].first); - } else { - // unchanged if original weight was positive - EXPECT_DOUBLES_EQUAL(weights1_positive[i], weights1[i], 1e-6); - EXPECT(graph_copy[i].first == graph[i].first && - graph_copy[i].second == graph[i].second); - } +// helper function to obtain map from keypairs to weights from the +// vector representations +std::map getEdgeWeights(const vector &graph, + const vector &weights) { + std::map edgeWeights; + for (size_t i = 0; i < graph.size(); i++) { + edgeWeights[graph[i]] = weights[i]; } + cout << "returning edge weights " << edgeWeights.size() << endl; + return edgeWeights; } // test the ordering and the outlierWeights function using weights2 - outlier // edge is rejected when projected in a direction that gives weights2 TEST(MFAS, OrderingWeights2) { - vector graph_copy = graph; - vector weights2_positive = weights2; - mfas::flipNegEdges(graph_copy, weights2_positive); - FastMap ordered_positions; - // compute ordering from positive edge weights - mfas::mfasRatio(graph_copy, weights2_positive, nodes, ordered_positions); + MFAS mfas_obj(make_shared>(nodes), getEdgeWeights(graph, weights2)); - // expected ordering in this example - FastMap gt_ordered_positions; - gt_ordered_positions[0] = 0; - gt_ordered_positions[1] = 1; - gt_ordered_positions[3] = 2; - gt_ordered_positions[2] = 3; + vector ordered_nodes = mfas_obj.computeOrdering(); + + // ground truth (expected) ordering in this example + vector gt_ordered_nodes = {0, 1, 3, 2}; // check if the expected ordering is obtained - for (auto node : nodes) { - EXPECT_LONGS_EQUAL(gt_ordered_positions[node], ordered_positions[node]); + for (size_t i = 0; i < ordered_nodes.size(); i++) { + EXPECT_LONGS_EQUAL(gt_ordered_nodes[i], ordered_nodes[i]); } - // testing the outlierWeights method - FastMap outlier_weights; - mfas::outlierWeights(graph_copy, weights2_positive, gt_ordered_positions, - outlier_weights); + map outlier_weights = mfas_obj.computeOutlierWeights(); + // since edge between 3 and 0 is inconsistent with the ordering, it must have // positive outlier weight, other outlier weights must be zero - for (auto &edge : graph_copy) { + for (auto &edge : graph) { if (edge == make_pair(Key(3), Key(0)) || edge == make_pair(Key(0), Key(3))) { EXPECT_DOUBLES_EQUAL(outlier_weights[edge], 0.5, 1e-6); @@ -87,33 +64,25 @@ TEST(MFAS, OrderingWeights2) { } // test the ordering function and the outlierWeights method using -// weights2 (outlier edge is accepted when projected in a direction that -// produces weights2) +// weights1 (outlier edge is accepted when projected in a direction that +// produces weights1) TEST(MFAS, OrderingWeights1) { - vector graph_copy = graph; - vector weights1_positive = weights1; - mfas::flipNegEdges(graph_copy, weights1_positive); - FastMap ordered_positions; - // compute ordering from positive edge weights - mfas::mfasRatio(graph_copy, weights1_positive, nodes, ordered_positions); + MFAS mfas_obj(make_shared>(nodes), getEdgeWeights(graph, weights1)); - // expected "ground truth" ordering in this example - FastMap gt_ordered_positions; - gt_ordered_positions[3] = 0; - gt_ordered_positions[0] = 1; - gt_ordered_positions[1] = 2; - gt_ordered_positions[2] = 3; + vector ordered_nodes = mfas_obj.computeOrdering(); + + // "ground truth" expected ordering in this example + vector gt_ordered_nodes = {3, 0, 1, 2}; // check if the expected ordering is obtained - for (auto node : nodes) { - EXPECT_LONGS_EQUAL(gt_ordered_positions[node], ordered_positions[node]); + for (size_t i = 0; i < ordered_nodes.size(); i++) { + EXPECT_LONGS_EQUAL(gt_ordered_nodes[i], ordered_nodes[i]); } - // since all edges (including the outlier) are consistent with this ordering, - // all outlier_weights must be zero - FastMap outlier_weights; - mfas::outlierWeights(graph, weights1_positive, gt_ordered_positions, - outlier_weights); + map outlier_weights = mfas_obj.computeOutlierWeights(); + + // since edge between 3 and 0 is inconsistent with the ordering, it must have + // positive outlier weight, other outlier weights must be zero for (auto &edge : graph) { EXPECT_DOUBLES_EQUAL(outlier_weights[edge], 0, 1e-6); } From 0eec6fbeec7e1568b564dbfcd2cffa6c0a001a7d Mon Sep 17 00:00:00 2001 From: akrishnan86 Date: Mon, 20 Jul 2020 23:45:45 -0700 Subject: [PATCH 230/869] minor comments change --- gtsam/sfm/MFAS.cpp | 2 +- gtsam/sfm/MFAS.h | 17 +++++++++-------- gtsam/sfm/tests/testMFAS.cpp | 6 ++++-- 3 files changed, 14 insertions(+), 11 deletions(-) diff --git a/gtsam/sfm/MFAS.cpp b/gtsam/sfm/MFAS.cpp index 76b7f532a..8c3e3596a 100644 --- a/gtsam/sfm/MFAS.cpp +++ b/gtsam/sfm/MFAS.cpp @@ -120,7 +120,7 @@ std::map MFAS::computeOutlierWeights() { for (auto it = start; it != end; it++) { // relativeTranslations may have negative weight edges, we make sure all edges - // are along the postive direction by flipping them if they are not. + // are along the positive direction by flipping them if they are not. KeyPair edge = it->first; if (positiveEdgeWeights_.find(edge) == positiveEdgeWeights_.end()) { std::swap(edge.first, edge.second); diff --git a/gtsam/sfm/MFAS.h b/gtsam/sfm/MFAS.h index 20213a168..10052548b 100644 --- a/gtsam/sfm/MFAS.h +++ b/gtsam/sfm/MFAS.h @@ -25,7 +25,7 @@ namespace gtsam { using KeyPair = std::pair; using TranslationEdges = std::map; -/* +/** The MFAS class to solve a Minimum feedback arc set (MFAS) problem. We implement the solution from: Kyle Wilson and Noah Snavely, "Robust Global Translations with 1DSfM", @@ -34,12 +34,13 @@ using TranslationEdges = std::map; Given a weighted directed graph, the objective in a Minimum feedback arc set problem is to obtain a graph that does not contain any cycles by removing edges such that the total weight of removed edges is minimum. + @addtogroup SFM */ class MFAS { public: - /* + /** * @brief Construct from the nodes in a graph (points in 3D), edges - * that are transation directions in 3D and the direction in + * that are translation directions in 3D and the direction in * which edges are to be projected. * @param nodes Nodes in the graph * @param relativeTranslations translation directions between nodes @@ -49,8 +50,8 @@ class MFAS { const std::shared_ptr &relativeTranslations, const Unit3 &projectionDirection); - /* - * Construct from the nodes in a graph and weighted directed edges + /** + * @brief Construct from the nodes in a graph and weighted directed edges * between the graph. Not recommended for any purpose other than unit testing. * The computeOutlierWeights method will return an empty output if this constructor * is used. @@ -62,7 +63,7 @@ class MFAS { MFAS(const std::shared_ptr> &nodes, const std::map &edgeWeights); - /* + /** * @brief Computes the "outlier weights" of the graph. We define the outlier weight * of a edge to be zero if the edge in an inlier and the magnitude of its edgeWeight * if it is an outlier. This function can only be used when constructing the @@ -70,8 +71,8 @@ class MFAS { */ std::map computeOutlierWeights(); - /* - * Computes the 1D MFAS ordering of nodes in the graph + /** + * @brief Computes the 1D MFAS ordering of nodes in the graph * @return orderedNodes: vector of nodes in the obtained order */ std::vector computeOrdering(); diff --git a/gtsam/sfm/tests/testMFAS.cpp b/gtsam/sfm/tests/testMFAS.cpp index 8b0192ade..345b3a5d4 100644 --- a/gtsam/sfm/tests/testMFAS.cpp +++ b/gtsam/sfm/tests/testMFAS.cpp @@ -5,12 +5,14 @@ using namespace std; using namespace gtsam; -/* We (partially) use the example from the paper on 1dsfm +/** + * We (partially) use the example from the paper on 1dsfm * (https://research.cs.cornell.edu/1dsfm/docs/1DSfM_ECCV14.pdf, Fig 1, Page 5) * for the unit tests here. The only change is that we leave out node 4 and use * only nodes 0-3. This makes the test easier to understand and also * avoids an ambiguity in the ground truth ordering that arises due to - * insufficient edges in the geaph when using the 4th node. */ + * insufficient edges in the geaph when using the 4th node. + */ // edges in the graph - last edge from node 3 to 0 is an outlier vector graph = {make_pair(3, 2), make_pair(0, 1), make_pair(3, 1), From 2605e10c27cdeacf5a65ff4dbc1f332e6eea44d0 Mon Sep 17 00:00:00 2001 From: Frank dellaert Date: Tue, 21 Jul 2020 11:04:36 -0400 Subject: [PATCH 231/869] Fixed conventions for Jacobians --- GTSAM-Concepts.md | 4 +- gtsam/geometry/Pose3.cpp | 158 ++++++++++++++++++++------------------- gtsam/geometry/Pose3.h | 80 ++++++++++---------- 3 files changed, 122 insertions(+), 120 deletions(-) diff --git a/GTSAM-Concepts.md b/GTSAM-Concepts.md index a6cfee984..953357ede 100644 --- a/GTSAM-Concepts.md +++ b/GTSAM-Concepts.md @@ -72,9 +72,9 @@ A Lie group is both a manifold *and* a group. Hence, a LIE_GROUP type should imp However, we now also need to be able to evaluate the derivatives of compose and inverse. Hence, we have the following extra valid static functions defined in the struct `gtsam::traits`: -* `r = traits::Compose(p,q,Hq,Hp)` +* `r = traits::Compose(p,q,Hp,Hq)` * `q = traits::Inverse(p,Hp)` -* `r = traits::Between(p,q,Hq,H2p)` +* `r = traits::Between(p,q,Hp,Hq)` where above the *H* arguments stand for optional Jacobian arguments. That makes it possible to create factors implementing priors (PriorFactor) or relations between two instances of a Lie group type (BetweenFactor). diff --git a/gtsam/geometry/Pose3.cpp b/gtsam/geometry/Pose3.cpp index 31033a027..0ee19ef76 100644 --- a/gtsam/geometry/Pose3.cpp +++ b/gtsam/geometry/Pose3.cpp @@ -19,8 +19,10 @@ #include #include -#include #include +#include +#include +#include using namespace std; @@ -36,10 +38,10 @@ Pose3::Pose3(const Pose2& pose2) : } /* ************************************************************************* */ -Pose3 Pose3::Create(const Rot3& R, const Point3& t, OptionalJacobian<6, 3> H1, - OptionalJacobian<6, 3> H2) { - if (H1) *H1 << I_3x3, Z_3x3; - if (H2) *H2 << Z_3x3, R.transpose(); +Pose3 Pose3::Create(const Rot3& R, const Point3& t, OptionalJacobian<6, 3> HR, + OptionalJacobian<6, 3> Ht) { + if (HR) *HR << I_3x3, Z_3x3; + if (Ht) *Ht << Z_3x3, R.transpose(); return Pose3(R, t); } @@ -72,15 +74,15 @@ Matrix6 Pose3::adjointMap(const Vector6& xi) { /* ************************************************************************* */ Vector6 Pose3::adjoint(const Vector6& xi, const Vector6& y, - OptionalJacobian<6,6> H) { - if (H) { - H->setZero(); + OptionalJacobian<6, 6> Hxi) { + if (Hxi) { + Hxi->setZero(); for (int i = 0; i < 6; ++i) { Vector6 dxi; dxi.setZero(); dxi(i) = 1.0; Matrix6 Gi = adjointMap(dxi); - H->col(i) = Gi * y; + Hxi->col(i) = Gi * y; } } return adjointMap(xi) * y; @@ -88,15 +90,15 @@ Vector6 Pose3::adjoint(const Vector6& xi, const Vector6& y, /* ************************************************************************* */ Vector6 Pose3::adjointTranspose(const Vector6& xi, const Vector6& y, - OptionalJacobian<6,6> H) { - if (H) { - H->setZero(); + OptionalJacobian<6, 6> Hxi) { + if (Hxi) { + Hxi->setZero(); for (int i = 0; i < 6; ++i) { Vector6 dxi; dxi.setZero(); dxi(i) = 1.0; Matrix6 GTi = adjointMap(dxi).transpose(); - H->col(i) = GTi * y; + Hxi->col(i) = GTi * y; } } return adjointMap(xi).transpose() * y; @@ -116,8 +118,8 @@ bool Pose3::equals(const Pose3& pose, double tol) const { /* ************************************************************************* */ /** Modified from Murray94book version (which assumes w and v normalized?) */ -Pose3 Pose3::Expmap(const Vector6& xi, OptionalJacobian<6, 6> H) { - if (H) *H = ExpmapDerivative(xi); +Pose3 Pose3::Expmap(const Vector6& xi, OptionalJacobian<6, 6> Hxi) { + if (Hxi) *Hxi = ExpmapDerivative(xi); // get angular velocity omega and translational velocity v from twist xi Vector3 omega(xi(0), xi(1), xi(2)), v(xi(3), xi(4), xi(5)); @@ -125,8 +127,8 @@ Pose3 Pose3::Expmap(const Vector6& xi, OptionalJacobian<6, 6> H) { Rot3 R = Rot3::Expmap(omega); double theta2 = omega.dot(omega); if (theta2 > std::numeric_limits::epsilon()) { - Vector3 t_parallel = omega * omega.dot(v); // translation parallel to axis - Vector3 omega_cross_v = omega.cross(v); // points towards axis + Vector3 t_parallel = omega * omega.dot(v); // translation parallel to axis + Vector3 omega_cross_v = omega.cross(v); // points towards axis Vector3 t = (omega_cross_v - R * omega_cross_v + t_parallel) / theta2; return Pose3(R, t); } else { @@ -135,10 +137,10 @@ Pose3 Pose3::Expmap(const Vector6& xi, OptionalJacobian<6, 6> H) { } /* ************************************************************************* */ -Vector6 Pose3::Logmap(const Pose3& p, OptionalJacobian<6, 6> H) { - if (H) *H = LogmapDerivative(p); - const Vector3 w = Rot3::Logmap(p.rotation()); - const Vector3 T = p.translation(); +Vector6 Pose3::Logmap(const Pose3& pose, OptionalJacobian<6, 6> Hpose) { + if (Hpose) *Hpose = LogmapDerivative(pose); + const Vector3 w = Rot3::Logmap(pose.rotation()); + const Vector3 T = pose.translation(); const double t = w.norm(); if (t < 1e-10) { Vector6 log; @@ -158,33 +160,33 @@ Vector6 Pose3::Logmap(const Pose3& p, OptionalJacobian<6, 6> H) { } /* ************************************************************************* */ -Pose3 Pose3::ChartAtOrigin::Retract(const Vector6& xi, ChartJacobian H) { +Pose3 Pose3::ChartAtOrigin::Retract(const Vector6& xi, ChartJacobian Hxi) { #ifdef GTSAM_POSE3_EXPMAP - return Expmap(xi, H); + return Expmap(xi, Hxi); #else Matrix3 DR; - Rot3 R = Rot3::Retract(xi.head<3>(), H ? &DR : 0); - if (H) { - *H = I_6x6; - H->topLeftCorner<3,3>() = DR; + Rot3 R = Rot3::Retract(xi.head<3>(), Hxi ? &DR : 0); + if (Hxi) { + *Hxi = I_6x6; + Hxi->topLeftCorner<3, 3>() = DR; } return Pose3(R, Point3(xi.tail<3>())); #endif } /* ************************************************************************* */ -Vector6 Pose3::ChartAtOrigin::Local(const Pose3& T, ChartJacobian H) { +Vector6 Pose3::ChartAtOrigin::Local(const Pose3& pose, ChartJacobian Hpose) { #ifdef GTSAM_POSE3_EXPMAP - return Logmap(T, H); + return Logmap(pose, Hpose); #else Matrix3 DR; - Vector3 omega = Rot3::LocalCoordinates(T.rotation(), H ? &DR : 0); - if (H) { - *H = I_6x6; - H->topLeftCorner<3,3>() = DR; + Vector3 omega = Rot3::LocalCoordinates(pose.rotation(), Hpose ? &DR : 0); + if (Hpose) { + *Hpose = I_6x6; + Hpose->topLeftCorner<3, 3>() = DR; } Vector6 xi; - xi << omega, T.translation(); + xi << omega, pose.translation(); return xi; #endif } @@ -261,16 +263,16 @@ Matrix6 Pose3::LogmapDerivative(const Pose3& pose) { } /* ************************************************************************* */ -const Point3& Pose3::translation(OptionalJacobian<3, 6> H) const { - if (H) *H << Z_3x3, rotation().matrix(); +const Point3& Pose3::translation(OptionalJacobian<3, 6> Hself) const { + if (Hself) *Hself << Z_3x3, rotation().matrix(); return t_; } /* ************************************************************************* */ -const Rot3& Pose3::rotation(OptionalJacobian<3, 6> H) const { - if (H) { - *H << I_3x3, Z_3x3; +const Rot3& Pose3::rotation(OptionalJacobian<3, 6> Hself) const { + if (Hself) { + *Hself << I_3x3, Z_3x3; } return R_; } @@ -299,101 +301,101 @@ Pose3 Pose3::transform_to(const Pose3& pose) const { #endif /* ************************************************************************* */ -Pose3 Pose3::transformPoseTo(const Pose3& wTb, OptionalJacobian<6, 6> H1, - OptionalJacobian<6, 6> H2) const { - if (H1) *H1 = -wTb.inverse().AdjointMap() * AdjointMap(); - if (H2) *H2 = I_6x6; +Pose3 Pose3::transformPoseTo(const Pose3& wTb, OptionalJacobian<6, 6> Hself, + OptionalJacobian<6, 6> HwTb) const { + if (Hself) *Hself = -wTb.inverse().AdjointMap() * AdjointMap(); + if (HwTb) *HwTb = I_6x6; const Pose3& wTa = *this; return wTa.inverse() * wTb; } /* ************************************************************************* */ -Point3 Pose3::transformFrom(const Point3& p, OptionalJacobian<3,6> Dpose, - OptionalJacobian<3,3> Dpoint) const { +Point3 Pose3::transformFrom(const Point3& p, OptionalJacobian<3, 6> Hself, + OptionalJacobian<3, 3> Hpoint) const { // Only get matrix once, to avoid multiple allocations, // as well as multiple conversions in the Quaternion case const Matrix3 R = R_.matrix(); - if (Dpose) { - Dpose->leftCols<3>() = R * skewSymmetric(-p.x(), -p.y(), -p.z()); - Dpose->rightCols<3>() = R; + if (Hself) { + Hself->leftCols<3>() = R * skewSymmetric(-p.x(), -p.y(), -p.z()); + Hself->rightCols<3>() = R; } - if (Dpoint) { - *Dpoint = R; + if (Hpoint) { + *Hpoint = R; } return R_ * p + t_; } /* ************************************************************************* */ -Point3 Pose3::transformTo(const Point3& p, OptionalJacobian<3,6> Dpose, - OptionalJacobian<3,3> Dpoint) const { +Point3 Pose3::transformTo(const Point3& p, OptionalJacobian<3, 6> Hself, + OptionalJacobian<3, 3> Hpoint) const { // Only get transpose once, to avoid multiple allocations, // as well as multiple conversions in the Quaternion case const Matrix3 Rt = R_.transpose(); const Point3 q(Rt*(p - t_)); - if (Dpose) { + if (Hself) { const double wx = q.x(), wy = q.y(), wz = q.z(); - (*Dpose) << + (*Hself) << 0.0, -wz, +wy,-1.0, 0.0, 0.0, +wz, 0.0, -wx, 0.0,-1.0, 0.0, -wy, +wx, 0.0, 0.0, 0.0,-1.0; } - if (Dpoint) { - *Dpoint = Rt; + if (Hpoint) { + *Hpoint = Rt; } return q; } /* ************************************************************************* */ -double Pose3::range(const Point3& point, OptionalJacobian<1, 6> H1, - OptionalJacobian<1, 3> H2) const { +double Pose3::range(const Point3& point, OptionalJacobian<1, 6> Hself, + OptionalJacobian<1, 3> Hpoint) const { Matrix36 D_local_pose; Matrix3 D_local_point; - Point3 local = transformTo(point, H1 ? &D_local_pose : 0, H2 ? &D_local_point : 0); - if (!H1 && !H2) { + Point3 local = transformTo(point, Hself ? &D_local_pose : 0, Hpoint ? &D_local_point : 0); + if (!Hself && !Hpoint) { return local.norm(); } else { Matrix13 D_r_local; const double r = norm3(local, D_r_local); - if (H1) *H1 = D_r_local * D_local_pose; - if (H2) *H2 = D_r_local * D_local_point; + if (Hself) *Hself = D_r_local * D_local_pose; + if (Hpoint) *Hpoint = D_r_local * D_local_point; return r; } } /* ************************************************************************* */ -double Pose3::range(const Pose3& pose, OptionalJacobian<1, 6> H1, - OptionalJacobian<1, 6> H2) const { +double Pose3::range(const Pose3& pose, OptionalJacobian<1, 6> Hself, + OptionalJacobian<1, 6> Hpose) const { Matrix13 D_local_point; - double r = range(pose.translation(), H1, H2 ? &D_local_point : 0); - if (H2) *H2 << Matrix13::Zero(), D_local_point * pose.rotation().matrix(); + double r = range(pose.translation(), Hself, Hpose ? &D_local_point : 0); + if (Hpose) *Hpose << Matrix13::Zero(), D_local_point * pose.rotation().matrix(); return r; } /* ************************************************************************* */ -Unit3 Pose3::bearing(const Point3& point, OptionalJacobian<2, 6> H1, - OptionalJacobian<2, 3> H2) const { +Unit3 Pose3::bearing(const Point3& point, OptionalJacobian<2, 6> Hself, + OptionalJacobian<2, 3> Hpoint) const { Matrix36 D_local_pose; Matrix3 D_local_point; - Point3 local = transformTo(point, H1 ? &D_local_pose : 0, H2 ? &D_local_point : 0); - if (!H1 && !H2) { + Point3 local = transformTo(point, Hself ? &D_local_pose : 0, Hpoint ? &D_local_point : 0); + if (!Hself && !Hpoint) { return Unit3(local); } else { Matrix23 D_b_local; Unit3 b = Unit3::FromPoint3(local, D_b_local); - if (H1) *H1 = D_b_local * D_local_pose; - if (H2) *H2 = D_b_local * D_local_point; + if (Hself) *Hself = D_b_local * D_local_pose; + if (Hpoint) *Hpoint = D_b_local * D_local_point; return b; } } /* ************************************************************************* */ -Unit3 Pose3::bearing(const Pose3& pose, OptionalJacobian<2, 6> H1, - OptionalJacobian<2, 6> H2) const { - if (H2) { - H2->setZero(); - return bearing(pose.translation(), H1, H2.cols<3>(3)); +Unit3 Pose3::bearing(const Pose3& pose, OptionalJacobian<2, 6> Hself, + OptionalJacobian<2, 6> Hpose) const { + if (Hpose) { + Hpose->setZero(); + return bearing(pose.translation(), Hself, Hpose.cols<3>(3)); } - return bearing(pose.translation(), H1, boost::none); + return bearing(pose.translation(), Hself, boost::none); } /* ************************************************************************* */ diff --git a/gtsam/geometry/Pose3.h b/gtsam/geometry/Pose3.h index ced3b904b..f56e6903a 100644 --- a/gtsam/geometry/Pose3.h +++ b/gtsam/geometry/Pose3.h @@ -75,8 +75,8 @@ public: /// Named constructor with derivatives static Pose3 Create(const Rot3& R, const Point3& t, - OptionalJacobian<6, 3> H1 = boost::none, - OptionalJacobian<6, 3> H2 = boost::none); + OptionalJacobian<6, 3> HR = boost::none, + OptionalJacobian<6, 3> Ht = boost::none); /** * Create Pose3 by aligning two point pairs @@ -117,10 +117,10 @@ public: /// @{ /// Exponential map at identity - create a rotation from canonical coordinates \f$ [R_x,R_y,R_z,T_x,T_y,T_z] \f$ - static Pose3 Expmap(const Vector6& xi, OptionalJacobian<6, 6> H = boost::none); + static Pose3 Expmap(const Vector6& xi, OptionalJacobian<6, 6> Hxi = boost::none); /// Log map at identity - return the canonical coordinates \f$ [R_x,R_y,R_z,T_x,T_y,T_z] \f$ of this rotation - static Vector6 Logmap(const Pose3& p, OptionalJacobian<6, 6> H = boost::none); + static Vector6 Logmap(const Pose3& pose, OptionalJacobian<6, 6> Hpose = boost::none); /** * Calculate Adjoint map, transforming a twist in the this pose's (i.e, body) frame to the world spatial frame @@ -157,7 +157,7 @@ public: * Action of the adjointMap on a Lie-algebra vector y, with optional derivatives */ static Vector6 adjoint(const Vector6 &xi, const Vector6 &y, - OptionalJacobian<6, 6> = boost::none); + OptionalJacobian<6, 6> Hxi = boost::none); // temporary fix for wrappers until case issue is resolved static Matrix6 adjointMap_(const Vector6 &xi) { return adjointMap(xi);} @@ -167,7 +167,7 @@ public: * The dual version of adjoint action, acting on the dual space of the Lie-algebra vector space. */ static Vector6 adjointTranspose(const Vector6& xi, const Vector6& y, - OptionalJacobian<6, 6> H = boost::none); + OptionalJacobian<6, 6> Hxi = boost::none); /// Derivative of Expmap static Matrix6 ExpmapDerivative(const Vector6& xi); @@ -177,8 +177,8 @@ public: // Chart at origin, depends on compile-time flag GTSAM_POSE3_EXPMAP struct ChartAtOrigin { - static Pose3 Retract(const Vector6& v, ChartJacobian H = boost::none); - static Vector6 Local(const Pose3& r, ChartJacobian H = boost::none); + static Pose3 Retract(const Vector6& xi, ChartJacobian Hxi = boost::none); + static Vector6 Local(const Pose3& pose, ChartJacobian Hpose = boost::none); }; using LieGroup::inverse; // version with derivative @@ -202,12 +202,12 @@ public: /** * @brief takes point in Pose coordinates and transforms it to world coordinates * @param p point in Pose coordinates - * @param Dpose optional 3*6 Jacobian wrpt this pose - * @param Dpoint optional 3*3 Jacobian wrpt point + * @param Hself optional 3*6 Jacobian wrpt this pose + * @param Hpoint optional 3*3 Jacobian wrpt point * @return point in world coordinates */ - Point3 transformFrom(const Point3& p, OptionalJacobian<3, 6> Dpose = - boost::none, OptionalJacobian<3, 3> Dpoint = boost::none) const; + Point3 transformFrom(const Point3& p, OptionalJacobian<3, 6> Hself = + boost::none, OptionalJacobian<3, 3> Hpoint = boost::none) const; /** syntactic sugar for transformFrom */ inline Point3 operator*(const Point3& p) const { @@ -217,22 +217,22 @@ public: /** * @brief takes point in world coordinates and transforms it to Pose coordinates * @param p point in world coordinates - * @param Dpose optional 3*6 Jacobian wrpt this pose - * @param Dpoint optional 3*3 Jacobian wrpt point + * @param Hself optional 3*6 Jacobian wrpt this pose + * @param Hpoint optional 3*3 Jacobian wrpt point * @return point in Pose coordinates */ - Point3 transformTo(const Point3& p, OptionalJacobian<3, 6> Dpose = - boost::none, OptionalJacobian<3, 3> Dpoint = boost::none) const; + Point3 transformTo(const Point3& p, OptionalJacobian<3, 6> Hself = + boost::none, OptionalJacobian<3, 3> Hpoint = boost::none) const; /// @} /// @name Standard Interface /// @{ /// get rotation - const Rot3& rotation(OptionalJacobian<3, 6> H = boost::none) const; + const Rot3& rotation(OptionalJacobian<3, 6> Hself = boost::none) const; /// get translation - const Point3& translation(OptionalJacobian<3, 6> H = boost::none) const; + const Point3& translation(OptionalJacobian<3, 6> Hself = boost::none) const; /// get x double x() const { @@ -256,32 +256,32 @@ public: Pose3 transformPoseFrom(const Pose3& pose) const; /** receives a pose in world coordinates and transforms it to local coordinates */ - Pose3 transformPoseTo(const Pose3& pose, OptionalJacobian<6, 6> H1 = boost::none, - OptionalJacobian<6, 6> H2 = boost::none) const; + Pose3 transformPoseTo(const Pose3& pose, OptionalJacobian<6, 6> Hself = boost::none, + OptionalJacobian<6, 6> Hpose = boost::none) const; /** * Calculate range to a landmark * @param point 3D location of landmark * @return range (double) */ - double range(const Point3& point, OptionalJacobian<1, 6> H1 = boost::none, - OptionalJacobian<1, 3> H2 = boost::none) const; + double range(const Point3& point, OptionalJacobian<1, 6> Hself = boost::none, + OptionalJacobian<1, 3> Hpoint = boost::none) const; /** * Calculate range to another pose * @param pose Other SO(3) pose * @return range (double) */ - double range(const Pose3& pose, OptionalJacobian<1, 6> H1 = boost::none, - OptionalJacobian<1, 6> H2 = boost::none) const; + double range(const Pose3& pose, OptionalJacobian<1, 6> Hself = boost::none, + OptionalJacobian<1, 6> Hpose = boost::none) const; /** * Calculate bearing to a landmark * @param point 3D location of landmark * @return bearing (Unit3) */ - Unit3 bearing(const Point3& point, OptionalJacobian<2, 6> H1 = boost::none, - OptionalJacobian<2, 3> H2 = boost::none) const; + Unit3 bearing(const Point3& point, OptionalJacobian<2, 6> Hself = boost::none, + OptionalJacobian<2, 3> Hpoint = boost::none) const; /** * Calculate bearing to another pose @@ -289,8 +289,8 @@ public: * information is ignored. * @return bearing (Unit3) */ - Unit3 bearing(const Pose3& pose, OptionalJacobian<2, 6> H1 = boost::none, - OptionalJacobian<2, 6> H2 = boost::none) const; + Unit3 bearing(const Pose3& pose, OptionalJacobian<2, 6> Hself = boost::none, + OptionalJacobian<2, 6> Hpose = boost::none) const; /// @} /// @name Advanced Interface @@ -321,20 +321,20 @@ public: #ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V4 /// @name Deprecated /// @{ - Point3 transform_from(const Point3& p, - OptionalJacobian<3, 6> Dpose = boost::none, - OptionalJacobian<3, 3> Dpoint = boost::none) const { - return transformFrom(p, Dpose, Dpoint); + Point3 transform_from(const Point3& point, + OptionalJacobian<3, 6> Hself = boost::none, + OptionalJacobian<3, 3> Hpoint = boost::none) const { + return transformFrom(point, Hself, Hpoint); } - Point3 transform_to(const Point3& p, - OptionalJacobian<3, 6> Dpose = boost::none, - OptionalJacobian<3, 3> Dpoint = boost::none) const { - return transformTo(p, Dpose, Dpoint); + Point3 transform_to(const Point3& point, + OptionalJacobian<3, 6> Hself = boost::none, + OptionalJacobian<3, 3> Hpoint = boost::none) const { + return transformTo(point, Hself, Hpoint); } - Pose3 transform_pose_to(const Pose3& pose, - OptionalJacobian<6, 6> H1 = boost::none, - OptionalJacobian<6, 6> H2 = boost::none) const { - return transformPoseTo(pose, H1, H2); + Pose3 transform_pose_to(const Pose3& pose, + OptionalJacobian<6, 6> Hself = boost::none, + OptionalJacobian<6, 6> Hpose = boost::none) const { + return transformPoseTo(pose, Hself, Hpose); } /** * @deprecated: this function is neither here not there. */ From d672e7eb871308524184a4033e4d7728c6c6f76b Mon Sep 17 00:00:00 2001 From: Frank dellaert Date: Tue, 21 Jul 2020 11:37:08 -0400 Subject: [PATCH 232/869] Unit test for transformPoseFrom --- gtsam/geometry/tests/testPose3.cpp | 23 +++++++++++++++++++++++ 1 file changed, 23 insertions(+) diff --git a/gtsam/geometry/tests/testPose3.cpp b/gtsam/geometry/tests/testPose3.cpp index 5808f36f8..a169c833c 100644 --- a/gtsam/geometry/tests/testPose3.cpp +++ b/gtsam/geometry/tests/testPose3.cpp @@ -418,6 +418,29 @@ TEST(Pose3, transform_to_rotate) { EXPECT(assert_equal(expected, actual, 0.001)); } +/* ************************************************************************* */ +// Check transformPoseFrom and its pushforward +Pose3 transformPoseFrom_(const Pose3& wTa, const Pose3& aTb) { + return wTa.transformPoseFrom(aTb); +} + +TEST(Pose3, transformPoseFrom) +{ + Matrix actual = (T2*T2).matrix(); + Matrix expected = T2.matrix()*T2.matrix(); + EXPECT(assert_equal(actual, expected, 1e-8)); + + Matrix H1, H2; + T2.transformPoseFrom(T2, H1, H2); + + Matrix numericalH1 = numericalDerivative21(transformPoseFrom_, T2, T2); + EXPECT(assert_equal(numericalH1, H1, 5e-3)); + EXPECT(assert_equal(T2.inverse().AdjointMap(), H1, 5e-3)); + + Matrix numericalH2 = numericalDerivative22(transformPoseFrom_, T2, T2); + EXPECT(assert_equal(numericalH2, H2, 1e-4)); +} + /* ************************************************************************* */ TEST(Pose3, transformTo) { Pose3 transform(Rot3::Rodrigues(0, 0, -1.570796), Point3(2, 4, 0)); From 6192f90de5cdf3b8e963678d3293b27b330cdbb5 Mon Sep 17 00:00:00 2001 From: Frank dellaert Date: Tue, 21 Jul 2020 11:37:23 -0400 Subject: [PATCH 233/869] Some more name changes and documentation --- gtsam/geometry/Pose3.cpp | 15 ++++++++------- gtsam/geometry/Pose3.h | 30 +++++++++++++++++++----------- 2 files changed, 27 insertions(+), 18 deletions(-) diff --git a/gtsam/geometry/Pose3.cpp b/gtsam/geometry/Pose3.cpp index 0ee19ef76..1b9285100 100644 --- a/gtsam/geometry/Pose3.cpp +++ b/gtsam/geometry/Pose3.cpp @@ -286,9 +286,10 @@ Matrix4 Pose3::matrix() const { } /* ************************************************************************* */ -Pose3 Pose3::transformPoseFrom(const Pose3& aTb) const { +Pose3 Pose3::transformPoseFrom(const Pose3& aTb, OptionalJacobian<6, 6> Hself, + OptionalJacobian<6, 6> HaTb) const { const Pose3& wTa = *this; - return wTa * aTb; + return wTa.compose(aTb, Hself, HaTb); } /* ************************************************************************* */ @@ -310,28 +311,28 @@ Pose3 Pose3::transformPoseTo(const Pose3& wTb, OptionalJacobian<6, 6> Hself, } /* ************************************************************************* */ -Point3 Pose3::transformFrom(const Point3& p, OptionalJacobian<3, 6> Hself, +Point3 Pose3::transformFrom(const Point3& point, OptionalJacobian<3, 6> Hself, OptionalJacobian<3, 3> Hpoint) const { // Only get matrix once, to avoid multiple allocations, // as well as multiple conversions in the Quaternion case const Matrix3 R = R_.matrix(); if (Hself) { - Hself->leftCols<3>() = R * skewSymmetric(-p.x(), -p.y(), -p.z()); + Hself->leftCols<3>() = R * skewSymmetric(-point.x(), -point.y(), -point.z()); Hself->rightCols<3>() = R; } if (Hpoint) { *Hpoint = R; } - return R_ * p + t_; + return R_ * point + t_; } /* ************************************************************************* */ -Point3 Pose3::transformTo(const Point3& p, OptionalJacobian<3, 6> Hself, +Point3 Pose3::transformTo(const Point3& point, OptionalJacobian<3, 6> Hself, OptionalJacobian<3, 3> Hpoint) const { // Only get transpose once, to avoid multiple allocations, // as well as multiple conversions in the Quaternion case const Matrix3 Rt = R_.transpose(); - const Point3 q(Rt*(p - t_)); + const Point3 q(Rt*(point - t_)); if (Hself) { const double wx = q.x(), wy = q.y(), wz = q.z(); (*Hself) << diff --git a/gtsam/geometry/Pose3.h b/gtsam/geometry/Pose3.h index f56e6903a..3825b6241 100644 --- a/gtsam/geometry/Pose3.h +++ b/gtsam/geometry/Pose3.h @@ -201,27 +201,27 @@ public: /** * @brief takes point in Pose coordinates and transforms it to world coordinates - * @param p point in Pose coordinates + * @param point point in Pose coordinates * @param Hself optional 3*6 Jacobian wrpt this pose * @param Hpoint optional 3*3 Jacobian wrpt point * @return point in world coordinates */ - Point3 transformFrom(const Point3& p, OptionalJacobian<3, 6> Hself = + Point3 transformFrom(const Point3& point, OptionalJacobian<3, 6> Hself = boost::none, OptionalJacobian<3, 3> Hpoint = boost::none) const; /** syntactic sugar for transformFrom */ - inline Point3 operator*(const Point3& p) const { - return transformFrom(p); + inline Point3 operator*(const Point3& point) const { + return transformFrom(point); } /** * @brief takes point in world coordinates and transforms it to Pose coordinates - * @param p point in world coordinates + * @param point point in world coordinates * @param Hself optional 3*6 Jacobian wrpt this pose * @param Hpoint optional 3*3 Jacobian wrpt point * @return point in Pose coordinates */ - Point3 transformTo(const Point3& p, OptionalJacobian<3, 6> Hself = + Point3 transformTo(const Point3& point, OptionalJacobian<3, 6> Hself = boost::none, OptionalJacobian<3, 3> Hpoint = boost::none) const; /// @} @@ -252,12 +252,20 @@ public: /** convert to 4*4 matrix */ Matrix4 matrix() const; - /** receives a pose in local coordinates and transforms it to world coordinates */ - Pose3 transformPoseFrom(const Pose3& pose) const; + /** + * Assuming self == wTa, takes a pose aTb in local coordinates + * and transforms it to world coordinates wTb = wTa * aTb. + * This is identical to compose. + */ + Pose3 transformPoseFrom(const Pose3& aTb, OptionalJacobian<6, 6> Hself = boost::none, + OptionalJacobian<6, 6> HaTb = boost::none) const; - /** receives a pose in world coordinates and transforms it to local coordinates */ - Pose3 transformPoseTo(const Pose3& pose, OptionalJacobian<6, 6> Hself = boost::none, - OptionalJacobian<6, 6> Hpose = boost::none) const; + /** + * Assuming self == wTa, takes a pose wTb in world coordinates + * and transforms it to local coordinates aTb = inv(wTa) * wTb + */ + Pose3 transformPoseTo(const Pose3& wTb, OptionalJacobian<6, 6> Hself = boost::none, + OptionalJacobian<6, 6> HwTb = boost::none) const; /** * Calculate range to a landmark From 3f065f25c66e3bce14ac0c1206af000ec171b329 Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Tue, 21 Jul 2020 11:32:58 -0500 Subject: [PATCH 234/869] Added more comments for clearer understanding --- gtsam/navigation/TangentPreintegration.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/gtsam/navigation/TangentPreintegration.cpp b/gtsam/navigation/TangentPreintegration.cpp index 55efdb151..56d7aa6d3 100644 --- a/gtsam/navigation/TangentPreintegration.cpp +++ b/gtsam/navigation/TangentPreintegration.cpp @@ -68,7 +68,7 @@ Vector9 TangentPreintegration::UpdatePreintegrated(const Vector3& a_body, Matrix3 w_tangent_H_theta, invH; const Vector3 w_tangent = // angular velocity mapped back to tangent space local.applyInvDexp(w_body, A ? &w_tangent_H_theta : 0, C ? &invH : 0); - const Rot3 R(local.expmap()); + const Rot3 R(local.expmap()); // nRb: rotation of body in nav frame const Vector3 a_nav = R * a_body; const double dt22 = 0.5 * dt * dt; @@ -110,7 +110,7 @@ void TangentPreintegration::update(const Vector3& measuredAcc, Vector3 acc = biasHat_.correctAccelerometer(measuredAcc); Vector3 omega = biasHat_.correctGyroscope(measuredOmega); - // Possibly correct for sensor pose + // Possibly correct for sensor pose by converting to body frame Matrix3 D_correctedAcc_acc, D_correctedAcc_omega, D_correctedOmega_omega; if (p().body_P_sensor) boost::tie(acc, omega) = correctMeasurementsBySensorPose(acc, omega, From 24b2f50fe374a2d808a44c133c03f4793da02c60 Mon Sep 17 00:00:00 2001 From: Fan Jiang Date: Tue, 21 Jul 2020 18:15:00 -0400 Subject: [PATCH 235/869] Bump version and switch Pose3 expmap default --- CMakeLists.txt | 6 +++--- appveyor.yml | 2 +- 2 files changed, 4 insertions(+), 4 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index 12cb6882e..edefbf2ea 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -10,7 +10,7 @@ endif() # Set the version number for the library set (GTSAM_VERSION_MAJOR 4) set (GTSAM_VERSION_MINOR 0) -set (GTSAM_VERSION_PATCH 2) +set (GTSAM_VERSION_PATCH 3) math (EXPR GTSAM_VERSION_NUMERIC "10000 * ${GTSAM_VERSION_MAJOR} + 100 * ${GTSAM_VERSION_MINOR} + ${GTSAM_VERSION_PATCH}") set (GTSAM_VERSION_STRING "${GTSAM_VERSION_MAJOR}.${GTSAM_VERSION_MINOR}.${GTSAM_VERSION_PATCH}") @@ -68,8 +68,8 @@ if(GTSAM_UNSTABLE_AVAILABLE) endif() option(BUILD_SHARED_LIBS "Build shared gtsam library, instead of static" ON) option(GTSAM_USE_QUATERNIONS "Enable/Disable using an internal Quaternion representation for rotations instead of rotation matrices. If enable, Rot3::EXPMAP is enforced by default." OFF) -option(GTSAM_POSE3_EXPMAP "Enable/Disable using Pose3::EXPMAP as the default mode. If disabled, Pose3::FIRST_ORDER will be used." OFF) -option(GTSAM_ROT3_EXPMAP "Ignore if GTSAM_USE_QUATERNIONS is OFF (Rot3::EXPMAP by default). Otherwise, enable Rot3::EXPMAP, or if disabled, use Rot3::CAYLEY." OFF) +option(GTSAM_POSE3_EXPMAP "Enable/Disable using Pose3::EXPMAP as the default mode. If disabled, Pose3::FIRST_ORDER will be used." ON) +option(GTSAM_ROT3_EXPMAP "Ignore if GTSAM_USE_QUATERNIONS is OFF (Rot3::EXPMAP by default). Otherwise, enable Rot3::EXPMAP, or if disabled, use Rot3::CAYLEY." ON) option(GTSAM_ENABLE_CONSISTENCY_CHECKS "Enable/Disable expensive consistency checks" OFF) option(GTSAM_WITH_TBB "Use Intel Threaded Building Blocks (TBB) if available" ON) option(GTSAM_WITH_EIGEN_MKL "Eigen will use Intel MKL if available" OFF) diff --git a/appveyor.yml b/appveyor.yml index 2c78ca1f2..3747354cf 100644 --- a/appveyor.yml +++ b/appveyor.yml @@ -1,5 +1,5 @@ # version format -version: 4.0.2-{branch}-build{build} +version: 4.0.3-{branch}-build{build} os: Visual Studio 2019 From b8f9ab1d87fce11085b3ed467fddc1c65c2c66e7 Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Tue, 21 Jul 2020 18:41:14 -0500 Subject: [PATCH 236/869] nicer formatting when printing values --- gtsam/base/GenericValue.h | 2 +- gtsam/nonlinear/Values.cpp | 3 ++- 2 files changed, 3 insertions(+), 2 deletions(-) diff --git a/gtsam/base/GenericValue.h b/gtsam/base/GenericValue.h index 2ac3eb80c..11b610799 100644 --- a/gtsam/base/GenericValue.h +++ b/gtsam/base/GenericValue.h @@ -84,7 +84,7 @@ public: /// Virtual print function, uses traits virtual void print(const std::string& str) const { - std::cout << "(" << demangle(typeid(T).name()) << ") "; + std::cout << "(" << demangle(typeid(T).name()) << ") " << std::endl; traits::Print(value_, str); } diff --git a/gtsam/nonlinear/Values.cpp b/gtsam/nonlinear/Values.cpp index 98790ccd9..3ec1f3067 100644 --- a/gtsam/nonlinear/Values.cpp +++ b/gtsam/nonlinear/Values.cpp @@ -69,7 +69,8 @@ namespace gtsam { /* ************************************************************************* */ void Values::print(const string& str, const KeyFormatter& keyFormatter) const { - cout << str << "Values with " << size() << " values:" << endl; + cout << str << endl; + cout << "Values with " << size() << " values:" << endl; for(const_iterator key_value = begin(); key_value != end(); ++key_value) { cout << "Value " << keyFormatter(key_value->key) << ": "; key_value->value.print(""); From 456f1baf8f3083146310b7a45ba4675783dc9c8d Mon Sep 17 00:00:00 2001 From: Fan Jiang Date: Tue, 21 Jul 2020 20:55:21 -0400 Subject: [PATCH 237/869] Fix test for full Pose3 expmap --- gtsam/nonlinear/tests/testAdaptAutoDiff.cpp | 8 ++++++++ 1 file changed, 8 insertions(+) diff --git a/gtsam/nonlinear/tests/testAdaptAutoDiff.cpp b/gtsam/nonlinear/tests/testAdaptAutoDiff.cpp index a85118c00..2f4f21286 100644 --- a/gtsam/nonlinear/tests/testAdaptAutoDiff.cpp +++ b/gtsam/nonlinear/tests/testAdaptAutoDiff.cpp @@ -168,7 +168,11 @@ Camera camera(Pose3(Rot3().retract(Vector3(0.1, 0.2, 0.3)), Point3(0, 5, 0)), Point3 point(10, 0, -5); // negative Z-axis convention of Snavely! Vector9 P = Camera().localCoordinates(camera); Vector3 X = point; +#ifdef GTSAM_POSE3_EXPMAP +Vector2 expectedMeasurement(1.3124675, 1.2057287); +#else Vector2 expectedMeasurement(1.2431567, 1.2525694); +#endif Matrix E1 = numericalDerivative21(adapted, P, X); Matrix E2 = numericalDerivative22(adapted, P, X); } @@ -177,7 +181,11 @@ Matrix E2 = numericalDerivative22(adapted, P, X); // Check that Local worked as expected TEST(AdaptAutoDiff, Local) { using namespace example; +#ifdef GTSAM_POSE3_EXPMAP + Vector9 expectedP = (Vector9() << 0.1, 0.2, 0.3, 0.7583528428, 4.9582357859, -0.224941471539, 1, 0, 0).finished(); +#else Vector9 expectedP = (Vector9() << 0.1, 0.2, 0.3, 0, 5, 0, 1, 0, 0).finished(); +#endif EXPECT(equal_with_abs_tol(expectedP, P)); Vector3 expectedX(10, 0, -5); // negative Z-axis convention of Snavely! EXPECT(equal_with_abs_tol(expectedX, X)); From 18636c8aa1f6f98489884e8667a4af2db26e852d Mon Sep 17 00:00:00 2001 From: Frank dellaert Date: Wed, 22 Jul 2020 17:32:07 -0400 Subject: [PATCH 238/869] Replaced flag with 4.1 version --- .travis.python.sh | 2 +- .travis.sh | 2 +- .travis.yml | 2 +- CMakeLists.txt | 4 ++-- README.md | 7 +++++-- gtsam/config.h.in | 2 +- 6 files changed, 11 insertions(+), 8 deletions(-) diff --git a/.travis.python.sh b/.travis.python.sh index 772311f38..99506e749 100644 --- a/.travis.python.sh +++ b/.travis.python.sh @@ -29,7 +29,7 @@ cmake $CURRDIR -DCMAKE_BUILD_TYPE=Release \ -DGTSAM_BUILD_WITH_MARCH_NATIVE=OFF \ -DGTSAM_INSTALL_CYTHON_TOOLBOX=ON \ -DGTSAM_PYTHON_VERSION=$PYTHON_VERSION \ - -DGTSAM_ALLOW_DEPRECATED_SINCE_V4=OFF \ + -DGTSAM_ALLOW_DEPRECATED_SINCE_V41=OFF \ -DCMAKE_INSTALL_PREFIX=$CURRDIR/../gtsam_install make -j$(nproc) install diff --git a/.travis.sh b/.travis.sh index 535a72f4b..7777e9919 100755 --- a/.travis.sh +++ b/.travis.sh @@ -61,7 +61,7 @@ function configure() -DGTSAM_WITH_TBB=${GTSAM_WITH_TBB:-OFF} \ -DGTSAM_USE_QUATERNIONS=${GTSAM_USE_QUATERNIONS:-OFF} \ -DGTSAM_BUILD_EXAMPLES_ALWAYS=${GTSAM_BUILD_EXAMPLES_ALWAYS:-ON} \ - -DGTSAM_ALLOW_DEPRECATED_SINCE_V4=${GTSAM_ALLOW_DEPRECATED_SINCE_V4:-OFF} \ + -DGTSAM_ALLOW_DEPRECATED_SINCE_V4=${GTSAM_ALLOW_DEPRECATED_SINCE_V41:-OFF} \ -DGTSAM_BUILD_WITH_MARCH_NATIVE=OFF \ -DCMAKE_VERBOSE_MAKEFILE=OFF } diff --git a/.travis.yml b/.travis.yml index d8094ef4d..3fceed6de 100644 --- a/.travis.yml +++ b/.travis.yml @@ -88,7 +88,7 @@ jobs: - stage: special os: linux compiler: clang - env: CC=clang-9 CXX=clang++-9 CMAKE_BUILD_TYPE=Debug GTSAM_BUILD_UNSTABLE=OFF GTSAM_ALLOW_DEPRECATED_SINCE_V4=ON + env: CC=clang-9 CXX=clang++-9 CMAKE_BUILD_TYPE=Debug GTSAM_BUILD_UNSTABLE=OFF GTSAM_ALLOW_DEPRECATED_SINCE_V41=ON script: bash .travis.sh -b # on Linux, with GTSAM_WITH_TBB on to make sure GTSAM still compiles/tests - stage: special diff --git a/CMakeLists.txt b/CMakeLists.txt index edefbf2ea..69ff9e3a0 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -75,7 +75,7 @@ option(GTSAM_WITH_TBB "Use Intel Threaded Building Blocks (TB option(GTSAM_WITH_EIGEN_MKL "Eigen will use Intel MKL if available" OFF) option(GTSAM_WITH_EIGEN_MKL_OPENMP "Eigen, when using Intel MKL, will also use OpenMP for multithreading if available" OFF) option(GTSAM_THROW_CHEIRALITY_EXCEPTION "Throw exception when a triangulated point is behind a camera" ON) -option(GTSAM_ALLOW_DEPRECATED_SINCE_V4 "Allow use of methods/functions deprecated in GTSAM 4" ON) +option(GTSAM_ALLOW_DEPRECATED_SINCE_V41 "Allow use of methods/functions deprecated in GTSAM 4.1" ON) option(GTSAM_TYPEDEF_POINTS_TO_VECTORS "Typedef Point2 and Point3 to Eigen::Vector equivalents" OFF) option(GTSAM_SUPPORT_NESTED_DISSECTION "Support Metis-based nested dissection" ON) option(GTSAM_TANGENT_PREINTEGRATION "Use new ImuFactor with integration on tangent space" ON) @@ -590,7 +590,7 @@ print_config_flag(${GTSAM_USE_QUATERNIONS} "Quaternions as default R print_config_flag(${GTSAM_ENABLE_CONSISTENCY_CHECKS} "Runtime consistency checking ") print_config_flag(${GTSAM_ROT3_EXPMAP} "Rot3 retract is full ExpMap ") print_config_flag(${GTSAM_POSE3_EXPMAP} "Pose3 retract is full ExpMap ") -print_config_flag(${GTSAM_ALLOW_DEPRECATED_SINCE_V4} "Deprecated in GTSAM 4 allowed ") +print_config_flag(${GTSAM_ALLOW_DEPRECATED_SINCE_V41} "Deprecated in GTSAM 4.1 allowed ") print_config_flag(${GTSAM_TYPEDEF_POINTS_TO_VECTORS} "Point3 is typedef to Vector3 ") print_config_flag(${GTSAM_SUPPORT_NESTED_DISSECTION} "Metis-based Nested Dissection ") print_config_flag(${GTSAM_TANGENT_PREINTEGRATION} "Use tangent-space preintegration") diff --git a/README.md b/README.md index 093e35f0f..0b3ecb11d 100644 --- a/README.md +++ b/README.md @@ -44,9 +44,12 @@ Optional prerequisites - used automatically if findable by CMake: ## GTSAM 4 Compatibility -GTSAM 4 introduces several new features, most notably Expressions and a Python toolbox. We also deprecate some legacy functionality and wrongly named methods, but by default the flag GTSAM_ALLOW_DEPRECATED_SINCE_V4 is enabled, allowing anyone to just pull V4 and compile. To build the python toolbox, however, you will have to explicitly disable that flag. +GTSAM 4 introduces several new features, most notably Expressions and a Python toolbox. It also introduces traits, a C++ technique that allows optimizing with non-GTSAM types. That opens the door to retiring geometric types such as Point2 and Point3 to pure Eigen types, which we also do. A significant change which will not trigger a compile error is that zero-initializing of Point2 and Point3 is deprecated, so please be aware that this might render functions using their default constructor incorrect. + +GTSAM 4 also deprecated some legacy functionality and wrongly named methods. If you are on a 4.0.X release, you can define the flag GTSAM_ALLOW_DEPRECATED_SINCE_V4 to use the deprecated methods. + +GTSAM 4.1 added a new pybind wrapper, and **removed** the deprecated functionality. There is a flag GTSAM_ALLOW_DEPRECATED_SINCE_V41 for newly deprecated methods since the 4.1 release, which is on by default, allowing anyone to just pull version 4.1 and compile. -Also, GTSAM 4 introduces traits, a C++ technique that allows optimizing with non-GTSAM types. That opens the door to retiring geometric types such as Point2 and Point3 to pure Eigen types, which we also do. A significant change which will not trigger a compile error is that zero-initializing of Point2 and Point3 is deprecated, so please be aware that this might render functions using their default constructor incorrect. ## Wrappers diff --git a/gtsam/config.h.in b/gtsam/config.h.in index b480996ec..9dc10c36a 100644 --- a/gtsam/config.h.in +++ b/gtsam/config.h.in @@ -70,7 +70,7 @@ #cmakedefine GTSAM_THROW_CHEIRALITY_EXCEPTION // Make sure dependent projects that want it can see deprecated functions -#cmakedefine GTSAM_ALLOW_DEPRECATED_SINCE_V4 +#cmakedefine GTSAM_ALLOW_DEPRECATED_SINCE_V41 // Publish flag about Eigen typedef #cmakedefine GTSAM_TYPEDEF_POINTS_TO_VECTORS From 30703ccb6a79bba1dbb2dbc7af744a40a81dbff3 Mon Sep 17 00:00:00 2001 From: Frank dellaert Date: Wed, 22 Jul 2020 17:32:25 -0400 Subject: [PATCH 239/869] Removed all deprecated code w Stephanie... --- gtsam/base/DSFVector.h | 5 -- gtsam/base/Manifold.h | 56 ---------------- gtsam/base/Matrix.h | 24 +------ gtsam/base/Vector.h | 20 ------ gtsam/geometry/EssentialMatrix.h | 11 ---- gtsam/geometry/Point2.cpp | 12 ---- gtsam/geometry/Point2.h | 27 +------- gtsam/geometry/Point3.cpp | 17 ----- gtsam/geometry/Point3.h | 27 +------- gtsam/geometry/Pose2.h | 16 ----- gtsam/geometry/Pose3.cpp | 9 --- gtsam/geometry/Pose3.h | 29 --------- gtsam/geometry/Rot3.h | 17 ----- gtsam/geometry/triangulation.h | 21 ------ gtsam/inference/BayesTree.h | 19 ------ gtsam/inference/ISAM.h | 11 ---- gtsam/linear/GaussianConditional.h | 12 +--- gtsam/linear/HessianFactor.h | 11 +--- gtsam/linear/LossFunctions.h | 12 ---- gtsam/linear/NoiseModel.cpp | 11 ---- gtsam/linear/NoiseModel.h | 39 ----------- gtsam/linear/Sampler.cpp | 11 ---- gtsam/linear/Sampler.h | 8 --- gtsam/linear/SubgraphSolver.cpp | 17 ----- gtsam/linear/SubgraphSolver.h | 17 ----- gtsam/navigation/CombinedImuFactor.cpp | 58 ----------------- gtsam/navigation/CombinedImuFactor.h | 32 +--------- gtsam/navigation/ImuFactor.cpp | 64 ++----------------- gtsam/navigation/ImuFactor.h | 41 +----------- gtsam/navigation/PreintegrationBase.cpp | 16 ----- gtsam/navigation/PreintegrationBase.h | 43 +------------ gtsam/navigation/ScenarioRunner.h | 9 --- gtsam/navigation/tests/testNavState.cpp | 31 --------- .../navigation/tests/testPoseVelocityBias.cpp | 34 ---------- gtsam/nonlinear/LinearContainerFactor.h | 17 ++--- gtsam/nonlinear/NonlinearFactor.h | 19 +----- gtsam/slam/SmartProjectionFactor.h | 19 ------ gtsam/slam/dataset.h | 11 +--- .../nonlinear/BatchFixedLagSmoother.h | 9 --- tests/testManifold.cpp | 28 -------- 40 files changed, 25 insertions(+), 865 deletions(-) diff --git a/gtsam/base/DSFVector.h b/gtsam/base/DSFVector.h index fdbd96dc8..6e9bc5c6b 100644 --- a/gtsam/base/DSFVector.h +++ b/gtsam/base/DSFVector.h @@ -55,11 +55,6 @@ public: /// Merge the sets containing i1 and i2. Does nothing if i1 and i2 are already in the same set. void merge(const size_t& i1, const size_t& i2); - -#ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V4 - inline size_t findSet(size_t key) const {return find(key);} - inline void makeUnionInPlace(const size_t& i1, const size_t& i2) {return merge(i1,i2);} -#endif }; /** diff --git a/gtsam/base/Manifold.h b/gtsam/base/Manifold.h index 9feb2b451..dbe497005 100644 --- a/gtsam/base/Manifold.h +++ b/gtsam/base/Manifold.h @@ -167,62 +167,6 @@ struct FixedDimension { BOOST_STATIC_ASSERT_MSG(value != Eigen::Dynamic, "FixedDimension instantiated for dymanically-sized type."); }; - -#ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V4 -/// Helper class to construct the product manifold of two other manifolds, M1 and M2 -/// Deprecated because of limited usefulness, maximum obfuscation -template -class ProductManifold: public std::pair { - BOOST_CONCEPT_ASSERT((IsManifold)); - BOOST_CONCEPT_ASSERT((IsManifold)); - -protected: - enum { dimension1 = traits::dimension }; - enum { dimension2 = traits::dimension }; - -public: - enum { dimension = dimension1 + dimension2 }; - inline static size_t Dim() { return dimension;} - inline size_t dim() const { return dimension;} - - typedef Eigen::Matrix TangentVector; - typedef OptionalJacobian ChartJacobian; - - /// Default constructor needs default constructors to be defined - ProductManifold():std::pair(M1(),M2()) {} - - // Construct from two original manifold values - ProductManifold(const M1& m1, const M2& m2):std::pair(m1,m2) {} - - /// Retract delta to manifold - ProductManifold retract(const TangentVector& xi) const { - M1 m1 = traits::Retract(this->first, xi.template head()); - M2 m2 = traits::Retract(this->second, xi.template tail()); - return ProductManifold(m1,m2); - } - - /// Compute the coordinates in the tangent space - TangentVector localCoordinates(const ProductManifold& other) const { - typename traits::TangentVector v1 = traits::Local(this->first, other.first); - typename traits::TangentVector v2 = traits::Local(this->second, other.second); - TangentVector v; - v << v1, v2; - return v; - } - - // Alignment, see https://eigen.tuxfamily.org/dox/group__TopicStructHavingEigenMembers.html - enum { NeedsToAlign = (sizeof(M1) % 16) == 0 || (sizeof(M2) % 16) == 0 - }; -public: - GTSAM_MAKE_ALIGNED_OPERATOR_NEW_IF(NeedsToAlign) -}; - -// Define any direct product group to be a model of the multiplicative Group concept -template -struct traits > : internal::Manifold > { -}; -#endif - } // \ namespace gtsam ///** diff --git a/gtsam/base/Matrix.h b/gtsam/base/Matrix.h index 1c1138438..89e5cd64c 100644 --- a/gtsam/base/Matrix.h +++ b/gtsam/base/Matrix.h @@ -23,14 +23,11 @@ // \callgraph #pragma once + #include #include #include -#ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V4 -#include -#include -#include -#endif + #include #include #include @@ -517,23 +514,6 @@ struct MultiplyWithInverseFunction { const Operator phi_; }; -#ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V4 -inline Matrix zeros( size_t m, size_t n ) { return Matrix::Zero(m,n); } -inline Matrix ones( size_t m, size_t n ) { return Matrix::Ones(m,n); } -inline Matrix eye( size_t m, size_t n) { return Matrix::Identity(m, n); } -inline Matrix eye( size_t m ) { return eye(m,m); } -inline Matrix diag(const Vector& v) { return v.asDiagonal(); } -inline void multiplyAdd(double alpha, const Matrix& A, const Vector& x, Vector& e) { e += alpha * A * x; } -inline void multiplyAdd(const Matrix& A, const Vector& x, Vector& e) { e += A * x; } -inline void transposeMultiplyAdd(double alpha, const Matrix& A, const Vector& e, Vector& x) { x += alpha * A.transpose() * e; } -inline void transposeMultiplyAdd(const Matrix& A, const Vector& e, Vector& x) { x += A.transpose() * e; } -inline void transposeMultiplyAdd(double alpha, const Matrix& A, const Vector& e, SubVector x) { x += alpha * A.transpose() * e; } -inline void insertColumn(Matrix& A, const Vector& col, size_t j) { A.col(j) = col; } -inline void insertColumn(Matrix& A, const Vector& col, size_t i, size_t j) { A.col(j).segment(i, col.size()) = col; } -inline void solve(Matrix& A, Matrix& B) { B = A.fullPivLu().solve(B); } -inline Matrix inverse(const Matrix& A) { return A.inverse(); } -#endif - GTSAM_EXPORT Matrix LLt(const Matrix& A); GTSAM_EXPORT Matrix RtR(const Matrix& A); diff --git a/gtsam/base/Vector.h b/gtsam/base/Vector.h index 81be36c0a..319ad6ee6 100644 --- a/gtsam/base/Vector.h +++ b/gtsam/base/Vector.h @@ -256,26 +256,6 @@ GTSAM_EXPORT Vector concatVectors(const std::list& vs); * concatenate Vectors */ GTSAM_EXPORT Vector concatVectors(size_t nrVectors, ...); - -#ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V4 -inline Vector abs(const Vector& v){return v.cwiseAbs();} -inline Vector basis(size_t n, size_t i) { return Vector::Unit(n,i); } -inline Vector delta(size_t n, size_t i, double value){ return Vector::Unit(n, i) * value;} -inline size_t dim(const Vector& v) { return v.size(); } -inline Vector ediv(const Vector &a, const Vector &b) {assert (b.size()==a.size()); return a.cwiseQuotient(b);} -inline Vector esqrt(const Vector& v) { return v.cwiseSqrt();} -inline Vector emul(const Vector &a, const Vector &b) {assert (b.size()==a.size()); return a.cwiseProduct(b);} -inline double max(const Vector &a){return a.maxCoeff();} -inline double norm_2(const Vector& v) {return v.norm();} -inline Vector ones(size_t n) { return Vector::Ones(n); } -inline Vector reciprocal(const Vector &a) {return a.array().inverse();} -inline Vector repeat(size_t n, double value) {return Vector::Constant(n, value);} -inline const Vector sub(const Vector &v, size_t i1, size_t i2) {return v.segment(i1,i2-i1);} -inline void subInsert(Vector& fullVector, const Vector& subVector, size_t i) {fullVector.segment(i, subVector.size()) = subVector;} -inline double sum(const Vector &a){return a.sum();} -inline bool zero(const Vector& v){ return v.isZero(); } -inline Vector zero(size_t n) { return Vector::Zero(n); } -#endif } // namespace gtsam #include diff --git a/gtsam/geometry/EssentialMatrix.h b/gtsam/geometry/EssentialMatrix.h index ca719eb37..909576aa0 100644 --- a/gtsam/geometry/EssentialMatrix.h +++ b/gtsam/geometry/EssentialMatrix.h @@ -176,17 +176,6 @@ class EssentialMatrix { /// @} -#ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V4 - /// @name Deprecated - /// @{ - Point3 transform_to(const Point3& p, - OptionalJacobian<3, 5> DE = boost::none, - OptionalJacobian<3, 3> Dpoint = boost::none) const { - return transformTo(p, DE, Dpoint); - }; - /// @} -#endif - private: /// @name Advanced Interface /// @{ diff --git a/gtsam/geometry/Point2.cpp b/gtsam/geometry/Point2.cpp index 3d4bb753e..4cead869f 100644 --- a/gtsam/geometry/Point2.cpp +++ b/gtsam/geometry/Point2.cpp @@ -79,18 +79,6 @@ ostream &operator<<(ostream &os, const Point2& p) { return os; } -#ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V4 -boost::optional CircleCircleIntersection(double R_d, double r_d, double tol) { - return circleCircleIntersection(R_d, r_d, tol); -} -std::list CircleCircleIntersection(Point2 c1, Point2 c2, boost::optional fh) { - return circleCircleIntersection(c1, c2, fh); -} -std::list CircleCircleIntersection(Point2 c1, double r1, Point2 c2, double r2, double tol) { - return circleCircleIntersection(c1, r1, c2, r2, tol); -} -#endif - #endif // GTSAM_TYPEDEF_POINTS_TO_VECTORS /* ************************************************************************* */ diff --git a/gtsam/geometry/Point2.h b/gtsam/geometry/Point2.h index 718fb2992..e186f7b67 100644 --- a/gtsam/geometry/Point2.h +++ b/gtsam/geometry/Point2.h @@ -46,12 +46,7 @@ public: /// @{ /// default constructor -#ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V4 - // Deprecated default constructor initializes to zero, in contrast to new behavior below - Point2() { setZero(); } -#else - Point2() {} -#endif + Point2() {} using Vector2::Vector2; @@ -113,25 +108,7 @@ public: /// Streaming GTSAM_EXPORT friend std::ostream &operator<<(std::ostream &os, const Point2& p); -#ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V4 - /// @name Deprecated - /// @{ - Point2 inverse() const { return -(*this); } - Point2 compose(const Point2& q) const { return (*this)+q;} - Point2 between(const Point2& q) const { return q-(*this);} - Vector2 localCoordinates(const Point2& q) const { return between(q);} - Point2 retract(const Vector2& v) const { return compose(Point2(v));} - static Vector2 Logmap(const Point2& p) { return p;} - static Point2 Expmap(const Vector2& v) { return Point2(v);} - inline double dist(const Point2& p2) const {return distance(p2);} - GTSAM_EXPORT static boost::optional CircleCircleIntersection(double R_d, double r_d, double tol = 1e-9); - GTSAM_EXPORT static std::list CircleCircleIntersection(Point2 c1, Point2 c2, boost::optional fh); - GTSAM_EXPORT static std::list CircleCircleIntersection(Point2 c1, double r1, Point2 c2, double r2, double tol = 1e-9); - /// @} -#endif - -private: - + private: /// @name Advanced Interface /// @{ diff --git a/gtsam/geometry/Point3.cpp b/gtsam/geometry/Point3.cpp index 8aa339a89..25fb9b92d 100644 --- a/gtsam/geometry/Point3.cpp +++ b/gtsam/geometry/Point3.cpp @@ -62,23 +62,6 @@ ostream &operator<<(ostream &os, const Point3& p) { return os; } -/* ************************************************************************* */ -#ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V4 -Point3 Point3::add(const Point3 &q, OptionalJacobian<3,3> H1, - OptionalJacobian<3,3> H2) const { - if (H1) *H1 = I_3x3; - if (H2) *H2 = I_3x3; - return *this + q; -} - -Point3 Point3::sub(const Point3 &q, OptionalJacobian<3,3> H1, - OptionalJacobian<3,3> H2) const { - if (H1) *H1 = I_3x3; - if (H2) *H2 = -I_3x3; - return *this - q; -} -#endif - #endif /* ************************************************************************* */ double distance3(const Point3 &p1, const Point3 &q, OptionalJacobian<1, 3> H1, diff --git a/gtsam/geometry/Point3.h b/gtsam/geometry/Point3.h index 3b2330403..1ab5c313e 100644 --- a/gtsam/geometry/Point3.h +++ b/gtsam/geometry/Point3.h @@ -51,11 +51,6 @@ class Point3 : public Vector3 { /// @name Standard Constructors /// @{ - // Deprecated default constructor initializes to zero, in contrast to new behavior below -#ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V4 - Point3() { setZero(); } -#endif - using Vector3::Vector3; /// @} @@ -118,27 +113,7 @@ class Point3 : public Vector3 { /// Output stream operator GTSAM_EXPORT friend std::ostream &operator<<(std::ostream &os, const Point3& p); -#ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V4 - /// @name Deprecated - /// @{ - Point3 inverse() const { return -(*this);} - Point3 compose(const Point3& q) const { return (*this)+q;} - Point3 between(const Point3& q) const { return q-(*this);} - Vector3 localCoordinates(const Point3& q) const { return between(q);} - Point3 retract(const Vector3& v) const { return compose(Point3(v));} - static Vector3 Logmap(const Point3& p) { return p;} - static Point3 Expmap(const Vector3& v) { return Point3(v);} - inline double dist(const Point3& q) const { return (q - *this).norm(); } - Point3 normalize(OptionalJacobian<3, 3> H = boost::none) const { return normalized(H);} - GTSAM_EXPORT Point3 add(const Point3& q, OptionalJacobian<3, 3> H1 = boost::none, - OptionalJacobian<3, 3> H2 = boost::none) const; - GTSAM_EXPORT Point3 sub(const Point3& q, OptionalJacobian<3, 3> H1 = boost::none, - OptionalJacobian<3, 3> H2 = boost::none) const; - /// @} -#endif - - private: - + private: /** Serialization function */ friend class boost::serialization::access; template diff --git a/gtsam/geometry/Pose2.h b/gtsam/geometry/Pose2.h index 2a1f108ca..6372779c3 100644 --- a/gtsam/geometry/Pose2.h +++ b/gtsam/geometry/Pose2.h @@ -289,22 +289,6 @@ public: /// @} -#ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V4 - /// @name Deprecated - /// @{ - Point2 transform_from(const Point2& point, - OptionalJacobian<2, 3> Dpose = boost::none, - OptionalJacobian<2, 2> Dpoint = boost::none) const { - return transformFrom(point, Dpose, Dpoint); - } - Point2 transform_to(const Point2& point, - OptionalJacobian<2, 3> Dpose = boost::none, - OptionalJacobian<2, 2> Dpoint = boost::none) const { - return transformTo(point, Dpose, Dpoint); - } - /// @} -#endif - private: // Serialization function diff --git a/gtsam/geometry/Pose3.cpp b/gtsam/geometry/Pose3.cpp index 1b9285100..c6be18586 100644 --- a/gtsam/geometry/Pose3.cpp +++ b/gtsam/geometry/Pose3.cpp @@ -292,15 +292,6 @@ Pose3 Pose3::transformPoseFrom(const Pose3& aTb, OptionalJacobian<6, 6> Hself, return wTa.compose(aTb, Hself, HaTb); } -/* ************************************************************************* */ -#ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V4 -Pose3 Pose3::transform_to(const Pose3& pose) const { - Rot3 cRv = R_ * Rot3(pose.R_.inverse()); - Point3 t = pose.transform_to(t_); - return Pose3(cRv, t); -} -#endif - /* ************************************************************************* */ Pose3 Pose3::transformPoseTo(const Pose3& wTb, OptionalJacobian<6, 6> Hself, OptionalJacobian<6, 6> HwTb) const { diff --git a/gtsam/geometry/Pose3.h b/gtsam/geometry/Pose3.h index 3825b6241..159fd2927 100644 --- a/gtsam/geometry/Pose3.h +++ b/gtsam/geometry/Pose3.h @@ -326,30 +326,6 @@ public: GTSAM_EXPORT friend std::ostream &operator<<(std::ostream &os, const Pose3& p); -#ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V4 - /// @name Deprecated - /// @{ - Point3 transform_from(const Point3& point, - OptionalJacobian<3, 6> Hself = boost::none, - OptionalJacobian<3, 3> Hpoint = boost::none) const { - return transformFrom(point, Hself, Hpoint); - } - Point3 transform_to(const Point3& point, - OptionalJacobian<3, 6> Hself = boost::none, - OptionalJacobian<3, 3> Hpoint = boost::none) const { - return transformTo(point, Hself, Hpoint); - } - Pose3 transform_pose_to(const Pose3& pose, - OptionalJacobian<6, 6> Hself = boost::none, - OptionalJacobian<6, 6> Hpose = boost::none) const { - return transformPoseTo(pose, Hself, Hpose); - } - /** - * @deprecated: this function is neither here not there. */ - Pose3 transform_to(const Pose3& pose) const; - /// @} -#endif - private: /** Serialization function */ friend class boost::serialization::access; @@ -380,11 +356,6 @@ inline Matrix wedge(const Vector& xi) { return Pose3::wedge(xi(0), xi(1), xi(2), xi(3), xi(4), xi(5)); } -#ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V4 -// deprecated: use Pose3::Align with point pairs ordered the opposite way -GTSAM_EXPORT boost::optional align(const std::vector& baPointPairs); -#endif - // For MATLAB wrapper typedef std::vector Pose3Vector; diff --git a/gtsam/geometry/Rot3.h b/gtsam/geometry/Rot3.h index 8f24f07c8..f16d7d153 100644 --- a/gtsam/geometry/Rot3.h +++ b/gtsam/geometry/Rot3.h @@ -500,23 +500,6 @@ namespace gtsam { /// @} -#ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V4 - /// @name Deprecated - /// @{ - static Rot3 rodriguez(const Point3& axis, double angle) { return AxisAngle(axis, angle); } - static Rot3 rodriguez(const Unit3& axis, double angle) { return AxisAngle(axis, angle); } - static Rot3 rodriguez(const Vector3& w) { return Rodrigues(w); } - static Rot3 rodriguez(double wx, double wy, double wz) { return Rodrigues(wx, wy, wz); } - static Rot3 yaw (double t) { return Yaw(t); } - static Rot3 pitch(double t) { return Pitch(t); } - static Rot3 roll (double t) { return Roll(t); } - static Rot3 ypr(double y, double p, double r) { return Ypr(r,p,y);} - static Rot3 quaternion(double w, double x, double y, double z) { - return Rot3::Quaternion(w, x, y, z); - } - /// @} -#endif - private: /** Serialization function */ friend class boost::serialization::access; diff --git a/gtsam/geometry/triangulation.h b/gtsam/geometry/triangulation.h index 8cdf0fdc0..6f6c645b8 100644 --- a/gtsam/geometry/triangulation.h +++ b/gtsam/geometry/triangulation.h @@ -123,27 +123,6 @@ std::pair triangulationGraph( return std::make_pair(graph, values); } -#ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V4 -/// DEPRECATED: PinholeCamera specific version -template -Point3 triangulateNonlinear( - const CameraSet >& cameras, - const Point2Vector& measurements, const Point3& initialEstimate) { - return triangulateNonlinear > // - (cameras, measurements, initialEstimate); -} - -/// DEPRECATED: PinholeCamera specific version -template -std::pair triangulationGraph( - const CameraSet >& cameras, - const Point2Vector& measurements, Key landmarkKey, - const Point3& initialEstimate) { - return triangulationGraph > // - (cameras, measurements, landmarkKey, initialEstimate); -} -#endif - /** * Optimize for triangulation * @param graph nonlinear factors for projection diff --git a/gtsam/inference/BayesTree.h b/gtsam/inference/BayesTree.h index 9d632ff06..054c55987 100644 --- a/gtsam/inference/BayesTree.h +++ b/gtsam/inference/BayesTree.h @@ -249,25 +249,6 @@ namespace gtsam { // Friend JunctionTree because it directly fills roots and nodes index. template friend class EliminatableClusterTree; -#ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V4 - public: - /// @name Deprecated - /// @{ - void removePath(sharedClique clique, BayesNetType& bn, Cliques& orphans) { - removePath(clique, &bn, &orphans); - } - void removeTop(const KeyVector& keys, BayesNetType& bn, Cliques& orphans) { - removeTop(keys, &bn, &orphans); - } - void getCliqueData(BayesTreeCliqueData& stats, sharedClique clique) const { - getCliqueData(clique, &stats); - } - void addFactorsToGraph(FactorGraph& graph) const{ - addFactorsToGraph(& graph); - } - /// @} -#endif - private: /** Serialization function */ friend class boost::serialization::access; diff --git a/gtsam/inference/ISAM.h b/gtsam/inference/ISAM.h index fe6763a13..b4a5db740 100644 --- a/gtsam/inference/ISAM.h +++ b/gtsam/inference/ISAM.h @@ -72,17 +72,6 @@ class ISAM : public BAYESTREE { const Eliminate& function = EliminationTraitsType::DefaultEliminate); /// @} - -#ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V4 - /// @name Deprecated - /// @{ - void update_internal( - const FactorGraphType& newFactors, Cliques& orphans, - const Eliminate& function = EliminationTraitsType::DefaultEliminate) { - updateInternal(newFactors, &orphans, function); - } - /// @} -#endif }; } // namespace gtsam diff --git a/gtsam/linear/GaussianConditional.h b/gtsam/linear/GaussianConditional.h index 8b41a4def..b6ce867e0 100644 --- a/gtsam/linear/GaussianConditional.h +++ b/gtsam/linear/GaussianConditional.h @@ -128,17 +128,9 @@ namespace gtsam { /** Scale the values in \c gy according to the sigmas for the frontal variables in this * conditional. */ void scaleFrontalsBySigma(VectorValues& gy) const; -// __declspec(deprecated) void scaleFrontalsBySigma(VectorValues& gy) const; // FIXME: depreciated flag doesn't appear to exist? -#ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V4 - /// @name Deprecated - /// @{ - constABlock get_R() const { return R(); } - constABlock get_S() const { return S(); } - constABlock get_S(const_iterator it) const { return S(it); } - const constBVector get_d() const { return d(); } - /// @} -#endif + // FIXME: deprecated flag doesn't appear to exist? + // __declspec(deprecated) void scaleFrontalsBySigma(VectorValues& gy) const; private: /** Serialization function */ diff --git a/gtsam/linear/HessianFactor.h b/gtsam/linear/HessianFactor.h index 64b764087..a4de46104 100644 --- a/gtsam/linear/HessianFactor.h +++ b/gtsam/linear/HessianFactor.h @@ -354,16 +354,7 @@ namespace gtsam { /// Solve the system A'*A delta = A'*b in-place, return delta as VectorValues VectorValues solve(); - -#ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V4 - /// @name Deprecated - /// @{ - const SymmetricBlockMatrix& matrixObject() const { return info_; } - /// @} -#endif - - private: - + private: /// Allocate for given scatter pattern void Allocate(const Scatter& scatter); diff --git a/gtsam/linear/LossFunctions.h b/gtsam/linear/LossFunctions.h index 6a5dc5a26..523fe1516 100644 --- a/gtsam/linear/LossFunctions.h +++ b/gtsam/linear/LossFunctions.h @@ -82,10 +82,6 @@ class GTSAM_EXPORT Base { */ virtual double loss(double distance) const { return 0; }; -#ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V4 - virtual double residual(double distance) const { return loss(distance); }; -#endif - /* * This method is responsible for returning the weight function for a given * amount of error. The weight function is related to the analytic derivative @@ -278,14 +274,6 @@ class GTSAM_EXPORT Welsch : public Base { ar &BOOST_SERIALIZATION_NVP(c_); } }; -#ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V4 -/// @name Deprecated -/// @{ -// Welsh implements the "Welsch" robust error model (Zhang97ivc) -// This was misspelled in previous versions of gtsam and should be -// removed in the future. -using Welsh = Welsch; -#endif /// GemanMcClure implements the "Geman-McClure" robust error model /// (Zhang97ivc). diff --git a/gtsam/linear/NoiseModel.cpp b/gtsam/linear/NoiseModel.cpp index f5ec95696..cf10cf115 100644 --- a/gtsam/linear/NoiseModel.cpp +++ b/gtsam/linear/NoiseModel.cpp @@ -376,17 +376,6 @@ Vector Constrained::whiten(const Vector& v) const { return c; } -#ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V4 -/* ************************************************************************* */ -double Constrained::error(const Vector& v) const { - Vector w = Diagonal::whiten(v); // get noisemodel for constrained elements - for (size_t i=0; i& A, Vector& b) const = 0; virtual void WhitenSystem(Matrix& A, Vector& b) const = 0; virtual void WhitenSystem(Matrix& A1, Matrix& A2, Vector& b) const = 0; @@ -226,19 +217,6 @@ namespace gtsam { Vector whiten(const Vector& v) const override; Vector unwhiten(const Vector& v) const override; -#ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V4 - virtual double Mahalanobis(const Vector& v) const { - return squaredMahalanobisDistance(v); - } - - /** - * error value 0.5 * v'*R'*R*v - */ - inline double error(const Vector& v) const override { - return 0.5 * squaredMahalanobisDistance(v); - } -#endif - /** * Multiply a derivative with R (derivative of whiten) * Equivalent to whitening each column of the input matrix. @@ -483,15 +461,6 @@ namespace gtsam { return MixedVariances(precisions.array().inverse()); } -#ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V4 - /** - * The error function for a constrained noisemodel, - * for non-constrained versions, uses sigmas, otherwise - * uses the penalty function with mu - */ - double error(const Vector& v) const override; -#endif - double squaredMahalanobisDistance(const Vector& v) const override; /** Fully constrained variations */ @@ -720,14 +689,6 @@ namespace gtsam { { Vector b; Matrix B=A; this->WhitenSystem(B,b); return B; } inline Vector unwhiten(const Vector& /*v*/) const override { throw std::invalid_argument("unwhiten is not currently supported for robust noise models."); } -#ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V4 - inline double distance(const Vector& v) override { - return robust_->loss(this->unweightedWhiten(v).norm()); - } - // Fold the use of the m-estimator loss(...) function into error(...) - inline double error(const Vector& v) const override - { return robust_->loss(noise_->mahalanobisDistance(v)); } -#endif double loss(const double squared_distance) const override { return robust_->loss(std::sqrt(squared_distance)); diff --git a/gtsam/linear/Sampler.cpp b/gtsam/linear/Sampler.cpp index 16c7e73e0..4957dfa14 100644 --- a/gtsam/linear/Sampler.cpp +++ b/gtsam/linear/Sampler.cpp @@ -54,17 +54,6 @@ Vector Sampler::sample() const { return sampleDiagonal(sigmas); } -/* ************************************************************************* */ -#ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V4 -Sampler::Sampler(uint_fast64_t seed) : generator_(seed) {} - -Vector Sampler::sampleNewModel( - const noiseModel::Diagonal::shared_ptr& model) const { - assert(model.get()); - const Vector& sigmas = model->sigmas(); - return sampleDiagonal(sigmas); -} -#endif /* ************************************************************************* */ } // namespace gtsam diff --git a/gtsam/linear/Sampler.h b/gtsam/linear/Sampler.h index 54c240a2b..bb5098f34 100644 --- a/gtsam/linear/Sampler.h +++ b/gtsam/linear/Sampler.h @@ -84,14 +84,6 @@ class GTSAM_EXPORT Sampler { /// @} -#ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V4 - /// @name Deprecated - /// @{ - explicit Sampler(uint_fast64_t seed = 42u); - Vector sampleNewModel(const noiseModel::Diagonal::shared_ptr& model) const; - /// @} -#endif - protected: /** given sigmas for a diagonal model, returns a sample */ Vector sampleDiagonal(const Vector& sigmas) const; diff --git a/gtsam/linear/SubgraphSolver.cpp b/gtsam/linear/SubgraphSolver.cpp index 56b843e8d..f49f9a135 100644 --- a/gtsam/linear/SubgraphSolver.cpp +++ b/gtsam/linear/SubgraphSolver.cpp @@ -65,23 +65,6 @@ SubgraphSolver::SubgraphSolver(const GaussianFactorGraph &Ab1, : SubgraphSolver(Ab1.eliminateSequential(ordering, EliminateQR), Ab2, parameters) {} -/**************************************************************************************************/ -// deprecated variants -#ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V4 -SubgraphSolver::SubgraphSolver(const GaussianBayesNet::shared_ptr &Rc1, - const GaussianFactorGraph &Ab2, - const Parameters ¶meters) - : SubgraphSolver(Rc1, boost::make_shared(Ab2), - parameters) {} - -SubgraphSolver::SubgraphSolver(const GaussianFactorGraph &Ab1, - const GaussianFactorGraph &Ab2, - const Parameters ¶meters, - const Ordering &ordering) - : SubgraphSolver(Ab1, boost::make_shared(Ab2), - parameters, ordering) {} -#endif - /**************************************************************************************************/ VectorValues SubgraphSolver::optimize() const { VectorValues ybar = conjugateGradients &A, - const Parameters ¶meters, const Ordering &ordering) - : SubgraphSolver(*A, parameters, ordering) {} - SubgraphSolver(const GaussianFactorGraph &, const GaussianFactorGraph &, - const Parameters &, const Ordering &); - SubgraphSolver(const boost::shared_ptr &Ab1, - const boost::shared_ptr &Ab2, - const Parameters ¶meters, const Ordering &ordering) - : SubgraphSolver(*Ab1, Ab2, parameters, ordering) {} - SubgraphSolver(const boost::shared_ptr &, - const GaussianFactorGraph &, const Parameters &); - /// @} -#endif }; } // namespace gtsam diff --git a/gtsam/navigation/CombinedImuFactor.cpp b/gtsam/navigation/CombinedImuFactor.cpp index d7b4b7bf1..49c666030 100644 --- a/gtsam/navigation/CombinedImuFactor.cpp +++ b/gtsam/navigation/CombinedImuFactor.cpp @@ -148,29 +148,6 @@ void PreintegratedCombinedMeasurements::integrateMeasurement( preintMeasCov_ = F * preintMeasCov_ * F.transpose() + G_measCov_Gt; } -//------------------------------------------------------------------------------ -#ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V4 -PreintegratedCombinedMeasurements::PreintegratedCombinedMeasurements( - const imuBias::ConstantBias& biasHat, const Matrix3& measuredAccCovariance, - const Matrix3& measuredOmegaCovariance, - const Matrix3& integrationErrorCovariance, const Matrix3& biasAccCovariance, - const Matrix3& biasOmegaCovariance, const Matrix6& biasAccOmegaInt, - const bool use2ndOrderIntegration) { - if (!use2ndOrderIntegration) - throw("PreintegratedImuMeasurements no longer supports first-order integration: it incorrectly compensated for gravity"); - biasHat_ = biasHat; - boost::shared_ptr p = Params::MakeSharedD(); - p->gyroscopeCovariance = measuredOmegaCovariance; - p->accelerometerCovariance = measuredAccCovariance; - p->integrationCovariance = integrationErrorCovariance; - p->biasAccCovariance = biasAccCovariance; - p->biasOmegaCovariance = biasOmegaCovariance; - p->biasAccOmegaInt = biasAccOmegaInt; - p_ = p; - resetIntegration(); - preintMeasCov_.setZero(); -} -#endif //------------------------------------------------------------------------------ // CombinedImuFactor methods //------------------------------------------------------------------------------ @@ -275,41 +252,6 @@ std::ostream& operator<<(std::ostream& os, const CombinedImuFactor& f) { os << " noise model sigmas: " << f.noiseModel_->sigmas().transpose(); return os; } - -//------------------------------------------------------------------------------ -#ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V4 -CombinedImuFactor::CombinedImuFactor( - Key pose_i, Key vel_i, Key pose_j, Key vel_j, Key bias_i, Key bias_j, - const CombinedPreintegratedMeasurements& pim, const Vector3& n_gravity, - const Vector3& omegaCoriolis, const boost::optional& body_P_sensor, - const bool use2ndOrderCoriolis) -: Base(noiseModel::Gaussian::Covariance(pim.preintMeasCov_), pose_i, vel_i, - pose_j, vel_j, bias_i, bias_j), -_PIM_(pim) { - using P = CombinedPreintegratedMeasurements::Params; - auto p = boost::allocate_shared

    (Eigen::aligned_allocator

    (), pim.p()); - p->n_gravity = n_gravity; - p->omegaCoriolis = omegaCoriolis; - p->body_P_sensor = body_P_sensor; - p->use2ndOrderCoriolis = use2ndOrderCoriolis; - _PIM_.p_ = p; -} - -void CombinedImuFactor::Predict(const Pose3& pose_i, const Vector3& vel_i, - Pose3& pose_j, Vector3& vel_j, - const imuBias::ConstantBias& bias_i, - CombinedPreintegratedMeasurements& pim, - const Vector3& n_gravity, - const Vector3& omegaCoriolis, - const bool use2ndOrderCoriolis) { - // use deprecated predict - PoseVelocityBias pvb = pim.predict(pose_i, vel_i, bias_i, n_gravity, - omegaCoriolis, use2ndOrderCoriolis); - pose_j = pvb.pose; - vel_j = pvb.velocity; -} -#endif - } /// namespace gtsam diff --git a/gtsam/navigation/CombinedImuFactor.h b/gtsam/navigation/CombinedImuFactor.h index a89568433..e1a38bc91 100644 --- a/gtsam/navigation/CombinedImuFactor.h +++ b/gtsam/navigation/CombinedImuFactor.h @@ -220,17 +220,6 @@ public: /// @} -#ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V4 - /// deprecated constructor - /// NOTE(frank): assumes Z-Down convention, only second order integration supported - PreintegratedCombinedMeasurements(const imuBias::ConstantBias& biasHat, - const Matrix3& measuredAccCovariance, - const Matrix3& measuredOmegaCovariance, - const Matrix3& integrationErrorCovariance, - const Matrix3& biasAccCovariance, const Matrix3& biasOmegaCovariance, - const Matrix6& biasAccOmegaInt, const bool use2ndOrderIntegration = true); -#endif - private: /// Serialization function friend class boost::serialization::access; @@ -338,26 +327,7 @@ public: boost::optional H4 = boost::none, boost::optional H5 = boost::none, boost::optional H6 = boost::none) const; -#ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V4 - /// @deprecated typename - typedef gtsam::PreintegratedCombinedMeasurements CombinedPreintegratedMeasurements; - - /// @deprecated constructor - CombinedImuFactor(Key pose_i, Key vel_i, Key pose_j, Key vel_j, Key bias_i, - Key bias_j, const CombinedPreintegratedMeasurements& pim, - const Vector3& n_gravity, const Vector3& omegaCoriolis, - const boost::optional& body_P_sensor = boost::none, - const bool use2ndOrderCoriolis = false); - - // @deprecated use PreintegrationBase::predict - static void Predict(const Pose3& pose_i, const Vector3& vel_i, Pose3& pose_j, - Vector3& vel_j, const imuBias::ConstantBias& bias_i, - CombinedPreintegratedMeasurements& pim, - const Vector3& n_gravity, const Vector3& omegaCoriolis, - const bool use2ndOrderCoriolis = false); -#endif - -private: + private: /** Serialization function */ friend class boost::serialization::access; template diff --git a/gtsam/navigation/ImuFactor.cpp b/gtsam/navigation/ImuFactor.cpp index 582d96acb..ac7221cd9 100644 --- a/gtsam/navigation/ImuFactor.cpp +++ b/gtsam/navigation/ImuFactor.cpp @@ -106,32 +106,6 @@ void PreintegratedImuMeasurements::mergeWith(const PreintegratedImuMeasurements& preintMeasCov_ = P + *H2 * pim12.preintMeasCov_ * H2->transpose(); } #endif -//------------------------------------------------------------------------------ -#ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V4 -PreintegratedImuMeasurements::PreintegratedImuMeasurements( - const imuBias::ConstantBias& biasHat, const Matrix3& measuredAccCovariance, - const Matrix3& measuredOmegaCovariance, - const Matrix3& integrationErrorCovariance, bool use2ndOrderIntegration) { - if (!use2ndOrderIntegration) - throw("PreintegratedImuMeasurements no longer supports first-order integration: it incorrectly compensated for gravity"); - biasHat_ = biasHat; - boost::shared_ptr p = Params::MakeSharedD(); - p->gyroscopeCovariance = measuredOmegaCovariance; - p->accelerometerCovariance = measuredAccCovariance; - p->integrationCovariance = integrationErrorCovariance; - p_ = p; - resetIntegration(); -} - -void PreintegratedImuMeasurements::integrateMeasurement( - const Vector3& measuredAcc, const Vector3& measuredOmega, double deltaT, - boost::optional body_P_sensor) { - // modify parameters to accommodate deprecated method:-( - p_->body_P_sensor = body_P_sensor; - integrateMeasurement(measuredAcc, measuredOmega, deltaT); -} -#endif - //------------------------------------------------------------------------------ // ImuFactor methods //------------------------------------------------------------------------------ @@ -218,43 +192,15 @@ ImuFactor::shared_ptr ImuFactor::Merge(const shared_ptr& f01, // return new factor auto pim02 = Merge(f01->preintegratedMeasurements(), f12->preintegratedMeasurements()); - return boost::make_shared(f01->key1(),// P0 - f01->key2(),// V0 - f12->key3(),// P2 - f12->key4(),// V2 - f01->key5(),// B + return boost::make_shared(f01->key1(), // P0 + f01->key2(), // V0 + f12->key3(), // P2 + f12->key4(), // V2 + f01->key5(), // B pim02); } #endif -//------------------------------------------------------------------------------ -#ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V4 -ImuFactor::ImuFactor(Key pose_i, Key vel_i, Key pose_j, Key vel_j, Key bias, - const PreintegratedImuMeasurements& pim, const Vector3& n_gravity, - const Vector3& omegaCoriolis, const boost::optional& body_P_sensor, - const bool use2ndOrderCoriolis) : -Base(noiseModel::Gaussian::Covariance(pim.preintMeasCov_), pose_i, vel_i, - pose_j, vel_j, bias), _PIM_(pim) { - boost::shared_ptr p = boost::make_shared< - PreintegrationParams>(pim.p()); - p->n_gravity = n_gravity; - p->omegaCoriolis = omegaCoriolis; - p->body_P_sensor = body_P_sensor; - p->use2ndOrderCoriolis = use2ndOrderCoriolis; - _PIM_.p_ = p; -} - -void ImuFactor::Predict(const Pose3& pose_i, const Vector3& vel_i, - Pose3& pose_j, Vector3& vel_j, const imuBias::ConstantBias& bias_i, - PreintegratedImuMeasurements& pim, const Vector3& n_gravity, - const Vector3& omegaCoriolis, const bool use2ndOrderCoriolis) { - // use deprecated predict - PoseVelocityBias pvb = pim.predict(pose_i, vel_i, bias_i, n_gravity, - omegaCoriolis, use2ndOrderCoriolis); - pose_j = pvb.pose; - vel_j = pvb.velocity; -} -#endif //------------------------------------------------------------------------------ // ImuFactor2 methods //------------------------------------------------------------------------------ diff --git a/gtsam/navigation/ImuFactor.h b/gtsam/navigation/ImuFactor.h index 7e080ffd5..f65ae67da 100644 --- a/gtsam/navigation/ImuFactor.h +++ b/gtsam/navigation/ImuFactor.h @@ -140,24 +140,7 @@ public: void mergeWith(const PreintegratedImuMeasurements& pim, Matrix9* H1, Matrix9* H2); #endif -#ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V4 - /// @deprecated constructor - /// NOTE(frank): assumes Z-Down convention, only second order integration supported - PreintegratedImuMeasurements(const imuBias::ConstantBias& biasHat, - const Matrix3& measuredAccCovariance, - const Matrix3& measuredOmegaCovariance, - const Matrix3& integrationErrorCovariance, - bool use2ndOrderIntegration = true); - - /// @deprecated version of integrateMeasurement with body_P_sensor - /// Use parameters instead - void integrateMeasurement(const Vector3& measuredAcc, - const Vector3& measuredOmega, double dt, - boost::optional body_P_sensor); -#endif - -private: - + private: /// Serialization function friend class boost::serialization::access; template @@ -253,27 +236,7 @@ public: static shared_ptr Merge(const shared_ptr& f01, const shared_ptr& f12); #endif -#ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V4 - /// @deprecated typename - typedef PreintegratedImuMeasurements PreintegratedMeasurements; - - /// @deprecated constructor, in the new one gravity, coriolis settings are in PreintegrationParams - ImuFactor(Key pose_i, Key vel_i, Key pose_j, Key vel_j, Key bias, - const PreintegratedMeasurements& preintegratedMeasurements, - const Vector3& n_gravity, const Vector3& omegaCoriolis, - const boost::optional& body_P_sensor = boost::none, - const bool use2ndOrderCoriolis = false); - - /// @deprecated use PreintegrationBase::predict, - /// in the new one gravity, coriolis settings are in PreintegrationParams - static void Predict(const Pose3& pose_i, const Vector3& vel_i, Pose3& pose_j, - Vector3& vel_j, const imuBias::ConstantBias& bias_i, - PreintegratedMeasurements& pim, const Vector3& n_gravity, - const Vector3& omegaCoriolis, const bool use2ndOrderCoriolis = false); -#endif - -private: - + private: /** Serialization function */ friend class boost::serialization::access; template diff --git a/gtsam/navigation/PreintegrationBase.cpp b/gtsam/navigation/PreintegrationBase.cpp index 4af752ac0..45560f34d 100644 --- a/gtsam/navigation/PreintegrationBase.cpp +++ b/gtsam/navigation/PreintegrationBase.cpp @@ -193,22 +193,6 @@ Vector9 PreintegrationBase::computeErrorAndJacobians(const Pose3& pose_i, return error; } -//------------------------------------------------------------------------------ -#ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V4 -PoseVelocityBias PreintegrationBase::predict(const Pose3& pose_i, - const Vector3& vel_i, const imuBias::ConstantBias& bias_i, - const Vector3& n_gravity, const Vector3& omegaCoriolis, - const bool use2ndOrderCoriolis) const { -// NOTE(frank): parameters are supposed to be constant, below is only provided for compatibility - boost::shared_ptr q = boost::make_shared(p()); - q->n_gravity = n_gravity; - q->omegaCoriolis = omegaCoriolis; - q->use2ndOrderCoriolis = use2ndOrderCoriolis; - p_ = q; - return PoseVelocityBias(predict(NavState(pose_i, vel_i), bias_i), bias_i); -} - -#endif //------------------------------------------------------------------------------ } // namespace gtsam diff --git a/gtsam/navigation/PreintegrationBase.h b/gtsam/navigation/PreintegrationBase.h index 29d7814b5..3ef7ad5df 100644 --- a/gtsam/navigation/PreintegrationBase.h +++ b/gtsam/navigation/PreintegrationBase.h @@ -32,25 +32,6 @@ namespace gtsam { -#ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V4 -/// @deprecated -struct PoseVelocityBias { - Pose3 pose; - Vector3 velocity; - imuBias::ConstantBias bias; - PoseVelocityBias(const Pose3& _pose, const Vector3& _velocity, - const imuBias::ConstantBias _bias) : - pose(_pose), velocity(_velocity), bias(_bias) { - } - PoseVelocityBias(const NavState& navState, const imuBias::ConstantBias _bias) : - pose(navState.pose()), velocity(navState.velocity()), bias(_bias) { - } - NavState navState() const { - return NavState(pose, velocity); - } -}; -#endif - /** * PreintegrationBase is the base class for PreintegratedMeasurements * (in ImuFactor) and CombinedPreintegratedMeasurements (in CombinedImuFactor). @@ -63,11 +44,6 @@ class GTSAM_EXPORT PreintegrationBase { typedef PreintegrationParams Params; protected: - /// Parameters. Declared mutable only for deprecated predict method. - /// TODO(frank): make const once deprecated method is removed -#ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V4 - mutable -#endif boost::shared_ptr p_; /// Acceleration and gyro bias used for preintegration @@ -121,12 +97,7 @@ class GTSAM_EXPORT PreintegrationBase { return *boost::static_pointer_cast(p_); } -#ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V4 - void set_body_P_sensor(const Pose3& body_P_sensor) { - p_->body_P_sensor = body_P_sensor; - } -#endif -/// @} + /// @} /// @name Instance variables access /// @{ @@ -201,18 +172,6 @@ class GTSAM_EXPORT PreintegrationBase { OptionalJacobian<9, 6> H3 = boost::none, OptionalJacobian<9, 3> H4 = boost::none, OptionalJacobian<9, 6> H5 = boost::none) const; -#ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V4 - /// @name Deprecated - /// @{ - - /// @deprecated predict - PoseVelocityBias predict(const Pose3& pose_i, const Vector3& vel_i, - const imuBias::ConstantBias& bias_i, const Vector3& n_gravity, - const Vector3& omegaCoriolis, const bool use2ndOrderCoriolis = false) const; - - /// @} -#endif - private: /** Serialization function */ friend class boost::serialization::access; diff --git a/gtsam/navigation/ScenarioRunner.h b/gtsam/navigation/ScenarioRunner.h index 649d0fe12..1577e36fe 100644 --- a/gtsam/navigation/ScenarioRunner.h +++ b/gtsam/navigation/ScenarioRunner.h @@ -104,15 +104,6 @@ class GTSAM_EXPORT ScenarioRunner { /// Estimate covariance of sampled noise for sanity-check Matrix6 estimateNoiseCovariance(size_t N = 1000) const; - -#ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V4 - /// @name Deprecated - /// @{ - ScenarioRunner(const Scenario* scenario, const SharedParams& p, - double imuSampleTime = 1.0 / 100.0, const Bias& bias = Bias()) - : ScenarioRunner(*scenario, p, imuSampleTime, bias) {} - /// @} -#endif }; } // namespace gtsam diff --git a/gtsam/navigation/tests/testNavState.cpp b/gtsam/navigation/tests/testNavState.cpp index 8ea8ce9b5..f8b8b9f33 100644 --- a/gtsam/navigation/tests/testNavState.cpp +++ b/gtsam/navigation/tests/testNavState.cpp @@ -163,37 +163,6 @@ TEST( NavState, Manifold ) { EXPECT(assert_equal(numericalDerivative22(local, state2, kIdentity), aH2)); } -/* ************************************************************************* */ -#ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V4 -TEST(NavState, Update) { - Vector3 omega(M_PI / 100.0, 0.0, 0.0); - Vector3 acc(0.1, 0.0, 0.0); - double dt = 10; - Matrix9 aF; - Matrix93 aG1, aG2; - boost::function update = - boost::bind(&NavState::update, _1, _2, _3, dt, boost::none, - boost::none, boost::none); - Vector3 b_acc = kAttitude * acc; - NavState expected(kAttitude.expmap(dt * omega), - kPosition + Point3((kVelocity + b_acc * dt / 2) * dt), - kVelocity + b_acc * dt); - NavState actual = kState1.update(acc, omega, dt, aF, aG1, aG2); - EXPECT(assert_equal(expected, actual)); - EXPECT(assert_equal(numericalDerivative31(update, kState1, acc, omega, 1e-7), aF, 1e-7)); - EXPECT(assert_equal(numericalDerivative32(update, kState1, acc, omega, 1e-7), aG1, 1e-7)); - EXPECT(assert_equal(numericalDerivative33(update, kState1, acc, omega, 1e-7), aG2, 1e-7)); - - // Try different values - omega = Vector3(0.1, 0.2, 0.3); - acc = Vector3(0.4, 0.5, 0.6); - kState1.update(acc, omega, dt, aF, aG1, aG2); - EXPECT(assert_equal(numericalDerivative31(update, kState1, acc, omega, 1e-7), aF, 1e-7)); - EXPECT(assert_equal(numericalDerivative32(update, kState1, acc, omega, 1e-7), aG1, 1e-7)); - EXPECT(assert_equal(numericalDerivative33(update, kState1, acc, omega, 1e-7), aG2, 1e-7)); -} -#endif - /* ************************************************************************* */ static const double dt = 2.0; boost::function coriolis = boost::bind( diff --git a/gtsam/navigation/tests/testPoseVelocityBias.cpp b/gtsam/navigation/tests/testPoseVelocityBias.cpp index 0b897bc6e..f3c36335b 100644 --- a/gtsam/navigation/tests/testPoseVelocityBias.cpp +++ b/gtsam/navigation/tests/testPoseVelocityBias.cpp @@ -25,40 +25,6 @@ using namespace std; using namespace gtsam; -#ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V4 - -// Should be seen as between(pvb1,pvb2), i.e., written as pvb2 \omin pvb1 -Vector9 error(const PoseVelocityBias& pvb1, const PoseVelocityBias& pvb2) { - Matrix3 R1 = pvb1.pose.rotation().matrix(); - // Ri.transpose() translate the error from the global frame into pose1's frame - const Vector3 fp = R1.transpose() * (pvb2.pose.translation() - pvb1.pose.translation()); - const Vector3 fv = R1.transpose() * (pvb2.velocity - pvb1.velocity); - const Rot3 R1BetweenR2 = pvb1.pose.rotation().between(pvb2.pose.rotation()); - const Vector3 fR = Rot3::Logmap(R1BetweenR2); - Vector9 r; - r << fp, fv, fR; - return r; -} - -/* ************************************************************************************************/ -TEST(PoseVelocityBias, error) { - Point3 i1(0, 1, 0), j1(-1, 0, 0), k1(0, 0, 1); - Pose3 x1(Rot3(i1, j1, k1), Point3(5.0, 1.0, 0.0)); - Vector3 v1(Vector3(0.5, 0.0, 0.0)); - imuBias::ConstantBias bias1(Vector3(0.2, 0, 0), Vector3(0.1, 0, 0.3)); - - Pose3 x2(Rot3(i1, j1, k1).expmap(Vector3(0.1, 0.2, 0.3)), Point3(5.5, 1.0, 6.0)); - Vector3 v2(Vector3(0.5, 4.0, 3.0)); - imuBias::ConstantBias bias2(Vector3(0.1, 0.2, -0.3), Vector3(0.2, 0.3, 0.1)); - - PoseVelocityBias pvb1(x1, v1, bias1), pvb2(x2, v2, bias2); - - Vector9 expected, actual = error(pvb1, pvb2); - expected << 0.0, -0.5, 6.0, 4.0, 0.0, 3.0, 0.1, 0.2, 0.3; - EXPECT(assert_equal(expected, actual, 1e-9)); -} -#endif - /* ************************************************************************************************/ int main() { TestResult tr; diff --git a/gtsam/nonlinear/LinearContainerFactor.h b/gtsam/nonlinear/LinearContainerFactor.h index 8a1f600ff..df293b78a 100644 --- a/gtsam/nonlinear/LinearContainerFactor.h +++ b/gtsam/nonlinear/LinearContainerFactor.h @@ -140,21 +140,14 @@ public: * Utility function for converting linear graphs to nonlinear graphs * consisting of LinearContainerFactors. */ - GTSAM_EXPORT static NonlinearFactorGraph ConvertLinearGraph(const GaussianFactorGraph& linear_graph, + GTSAM_EXPORT + static NonlinearFactorGraph ConvertLinearGraph(const GaussianFactorGraph& linear_graph, const Values& linearizationPoint = Values()); -#ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V4 - GTSAM_EXPORT static NonlinearFactorGraph convertLinearGraph(const GaussianFactorGraph& linear_graph, - const Values& linearizationPoint = Values()) { - return ConvertLinearGraph(linear_graph, linearizationPoint); - } -#endif - -protected: - GTSAM_EXPORT void initializeLinearizationPoint(const Values& linearizationPoint); - -private: + protected: + GTSAM_EXPORT void initializeLinearizationPoint(const Values& linearizationPoint); + private: /** Serialization function */ friend class boost::serialization::access; template diff --git a/gtsam/nonlinear/NonlinearFactor.h b/gtsam/nonlinear/NonlinearFactor.h index 63547a248..676d42349 100644 --- a/gtsam/nonlinear/NonlinearFactor.h +++ b/gtsam/nonlinear/NonlinearFactor.h @@ -29,13 +29,6 @@ #include #include -#ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V4 -#define ADD_CLONE_NONLINEAR_FACTOR(Derived) \ - virtual gtsam::NonlinearFactor::shared_ptr clone() const { \ - return boost::static_pointer_cast( \ - gtsam::NonlinearFactor::shared_ptr(new Derived(*this))); } -#endif - namespace gtsam { using boost::assign::cref_list_of; @@ -251,21 +244,13 @@ public: */ boost::shared_ptr linearize(const Values& x) const; -#ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V4 - /// @name Deprecated - /// @{ - SharedNoiseModel get_noiseModel() const { return noiseModel_; } - /// @} -#endif - -private: - + private: /** Serialization function */ friend class boost::serialization::access; template void serialize(ARCHIVE & ar, const unsigned int /*version*/) { ar & boost::serialization::make_nvp("NonlinearFactor", - boost::serialization::base_object(*this)); + boost::serialization::base_object(*this)); ar & BOOST_SERIALIZATION_NVP(noiseModel_); } diff --git a/gtsam/slam/SmartProjectionFactor.h b/gtsam/slam/SmartProjectionFactor.h index 15d632cda..15b2474d1 100644 --- a/gtsam/slam/SmartProjectionFactor.h +++ b/gtsam/slam/SmartProjectionFactor.h @@ -443,25 +443,6 @@ public: /** return the farPoint state */ bool isFarPoint() const { return result_.farPoint(); } -#ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V4 - /// @name Deprecated - /// @{ - // It does not make sense to optimize for a camera where the pose would not be - // the actual pose of the camera. An unfortunate consequence of deprecating - // this constructor means that we cannot optimize for calibration when the - // camera is offset from the body pose. That would need a new factor with - // (body) pose and calibration as variables. However, that use case is - // unlikely: when a global offset is know, calibration is typically known. - SmartProjectionFactor( - const SharedNoiseModel& sharedNoiseModel, - const boost::optional body_P_sensor, - const SmartProjectionParams& params = SmartProjectionParams()) - : Base(sharedNoiseModel, body_P_sensor), - params_(params), - result_(TriangulationResult::Degenerate()) {} - /// @} -#endif - private: /// Serialization function diff --git a/gtsam/slam/dataset.h b/gtsam/slam/dataset.h index 032799429..9146d7681 100644 --- a/gtsam/slam/dataset.h +++ b/gtsam/slam/dataset.h @@ -301,13 +301,4 @@ GTSAM_EXPORT Values initialCamerasEstimate(const SfmData& db); */ GTSAM_EXPORT Values initialCamerasAndPointsEstimate(const SfmData& db); -/// Aliases for backwards compatibility -#ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V4 -typedef SfmMeasurement SfM_Measurement; -typedef SiftIndex SIFT_Index; -typedef SfmTrack SfM_Track; -typedef SfmCamera SfM_Camera; -typedef SfmData SfM_data; -#endif - -} // namespace gtsam +} // namespace gtsam diff --git a/gtsam_unstable/nonlinear/BatchFixedLagSmoother.h b/gtsam_unstable/nonlinear/BatchFixedLagSmoother.h index d71cdd409..8df30cb80 100644 --- a/gtsam_unstable/nonlinear/BatchFixedLagSmoother.h +++ b/gtsam_unstable/nonlinear/BatchFixedLagSmoother.h @@ -117,15 +117,6 @@ public: const NonlinearFactorGraph& graph, const Values& theta, const KeyVector& keys, const GaussianFactorGraph::Eliminate& eliminateFunction = EliminatePreferCholesky); -#ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V4 - static NonlinearFactorGraph calculateMarginalFactors( - const NonlinearFactorGraph& graph, const Values& theta, const std::set& keys, - const GaussianFactorGraph::Eliminate& eliminateFunction = EliminatePreferCholesky) { - KeyVector keyVector(keys.begin(), keys.end()); - return CalculateMarginalFactors(graph, theta, keyVector, eliminateFunction); - } -#endif - protected: /** A typedef defining an Key-Factor mapping **/ diff --git a/tests/testManifold.cpp b/tests/testManifold.cpp index d0b4a1ffa..ac3a09e36 100644 --- a/tests/testManifold.cpp +++ b/tests/testManifold.cpp @@ -149,34 +149,6 @@ TEST(Manifold, DefaultChart) { EXPECT(assert_equal((Vector) Z_3x1, traits::Local(R, R))); } -#ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V4 -//****************************************************************************** -typedef ProductManifold MyPoint2Pair; - -// Define any direct product group to be a model of the multiplicative Group concept -namespace gtsam { -template<> struct traits : internal::ManifoldTraits { - static void Print(const MyPoint2Pair& m, const string& s = "") { - cout << s << "(" << m.first << "," << m.second << ")" << endl; - } - static bool Equals(const MyPoint2Pair& m1, const MyPoint2Pair& m2, double tol = 1e-8) { - return m1 == m2; - } -}; -} - -TEST(Manifold, ProductManifold) { - BOOST_CONCEPT_ASSERT((IsManifold)); - MyPoint2Pair pair1(Point2(0,0),Point2(0,0)); - Vector4 d; - d << 1,2,3,4; - MyPoint2Pair expected(Point2(1,2),Point2(3,4)); - MyPoint2Pair pair2 = pair1.retract(d); - EXPECT(assert_equal(expected,pair2,1e-9)); - EXPECT(assert_equal(d, pair1.localCoordinates(pair2),1e-9)); -} -#endif - //****************************************************************************** int main() { TestResult tr; From e7214a7777e31509ff2ddfc7e393204a28be230a Mon Sep 17 00:00:00 2001 From: akrishnan86 Date: Thu, 23 Jul 2020 00:06:31 -0700 Subject: [PATCH 240/869] constructor API change after review1 --- gtsam/sfm/MFAS.cpp | 140 +++++++++++++++-------------------- gtsam/sfm/MFAS.h | 92 +++++++++-------------- gtsam/sfm/tests/testMFAS.cpp | 10 +-- 3 files changed, 101 insertions(+), 141 deletions(-) diff --git a/gtsam/sfm/MFAS.cpp b/gtsam/sfm/MFAS.cpp index 8c3e3596a..e3288387e 100644 --- a/gtsam/sfm/MFAS.cpp +++ b/gtsam/sfm/MFAS.cpp @@ -5,76 +5,53 @@ using std::pair; using std::vector; MFAS::MFAS(const std::shared_ptr> &nodes, - const std::shared_ptr &relativeTranslations, + const TranslationEdges& relativeTranslations, const Unit3 &projection_direction) - : nodes_(nodes), relativeTranslations_(relativeTranslations), - relativeTranslationsForWeights_(std::make_shared()) { - // iterate over edges and flip all edges that have negative weights, - // while storing the magnitude of the weights. - for (auto it = relativeTranslations->begin(); - it != relativeTranslations->end(); it++) { - KeyPair edge = it->first; - double weight = it->second.dot(projection_direction); - if (weight < 0.0) { - std::swap(edge.first, edge.second); - weight *= -1; - } - positiveEdgeWeights_[edge] = weight; + : nodes_(nodes) { + // iterate over edges, obtain weights by projecting + // their relativeTranslations along the projection direction + for (auto it = relativeTranslations.begin(); + it != relativeTranslations.end(); it++) { + edgeWeights_[it->first] = it->second.dot(projection_direction); } } -MFAS::MFAS(const std::shared_ptr> &nodes, - const std::map &edgeWeights) : nodes_(nodes), - relativeTranslations_(std::make_shared()), - relativeTranslationsForWeights_(std::make_shared< - TranslationEdges>()) { - // similar to the above direction constructor, but here weights are - // provided as input. - for (auto it = edgeWeights.begin(); it != edgeWeights.end(); it++) { - KeyPair edge = it->first; - - // When constructed like this, we do not have access to the relative translations. - // So, we store the unswapped edge in the relativeTranslationsForWeights_ map with a default - // Unit3 value. This helps retain the original direction of the edge in the returned result - // of computeOutlierWeights - relativeTranslationsForWeights_->insert({edge, Unit3()}); - - double weight = it->second; - if (weight < 0.0) { - // change the direction of the edge to make weight positive - std::swap(edge.first, edge.second); - weight *= -1; - } - positiveEdgeWeights_[edge] = weight; - } -} - -std::vector MFAS::computeOrdering() { +std::vector MFAS::computeOrdering() const { FastMap in_weights; // sum on weights of incoming edges for a node FastMap out_weights; // sum on weights of outgoing edges for a node FastMap > in_neighbors; FastMap > out_neighbors; + vector ordered_nodes; // nodes in MFAS order (result) + FastMap ordered_positions; // map from node to its position in the output order + // populate neighbors and weights - for (auto it = positiveEdgeWeights_.begin(); it != positiveEdgeWeights_.end(); it++) { + for (auto it = edgeWeights_.begin(); it != edgeWeights_.end(); it++) { const KeyPair &edge = it->first; - in_weights[edge.second] += it->second; - out_weights[edge.first] += it->second; - in_neighbors[edge.second].push_back(edge.first); - out_neighbors[edge.first].push_back(edge.second); + const double weight = it->second; + Key edge_source = weight >= 0 ? edge.first : edge.second; + Key edge_dest = weight >= 0 ? edge.second : edge.first; + + in_weights[edge_dest] += weight; + out_weights[edge_source] += weight; + in_neighbors[edge_dest].push_back(edge_source); + out_neighbors[edge_source].push_back(edge_dest); } // in each iteration, one node is appended to the ordered list - while (orderedNodes_.size() < nodes_->size()) { + while (ordered_nodes.size() < nodes_->size()) { // finding the node with the max heuristic score Key choice; double max_score = 0.0; for (const Key &node : *nodes_) { - if (orderedPositions_.find(node) == orderedPositions_.end()) { - // is this a source + // if this node has not been chosen so far + if (ordered_positions.find(node) == ordered_positions.end()) { + // is this a root node if (in_weights[node] < 1e-8) { + // TODO(akshay-krishnan) if there are multiple roots, it is better to choose the + // one with highest heuristic. This is missing in the 1dsfm solution. choice = node; break; } else { @@ -86,53 +63,54 @@ std::vector MFAS::computeOrdering() { } } } - // find its inbrs, adjust their wout_deg + // find its in_neighbors, adjust their out_weights for (auto it = in_neighbors[choice].begin(); it != in_neighbors[choice].end(); ++it) - out_weights[*it] -= positiveEdgeWeights_[KeyPair(*it, choice)]; - // find its onbrs, adjust their win_deg + // the edge could be either (*it, choice) with a positive weight or (choice, *it) with a negative weight + out_weights[*it] -= edgeWeights_.find(KeyPair(*it, choice)) == edgeWeights_.end() ? -edgeWeights_.at(KeyPair(choice, *it)) : edgeWeights_.at(KeyPair(*it, choice)); + + // find its out_neighbors, adjust their in_weights for (auto it = out_neighbors[choice].begin(); it != out_neighbors[choice].end(); ++it) - in_weights[*it] -= positiveEdgeWeights_[KeyPair(choice, *it)]; + in_weights[*it] -= edgeWeights_.find(KeyPair(choice, *it)) == edgeWeights_.end() ? -edgeWeights_.at(KeyPair(*it, choice)) : edgeWeights_.at(KeyPair(choice, *it)); - orderedPositions_[choice] = orderedNodes_.size(); - orderedNodes_.push_back(choice); + ordered_positions[choice] = ordered_nodes.size(); + ordered_nodes.push_back(choice); } - return orderedNodes_; + return ordered_nodes; } -std::map MFAS::computeOutlierWeights() { - // if ordering has not been computed yet - if (orderedNodes_.size() != nodes_->size()) { - computeOrdering(); - } - // iterate over all edges - // start and end iterators depend on whether we are using relativeTranslations_ or - // relativeTranslationsForWeights_ to store the original edge directions - TranslationEdges::iterator start, end; - if (relativeTranslationsForWeights_->size() == 0) { - start = relativeTranslations_->begin(); - end = relativeTranslations_->end(); - } else { - start = relativeTranslationsForWeights_->begin(); - end = relativeTranslationsForWeights_->end(); +std::map MFAS::computeOutlierWeights() const { + vector ordered_nodes = computeOrdering(); + FastMap ordered_positions; + std::map outlier_weights; + + // create a map becuase it is much faster to lookup the position of each node + // TODO(akshay-krishnan) this is already computed in computeOrdering. Would be nice if + // we could re-use. Either use an optional argument or change the output of + // computeOrdering + for(unsigned int i = 0; i < ordered_nodes.size(); i++) { + ordered_positions[ordered_nodes[i]] = i; } - for (auto it = start; it != end; it++) { - // relativeTranslations may have negative weight edges, we make sure all edges - // are along the positive direction by flipping them if they are not. - KeyPair edge = it->first; - if (positiveEdgeWeights_.find(edge) == positiveEdgeWeights_.end()) { - std::swap(edge.first, edge.second); + // iterate over all edges + for (auto it = edgeWeights_.begin(); it != edgeWeights_.end(); it++) { + Key edge_source, edge_dest; + if(it->second > 0) { + edge_source = it->first.first; + edge_dest = it->first.second; + } else { + edge_source = it->first.second; + edge_dest = it->first.first; } // if the ordered position of nodes is not consistent with the edge // direction for consistency second should be greater than first - if (orderedPositions_.at(edge.second) < orderedPositions_.at(edge.first)) { - outlierWeights_[it->first] = std::abs(positiveEdgeWeights_[edge]); + if (ordered_positions.at(edge_dest) < ordered_positions.at(edge_source)) { + outlier_weights[it->first] = std::abs(edgeWeights_.at(it->first)); } else { - outlierWeights_[it->first] = 0; + outlier_weights[it->first] = 0; } } - return outlierWeights_; + return outlier_weights; } \ No newline at end of file diff --git a/gtsam/sfm/MFAS.h b/gtsam/sfm/MFAS.h index 10052548b..c8ea4f45d 100644 --- a/gtsam/sfm/MFAS.h +++ b/gtsam/sfm/MFAS.h @@ -9,8 +9,7 @@ * -------------------------------------------------------------------------- */ -#ifndef __MFAS_H__ -#define __MFAS_H__ +#pragma once #include #include @@ -21,10 +20,6 @@ namespace gtsam { -// used to represent edges between two nodes in the graph -using KeyPair = std::pair; -using TranslationEdges = std::map; - /** The MFAS class to solve a Minimum feedback arc set (MFAS) problem. We implement the solution from: @@ -32,77 +27,64 @@ using TranslationEdges = std::map; Proceedings of the European Conference on Computer Vision, ECCV 2014 Given a weighted directed graph, the objective in a Minimum feedback arc set - problem is to obtain a graph that does not contain any cycles by removing + problem is to obtain a directed acyclic graph by removing edges such that the total weight of removed edges is minimum. @addtogroup SFM */ class MFAS { + public: + // used to represent edges between two nodes in the graph + using KeyPair = std::pair; + using TranslationEdges = std::map; + private: + // pointer to nodes in the graph + const std::shared_ptr> nodes_; + + // edges with a direction such that all weights are positive + // i.e, edges that originally had negative weights are flipped + std::map edgeWeights_; + public: /** - * @brief Construct from the nodes in a graph (points in 3D), edges - * that are translation directions in 3D and the direction in - * which edges are to be projected. + * @brief Construct from the nodes in a graph and weighted directed edges + * between the graph. A shared pointer to the nodes is used as input parameter. + * This is because, MFAS ordering is usually used to compute the ordering of a + * large graph that is already stored in memory. It is unnecessary to copy the + * set of nodes in this class. + * @param nodes: Nodes in the graph + * @param edgeWeights: weights of edges in the graph (map from pair of keys + * to signed double) + */ + MFAS(const std::shared_ptr> &nodes, + const std::map &edgeWeights) : + nodes_(nodes), edgeWeights_(edgeWeights) {} + + /** + * @brief Constructor for using in the context of translation averaging. Here, + * the nodes of the graph are cameras in 3D and the edges have a unit translation + * direction between them. The weights of the edges is computed by projecting + * them along a projection direction. * @param nodes Nodes in the graph * @param relativeTranslations translation directions between nodes * @param projectionDirection direction in which edges are to be projected */ MFAS(const std::shared_ptr> &nodes, - const std::shared_ptr &relativeTranslations, + const TranslationEdges& relativeTranslations, const Unit3 &projectionDirection); - /** - * @brief Construct from the nodes in a graph and weighted directed edges - * between the graph. Not recommended for any purpose other than unit testing. - * The computeOutlierWeights method will return an empty output if this constructor - * is used. - * When used in a translation averaging context, these weights are obtained - * by projecting edges in a particular direction. - * @param nodes: Nodes in the graph - * @param edgeWeights: weights of edges in the graph (map from edge to signed double) - */ - MFAS(const std::shared_ptr> &nodes, - const std::map &edgeWeights); - /** * @brief Computes the "outlier weights" of the graph. We define the outlier weight - * of a edge to be zero if the edge in an inlier and the magnitude of its edgeWeight - * if it is an outlier. This function can only be used when constructing the + * of a edge to be zero if the edge is an inlier and the magnitude of its edgeWeight + * if it is an outlier. * @return outlierWeights: map from an edge to its outlier weight. */ - std::map computeOutlierWeights(); + std::map computeOutlierWeights() const; /** * @brief Computes the 1D MFAS ordering of nodes in the graph * @return orderedNodes: vector of nodes in the obtained order */ - std::vector computeOrdering(); - - private: - // pointer to nodes in the graph - const std::shared_ptr> nodes_; - // pointer to translation edges (translation directions between two node points) - const std::shared_ptr relativeTranslations_; - - // relative translations when the object is initialized without using the actual - // relative translations, but with the weights from projecting in a certain - // direction. This is used for unit testing, but not in practice. - std::shared_ptr relativeTranslationsForWeights_; - - // edges with a direction such that all weights are positive - // i.e, edges that originally had negative weights are flipped - std::map positiveEdgeWeights_; - - // map from edges to their outlier weight - std::map outlierWeights_; - - // nodes arranged in the MFAS order - std::vector orderedNodes_; - - // map from nodes to their position in the MFAS order - // used to speed up computation (lookup) when computing outlierWeights_ - FastMap orderedPositions_; + std::vector computeOrdering() const; }; } // namespace gtsam - -#endif // __MFAS_H__ diff --git a/gtsam/sfm/tests/testMFAS.cpp b/gtsam/sfm/tests/testMFAS.cpp index 345b3a5d4..8819493be 100644 --- a/gtsam/sfm/tests/testMFAS.cpp +++ b/gtsam/sfm/tests/testMFAS.cpp @@ -15,7 +15,7 @@ using namespace gtsam; */ // edges in the graph - last edge from node 3 to 0 is an outlier -vector graph = {make_pair(3, 2), make_pair(0, 1), make_pair(3, 1), +vector graph = {make_pair(3, 2), make_pair(0, 1), make_pair(3, 1), make_pair(1, 2), make_pair(0, 2), make_pair(3, 0)}; // nodes in the graph vector nodes = {Key(0), Key(1), Key(2), Key(3)}; @@ -26,9 +26,9 @@ vector weights2 = {0.5, 0.75, -0.25, 0.75, 1, 0.5}; // helper function to obtain map from keypairs to weights from the // vector representations -std::map getEdgeWeights(const vector &graph, +std::map getEdgeWeights(const vector &graph, const vector &weights) { - std::map edgeWeights; + std::map edgeWeights; for (size_t i = 0; i < graph.size(); i++) { edgeWeights[graph[i]] = weights[i]; } @@ -51,7 +51,7 @@ TEST(MFAS, OrderingWeights2) { EXPECT_LONGS_EQUAL(gt_ordered_nodes[i], ordered_nodes[i]); } - map outlier_weights = mfas_obj.computeOutlierWeights(); + map outlier_weights = mfas_obj.computeOutlierWeights(); // since edge between 3 and 0 is inconsistent with the ordering, it must have // positive outlier weight, other outlier weights must be zero @@ -81,7 +81,7 @@ TEST(MFAS, OrderingWeights1) { EXPECT_LONGS_EQUAL(gt_ordered_nodes[i], ordered_nodes[i]); } - map outlier_weights = mfas_obj.computeOutlierWeights(); + map outlier_weights = mfas_obj.computeOutlierWeights(); // since edge between 3 and 0 is inconsistent with the ordering, it must have // positive outlier weight, other outlier weights must be zero From e993afe2bfe70366685b5395c84c3217ff8e63f7 Mon Sep 17 00:00:00 2001 From: acxz <17132214+acxz@users.noreply.github.com> Date: Thu, 23 Jul 2020 14:05:23 -0400 Subject: [PATCH 241/869] replace boost random with std random --- examples/SolverComparer.cpp | 6 ++-- gtsam/geometry/SO4.cpp | 4 +-- gtsam/geometry/SO4.h | 2 +- timing/timeFactorOverhead.cpp | 13 ++++---- timing/timeFrobeniusFactor.cpp | 3 +- timing/timeMatrixOps.cpp | 61 +++++++++++++++++----------------- 6 files changed, 46 insertions(+), 43 deletions(-) diff --git a/examples/SolverComparer.cpp b/examples/SolverComparer.cpp index d1155fe4c..718ae6286 100644 --- a/examples/SolverComparer.cpp +++ b/examples/SolverComparer.cpp @@ -50,11 +50,11 @@ #include #include #include -#include #include #include #include +#include #ifdef GTSAM_USE_TBB #include // tbb::task_arena @@ -554,8 +554,8 @@ void runCompare() void runPerturb() { // Set up random number generator - boost::mt19937 rng; - boost::normal_distribution normal(0.0, perturbationNoise); + std::mt19937 rng; + std::normal_distribution normal(0.0, perturbationNoise); // Perturb values VectorValues noise; diff --git a/gtsam/geometry/SO4.cpp b/gtsam/geometry/SO4.cpp index 8a78bb83f..1c4920af8 100644 --- a/gtsam/geometry/SO4.cpp +++ b/gtsam/geometry/SO4.cpp @@ -35,7 +35,7 @@ namespace gtsam { // TODO(frank): is this better than SOn::Random? // /* ************************************************************************* -// */ static Vector3 randomOmega(boost::mt19937 &rng) { +// */ static Vector3 randomOmega(std::mt19937 &rng) { // static std::uniform_real_distribution randomAngle(-M_PI, M_PI); // return Unit3::Random(rng).unitVector() * randomAngle(rng); // } @@ -43,7 +43,7 @@ namespace gtsam { // /* ************************************************************************* // */ // // Create random SO(4) element using direct product of lie algebras. -// SO4 SO4::Random(boost::mt19937 &rng) { +// SO4 SO4::Random(std::mt19937 &rng) { // Vector6 delta; // delta << randomOmega(rng), randomOmega(rng); // return SO4::Expmap(delta); diff --git a/gtsam/geometry/SO4.h b/gtsam/geometry/SO4.h index 5014414c2..33bd8c161 100644 --- a/gtsam/geometry/SO4.h +++ b/gtsam/geometry/SO4.h @@ -34,7 +34,7 @@ namespace gtsam { using SO4 = SO<4>; // /// Random SO(4) element (no big claims about uniformity) -// static SO4 Random(boost::mt19937 &rng); +// static SO4 Random(std::mt19937 &rng); // Below are all declarations of SO<4> specializations. // They are *defined* in SO4.cpp. diff --git a/timing/timeFactorOverhead.cpp b/timing/timeFactorOverhead.cpp index d9c19703c..717a2f434 100644 --- a/timing/timeFactorOverhead.cpp +++ b/timing/timeFactorOverhead.cpp @@ -22,13 +22,14 @@ #include #include -#include +#include #include using namespace gtsam; using namespace std; -static boost::variate_generator > rg(boost::mt19937(), boost::uniform_real<>(0.0, 1.0)); +static std::mt19937 rng; +static std::uniform_real_distribution<> rg(0.0, 1.0); int main(int argc, char *argv[]) { @@ -64,10 +65,10 @@ int main(int argc, char *argv[]) { Matrix A(blockdim, vardim); for(size_t j=0; j(key, A, b, noise)); } } @@ -111,10 +112,10 @@ int main(int argc, char *argv[]) { // Generate a random Gaussian factor for(size_t j=0; j(key, Acomb, bcomb, noiseModel::Isotropic::Sigma(blockdim*nBlocks, 1.0))); diff --git a/timing/timeFrobeniusFactor.cpp b/timing/timeFrobeniusFactor.cpp index c8bdd8fec..30ebff7bc 100644 --- a/timing/timeFrobeniusFactor.cpp +++ b/timing/timeFrobeniusFactor.cpp @@ -31,6 +31,7 @@ #include #include +#include #include #include @@ -76,7 +77,7 @@ int main(int argc, char* argv[]) { keys[0], keys[1], SO3(Tij.rotation().matrix()), model); } - boost::mt19937 rng(42); + std::mt19937 rng(42); // Set parameters to be similar to ceres LevenbergMarquardtParams params; diff --git a/timing/timeMatrixOps.cpp b/timing/timeMatrixOps.cpp index d9f2ffaf6..8dcb2bbc9 100644 --- a/timing/timeMatrixOps.cpp +++ b/timing/timeMatrixOps.cpp @@ -16,7 +16,6 @@ * @date Sep 18, 2010 */ -#include #include #include @@ -24,6 +23,7 @@ #include #include +#include #include #include @@ -33,7 +33,8 @@ using namespace std; using boost::format; using namespace boost::lambda; -static boost::variate_generator > rng(boost::mt19937(), boost::uniform_real<>(-1.0, 0.0)); +static std::mt19937 rng; +static std::uniform_real_distribution<> rg(-1.0, 0.0); //typedef ublas::matrix matrix; //typedef ublas::matrix_range matrix_range; //typedef Eigen::Matrix matrix; @@ -53,8 +54,8 @@ int main(int argc, char* argv[]) { volatile size_t n=300; volatile size_t nReps = 1000; assert(m > n); - boost::variate_generator > rni(boost::mt19937(), boost::uniform_int(0,m-1)); - boost::variate_generator > rnj(boost::mt19937(), boost::uniform_int(0,n-1)); + std::uniform_int_distribution ri(0,m-1); + std::uniform_int_distribution rj(0,n-1); gtsam::Matrix mat((int)m,(int)n); gtsam::SubMatrix full = mat.block(0, 0, m, n); gtsam::SubMatrix top = mat.block(0, 0, n, n); @@ -75,13 +76,13 @@ int main(int argc, char* argv[]) { for(size_t rep=0; rep<1000; ++rep) for(size_t i=0; i<(size_t)mat.rows(); ++i) for(size_t j=0; j<(size_t)mat.cols(); ++j) - mat(i,j) = rng(); + mat(i,j) = rg(rng); gttic_(basicTime); for(size_t rep=0; repsecs(); @@ -92,7 +93,7 @@ int main(int argc, char* argv[]) { for(size_t rep=0; repsecs(); @@ -103,7 +104,7 @@ int main(int argc, char* argv[]) { for(size_t rep=0; repsecs(); @@ -114,7 +115,7 @@ int main(int argc, char* argv[]) { for(size_t rep=0; repsecs(); @@ -133,13 +134,13 @@ int main(int argc, char* argv[]) { for(size_t rep=0; rep<1000; ++rep) for(size_t j=0; j<(size_t)mat.cols(); ++j) for(size_t i=0; i<(size_t)mat.rows(); ++i) - mat(i,j) = rng(); + mat(i,j) = rg(rng); gttic_(basicTime); for(size_t rep=0; repsecs(); @@ -150,7 +151,7 @@ int main(int argc, char* argv[]) { for(size_t rep=0; repsecs(); @@ -161,7 +162,7 @@ int main(int argc, char* argv[]) { for(size_t rep=0; repsecs(); @@ -172,7 +173,7 @@ int main(int argc, char* argv[]) { for(size_t rep=0; repsecs(); @@ -190,14 +191,14 @@ int main(int argc, char* argv[]) { cout << "Row-major matrix, random assignment:" << endl; // Do a few initial assignments to let any cache effects stabilize - for_each(ijs.begin(), ijs.end(), _1 = make_pair(rni(),rnj())); + for_each(ijs.begin(), ijs.end(), _1 = make_pair(ri(rng),rj(rng))); for(size_t rep=0; rep<1000; ++rep) - for(const ij_t& ij: ijs) { mat(ij.first, ij.second) = rng(); } + for(const ij_t& ij: ijs) { mat(ij.first, ij.second) = rg(rng); } gttic_(basicTime); - for_each(ijs.begin(), ijs.end(), _1 = make_pair(rni(),rnj())); + for_each(ijs.begin(), ijs.end(), _1 = make_pair(ri(rng),rj(rng))); for(size_t rep=0; rep<1000; ++rep) - for(const ij_t& ij: ijs) { mat(ij.first, ij.second) = rng(); } + for(const ij_t& ij: ijs) { mat(ij.first, ij.second) = rg(rng); } gttoc_(basicTime); tictoc_getNode(basicTimeNode, basicTime); basicTime = basicTimeNode->secs(); @@ -205,9 +206,9 @@ int main(int argc, char* argv[]) { cout << format(" Basic: %1% mus/element") % double(1000000 * basicTime / double(ijs.size()*nReps)) << endl; gttic_(fullTime); - for_each(ijs.begin(), ijs.end(), _1 = make_pair(rni(),rnj())); + for_each(ijs.begin(), ijs.end(), _1 = make_pair(ri(rng),rj(rng))); for(size_t rep=0; rep<1000; ++rep) - for(const ij_t& ij: ijs) { full(ij.first, ij.second) = rng(); } + for(const ij_t& ij: ijs) { full(ij.first, ij.second) = rg(rng); } gttoc_(fullTime); tictoc_getNode(fullTimeNode, fullTime); fullTime = fullTimeNode->secs(); @@ -215,9 +216,9 @@ int main(int argc, char* argv[]) { cout << format(" Full: %1% mus/element") % double(1000000 * fullTime / double(ijs.size()*nReps)) << endl; gttic_(topTime); - for_each(ijs.begin(), ijs.end(), _1 = make_pair(rni()%top.rows(),rnj())); + for_each(ijs.begin(), ijs.end(), _1 = make_pair(ri(rng)%top.rows(),rj(rng))); for(size_t rep=0; rep<1000; ++rep) - for(const ij_t& ij: ijs) { top(ij.first, ij.second) = rng(); } + for(const ij_t& ij: ijs) { top(ij.first, ij.second) = rg(rng); } gttoc_(topTime); tictoc_getNode(topTimeNode, topTime); topTime = topTimeNode->secs(); @@ -225,9 +226,9 @@ int main(int argc, char* argv[]) { cout << format(" Top: %1% mus/element") % double(1000000 * topTime / double(ijs.size()*nReps)) << endl; gttic_(blockTime); - for_each(ijs.begin(), ijs.end(), _1 = make_pair(rni()%block.rows(),rnj()%block.cols())); + for_each(ijs.begin(), ijs.end(), _1 = make_pair(ri(rng)%block.rows(),rj(rng)%block.cols())); for(size_t rep=0; rep<1000; ++rep) - for(const ij_t& ij: ijs) { block(ij.first, ij.second) = rng(); } + for(const ij_t& ij: ijs) { block(ij.first, ij.second) = rg(rng); } gttoc_(blockTime); tictoc_getNode(blockTimeNode, blockTime); blockTime = blockTimeNode->secs(); @@ -250,7 +251,7 @@ int main(int argc, char* argv[]) { // matrix mat(5,5); // for(size_t j=0; j<(size_t)mat.cols(); ++j) // for(size_t i=0; i<(size_t)mat.rows(); ++i) -// mat(i,j) = rng(); +// mat(i,j) = rg(rng); // // tri = ublas::triangular_adaptor(mat); // cout << " Assigned from triangular adapter: " << tri << endl; @@ -259,13 +260,13 @@ int main(int argc, char* argv[]) { // // for(size_t j=0; j<(size_t)mat.cols(); ++j) // for(size_t i=0; i<(size_t)mat.rows(); ++i) -// mat(i,j) = rng(); +// mat(i,j) = rg(rng); // mat = tri; // cout << " Assign matrix from triangular: " << mat << endl; // // for(size_t j=0; j<(size_t)mat.cols(); ++j) // for(size_t i=0; i<(size_t)mat.rows(); ++i) -// mat(i,j) = rng(); +// mat(i,j) = rg(rng); // (ublas::triangular_adaptor(mat)) = tri; // cout << " Assign triangular adaptor from triangular: " << mat << endl; // } @@ -281,7 +282,7 @@ int main(int argc, char* argv[]) { // matrix mat(5,7); // for(size_t j=0; j<(size_t)mat.cols(); ++j) // for(size_t i=0; i<(size_t)mat.rows(); ++i) -// mat(i,j) = rng(); +// mat(i,j) = rg(rng); // // tri = ublas::triangular_adaptor(mat); // cout << " Assigned from triangular adapter: " << tri << endl; @@ -290,13 +291,13 @@ int main(int argc, char* argv[]) { // // for(size_t j=0; j<(size_t)mat.cols(); ++j) // for(size_t i=0; i<(size_t)mat.rows(); ++i) -// mat(i,j) = rng(); +// mat(i,j) = rg(rng); // mat = tri; // cout << " Assign matrix from triangular: " << mat << endl; // // for(size_t j=0; j<(size_t)mat.cols(); ++j) // for(size_t i=0; i<(size_t)mat.rows(); ++i) -// mat(i,j) = rng(); +// mat(i,j) = rg(rng); // mat = ublas::triangular_adaptor(mat); // cout << " Assign matrix from triangular adaptor of self: " << mat << endl; // } From 2e0f2962c4e8a2f81f831eec0af715e7edf8c42f Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Thu, 23 Jul 2020 13:20:57 -0500 Subject: [PATCH 242/869] add axis labels to the trajectory plot --- cython/gtsam/utils/plot.py | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/cython/gtsam/utils/plot.py b/cython/gtsam/utils/plot.py index b67444fc1..93d8ba47b 100644 --- a/cython/gtsam/utils/plot.py +++ b/cython/gtsam/utils/plot.py @@ -267,6 +267,10 @@ def plot_pose3(fignum, pose, axis_length=0.1, P=None): plot_pose3_on_axes(axes, pose, P=P, axis_length=axis_length) + axes.set_xlabel('X axis') + axes.set_ylabel('Y axis') + axes.set_zlabel('Z axis') + def plot_trajectory(fignum, values, scale=1, marginals=None): """ From d5d58fd707e0210ea3401f67f021c9a55848c551 Mon Sep 17 00:00:00 2001 From: acxz <17132214+acxz@users.noreply.github.com> Date: Thu, 23 Jul 2020 14:49:13 -0400 Subject: [PATCH 243/869] use reasonable distribution names --- timing/timeMatrixOps.cpp | 58 ++++++++++++++++++++-------------------- 1 file changed, 29 insertions(+), 29 deletions(-) diff --git a/timing/timeMatrixOps.cpp b/timing/timeMatrixOps.cpp index 8dcb2bbc9..95333fbf8 100644 --- a/timing/timeMatrixOps.cpp +++ b/timing/timeMatrixOps.cpp @@ -34,7 +34,7 @@ using boost::format; using namespace boost::lambda; static std::mt19937 rng; -static std::uniform_real_distribution<> rg(-1.0, 0.0); +static std::uniform_real_distribution<> uniform(-1.0, 0.0); //typedef ublas::matrix matrix; //typedef ublas::matrix_range matrix_range; //typedef Eigen::Matrix matrix; @@ -54,8 +54,8 @@ int main(int argc, char* argv[]) { volatile size_t n=300; volatile size_t nReps = 1000; assert(m > n); - std::uniform_int_distribution ri(0,m-1); - std::uniform_int_distribution rj(0,n-1); + std::uniform_int_distribution uniform_i(0,m-1); + std::uniform_int_distribution uniform_j(0,n-1); gtsam::Matrix mat((int)m,(int)n); gtsam::SubMatrix full = mat.block(0, 0, m, n); gtsam::SubMatrix top = mat.block(0, 0, n, n); @@ -76,13 +76,13 @@ int main(int argc, char* argv[]) { for(size_t rep=0; rep<1000; ++rep) for(size_t i=0; i<(size_t)mat.rows(); ++i) for(size_t j=0; j<(size_t)mat.cols(); ++j) - mat(i,j) = rg(rng); + mat(i,j) = uniform(rng); gttic_(basicTime); for(size_t rep=0; repsecs(); @@ -93,7 +93,7 @@ int main(int argc, char* argv[]) { for(size_t rep=0; repsecs(); @@ -104,7 +104,7 @@ int main(int argc, char* argv[]) { for(size_t rep=0; repsecs(); @@ -115,7 +115,7 @@ int main(int argc, char* argv[]) { for(size_t rep=0; repsecs(); @@ -134,13 +134,13 @@ int main(int argc, char* argv[]) { for(size_t rep=0; rep<1000; ++rep) for(size_t j=0; j<(size_t)mat.cols(); ++j) for(size_t i=0; i<(size_t)mat.rows(); ++i) - mat(i,j) = rg(rng); + mat(i,j) = uniform(rng); gttic_(basicTime); for(size_t rep=0; repsecs(); @@ -151,7 +151,7 @@ int main(int argc, char* argv[]) { for(size_t rep=0; repsecs(); @@ -162,7 +162,7 @@ int main(int argc, char* argv[]) { for(size_t rep=0; repsecs(); @@ -173,7 +173,7 @@ int main(int argc, char* argv[]) { for(size_t rep=0; repsecs(); @@ -191,14 +191,14 @@ int main(int argc, char* argv[]) { cout << "Row-major matrix, random assignment:" << endl; // Do a few initial assignments to let any cache effects stabilize - for_each(ijs.begin(), ijs.end(), _1 = make_pair(ri(rng),rj(rng))); + for_each(ijs.begin(), ijs.end(), _1 = make_pair(uniform_i(rng),uniform_j(rng))); for(size_t rep=0; rep<1000; ++rep) - for(const ij_t& ij: ijs) { mat(ij.first, ij.second) = rg(rng); } + for(const ij_t& ij: ijs) { mat(ij.first, ij.second) = uniform(rng); } gttic_(basicTime); - for_each(ijs.begin(), ijs.end(), _1 = make_pair(ri(rng),rj(rng))); + for_each(ijs.begin(), ijs.end(), _1 = make_pair(uniform_i(rng),uniform_j(rng))); for(size_t rep=0; rep<1000; ++rep) - for(const ij_t& ij: ijs) { mat(ij.first, ij.second) = rg(rng); } + for(const ij_t& ij: ijs) { mat(ij.first, ij.second) = uniform(rng); } gttoc_(basicTime); tictoc_getNode(basicTimeNode, basicTime); basicTime = basicTimeNode->secs(); @@ -206,9 +206,9 @@ int main(int argc, char* argv[]) { cout << format(" Basic: %1% mus/element") % double(1000000 * basicTime / double(ijs.size()*nReps)) << endl; gttic_(fullTime); - for_each(ijs.begin(), ijs.end(), _1 = make_pair(ri(rng),rj(rng))); + for_each(ijs.begin(), ijs.end(), _1 = make_pair(uniform_i(rng),uniform_j(rng))); for(size_t rep=0; rep<1000; ++rep) - for(const ij_t& ij: ijs) { full(ij.first, ij.second) = rg(rng); } + for(const ij_t& ij: ijs) { full(ij.first, ij.second) = uniform(rng); } gttoc_(fullTime); tictoc_getNode(fullTimeNode, fullTime); fullTime = fullTimeNode->secs(); @@ -216,9 +216,9 @@ int main(int argc, char* argv[]) { cout << format(" Full: %1% mus/element") % double(1000000 * fullTime / double(ijs.size()*nReps)) << endl; gttic_(topTime); - for_each(ijs.begin(), ijs.end(), _1 = make_pair(ri(rng)%top.rows(),rj(rng))); + for_each(ijs.begin(), ijs.end(), _1 = make_pair(uniform_i(rng)%top.rows(),uniform_j(rng))); for(size_t rep=0; rep<1000; ++rep) - for(const ij_t& ij: ijs) { top(ij.first, ij.second) = rg(rng); } + for(const ij_t& ij: ijs) { top(ij.first, ij.second) = uniform(rng); } gttoc_(topTime); tictoc_getNode(topTimeNode, topTime); topTime = topTimeNode->secs(); @@ -226,9 +226,9 @@ int main(int argc, char* argv[]) { cout << format(" Top: %1% mus/element") % double(1000000 * topTime / double(ijs.size()*nReps)) << endl; gttic_(blockTime); - for_each(ijs.begin(), ijs.end(), _1 = make_pair(ri(rng)%block.rows(),rj(rng)%block.cols())); + for_each(ijs.begin(), ijs.end(), _1 = make_pair(uniform_i(rng)%block.rows(),uniform_j(rng)%block.cols())); for(size_t rep=0; rep<1000; ++rep) - for(const ij_t& ij: ijs) { block(ij.first, ij.second) = rg(rng); } + for(const ij_t& ij: ijs) { block(ij.first, ij.second) = uniform(rng); } gttoc_(blockTime); tictoc_getNode(blockTimeNode, blockTime); blockTime = blockTimeNode->secs(); @@ -251,7 +251,7 @@ int main(int argc, char* argv[]) { // matrix mat(5,5); // for(size_t j=0; j<(size_t)mat.cols(); ++j) // for(size_t i=0; i<(size_t)mat.rows(); ++i) -// mat(i,j) = rg(rng); +// mat(i,j) = uniform(rng); // // tri = ublas::triangular_adaptor(mat); // cout << " Assigned from triangular adapter: " << tri << endl; @@ -260,13 +260,13 @@ int main(int argc, char* argv[]) { // // for(size_t j=0; j<(size_t)mat.cols(); ++j) // for(size_t i=0; i<(size_t)mat.rows(); ++i) -// mat(i,j) = rg(rng); +// mat(i,j) = uniform(rng); // mat = tri; // cout << " Assign matrix from triangular: " << mat << endl; // // for(size_t j=0; j<(size_t)mat.cols(); ++j) // for(size_t i=0; i<(size_t)mat.rows(); ++i) -// mat(i,j) = rg(rng); +// mat(i,j) = uniform(rng); // (ublas::triangular_adaptor(mat)) = tri; // cout << " Assign triangular adaptor from triangular: " << mat << endl; // } @@ -282,7 +282,7 @@ int main(int argc, char* argv[]) { // matrix mat(5,7); // for(size_t j=0; j<(size_t)mat.cols(); ++j) // for(size_t i=0; i<(size_t)mat.rows(); ++i) -// mat(i,j) = rg(rng); +// mat(i,j) = uniform(rng); // // tri = ublas::triangular_adaptor(mat); // cout << " Assigned from triangular adapter: " << tri << endl; @@ -291,13 +291,13 @@ int main(int argc, char* argv[]) { // // for(size_t j=0; j<(size_t)mat.cols(); ++j) // for(size_t i=0; i<(size_t)mat.rows(); ++i) -// mat(i,j) = rg(rng); +// mat(i,j) = uniform(rng); // mat = tri; // cout << " Assign matrix from triangular: " << mat << endl; // // for(size_t j=0; j<(size_t)mat.cols(); ++j) // for(size_t i=0; i<(size_t)mat.rows(); ++i) -// mat(i,j) = rg(rng); +// mat(i,j) = uniform(rng); // mat = ublas::triangular_adaptor(mat); // cout << " Assign matrix from triangular adaptor of self: " << mat << endl; // } From 5eb2bea3572790fe73f6771e0121e148ebf0f66f Mon Sep 17 00:00:00 2001 From: acxz <17132214+acxz@users.noreply.github.com> Date: Thu, 23 Jul 2020 14:54:21 -0400 Subject: [PATCH 244/869] use reasonable distribution name --- timing/timeFactorOverhead.cpp | 10 +++++----- 1 file changed, 5 insertions(+), 5 deletions(-) diff --git a/timing/timeFactorOverhead.cpp b/timing/timeFactorOverhead.cpp index 717a2f434..038901388 100644 --- a/timing/timeFactorOverhead.cpp +++ b/timing/timeFactorOverhead.cpp @@ -29,7 +29,7 @@ using namespace gtsam; using namespace std; static std::mt19937 rng; -static std::uniform_real_distribution<> rg(0.0, 1.0); +static std::uniform_real_distribution<> uniform(0.0, 1.0); int main(int argc, char *argv[]) { @@ -65,10 +65,10 @@ int main(int argc, char *argv[]) { Matrix A(blockdim, vardim); for(size_t j=0; j(key, A, b, noise)); } } @@ -112,10 +112,10 @@ int main(int argc, char *argv[]) { // Generate a random Gaussian factor for(size_t j=0; j(key, Acomb, bcomb, noiseModel::Isotropic::Sigma(blockdim*nBlocks, 1.0))); From c738f6b7f727b79b63596677bee5a0ffb578b00c Mon Sep 17 00:00:00 2001 From: acxz <17132214+acxz@users.noreply.github.com> Date: Thu, 23 Jul 2020 15:47:14 -0400 Subject: [PATCH 245/869] remove unused base variable --- gtsam/nonlinear/FunctorizedFactor.h | 1 - 1 file changed, 1 deletion(-) diff --git a/gtsam/nonlinear/FunctorizedFactor.h b/gtsam/nonlinear/FunctorizedFactor.h index a83198967..5351b126f 100644 --- a/gtsam/nonlinear/FunctorizedFactor.h +++ b/gtsam/nonlinear/FunctorizedFactor.h @@ -109,7 +109,6 @@ class GTSAM_EXPORT FunctorizedFactor : public NoiseModelFactor1 { virtual bool equals(const NonlinearFactor &other, double tol = 1e-9) const { const FunctorizedFactor *e = dynamic_cast *>(&other); - const bool base = Base::equals(*e, tol); return e && Base::equals(other, tol) && traits::Equals(this->measured_, e->measured_, tol); } From aaf632f583090cbacc9f6683538d68ab0cd79152 Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Fri, 24 Jul 2020 02:30:35 -0500 Subject: [PATCH 246/869] fix test for FunctorizedFactor printing --- gtsam/nonlinear/tests/testFunctorizedFactor.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/gtsam/nonlinear/tests/testFunctorizedFactor.cpp b/gtsam/nonlinear/tests/testFunctorizedFactor.cpp index 12dd6b91c..48ab73ad0 100644 --- a/gtsam/nonlinear/tests/testFunctorizedFactor.cpp +++ b/gtsam/nonlinear/tests/testFunctorizedFactor.cpp @@ -131,7 +131,7 @@ TEST(FunctorizedFactor, Print) { "FunctorizedFactor(X0)\n" " measurement: [\n" " 1, 0;\n" - " 0, 1\n" + " 0, 1\n" "]\n" " noise model sigmas: 1 1 1 1 1 1 1 1 1\n"; From 05f50eae40842abed479164d39903be905396692 Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Fri, 24 Jul 2020 03:10:03 -0500 Subject: [PATCH 247/869] Fix minor bugs --- gtsam/slam/dataset.h | 4 ++-- tests/testNonlinearISAM.cpp | 2 +- 2 files changed, 3 insertions(+), 3 deletions(-) diff --git a/gtsam/slam/dataset.h b/gtsam/slam/dataset.h index a18ae12f6..439a69fdc 100644 --- a/gtsam/slam/dataset.h +++ b/gtsam/slam/dataset.h @@ -94,7 +94,7 @@ GTSAM_EXPORT boost::optional parseVertexPose(std::istream& is, */ GTSAM_EXPORT boost::optional parseVertexLandmark(std::istream& is, - const std::string& tag) + const std::string& tag); /** * Parse TORO/G2O edge "id1 id2 x y yaw" @@ -176,7 +176,7 @@ GTSAM_EXPORT BetweenFactorPose3s parse3DFactors(const std::string& filename, GTSAM_EXPORT std::map parse3DPoses(const std::string& filename); /// Parse landmarks in 3D g2o graph file into a map of Point3s. -GTSAM_EXPORT std::map parse3DLandmarks(const string& filename) +GTSAM_EXPORT std::map parse3DLandmarks(const string& filename); /// Load TORO 3D Graph GTSAM_EXPORT GraphAndValues load3D(const std::string& filename); diff --git a/tests/testNonlinearISAM.cpp b/tests/testNonlinearISAM.cpp index 88ae508b6..974806612 100644 --- a/tests/testNonlinearISAM.cpp +++ b/tests/testNonlinearISAM.cpp @@ -288,7 +288,7 @@ TEST(testNonlinearISAM, loop_closures ) { break; // Check if vertex - const auto indexedPose = parseVertex(is, tag); + const auto indexedPose = parseVertexPose(is, tag); if (indexedPose) { Key id = indexedPose->first; initialEstimate.insert(Symbol('x', id), indexedPose->second); From 8a210188f3923fa8007168d0ba941fe450fdef9e Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Fri, 24 Jul 2020 03:10:14 -0500 Subject: [PATCH 248/869] test for readG2o --- examples/Data/example_with_vertices.g2o | 16 ++++++++++++++++ gtsam/slam/tests/testDataset.cpp | 11 +++++++++++ 2 files changed, 27 insertions(+) create mode 100644 examples/Data/example_with_vertices.g2o diff --git a/examples/Data/example_with_vertices.g2o b/examples/Data/example_with_vertices.g2o new file mode 100644 index 000000000..6c2f1a530 --- /dev/null +++ b/examples/Data/example_with_vertices.g2o @@ -0,0 +1,16 @@ +VERTEX_SE3:QUAT 8646911284551352320 40 -1.15443e-13 10 0.557345 0.557345 -0.435162 -0.435162 +VERTEX_SE3:QUAT 8646911284551352321 28.2843 28.2843 10 0.301633 0.728207 -0.568567 -0.235508 +VERTEX_SE3:QUAT 8646911284551352322 -1.6986e-08 40 10 -3.89609e-10 0.788205 -0.615412 -2.07622e-10 +VERTEX_SE3:QUAT 8646911284551352323 -28.2843 28.2843 10 -0.301633 0.728207 -0.568567 0.235508 +VERTEX_SE3:QUAT 8646911284551352324 -40 -2.32554e-10 10 -0.557345 0.557345 -0.435162 0.435162 +VERTEX_SE3:QUAT 8646911284551352325 -28.2843 -28.2843 10 -0.728207 0.301633 -0.235508 0.568567 +VERTEX_SE3:QUAT 8646911284551352326 -2.53531e-09 -40 10 -0.788205 -1.25891e-11 -3.82742e-13 0.615412 +VERTEX_SE3:QUAT 8646911284551352327 28.2843 -28.2843 10 -0.728207 -0.301633 0.235508 0.568567 +VERTEX_TRACKXYZ 7782220156096217088 10 10 10 +VERTEX_TRACKXYZ 7782220156096217089 -10 10 10 +VERTEX_TRACKXYZ 7782220156096217090 -10 -10 10 +VERTEX_TRACKXYZ 7782220156096217091 10 -10 10 +VERTEX_TRACKXYZ 7782220156096217092 10 10 -10 +VERTEX_TRACKXYZ 7782220156096217093 -10 10 -10 +VERTEX_TRACKXYZ 7782220156096217094 -10 -10 -10 +VERTEX_TRACKXYZ 7782220156096217095 10 -10 -10 diff --git a/gtsam/slam/tests/testDataset.cpp b/gtsam/slam/tests/testDataset.cpp index 136b7a93c..b6b1776d2 100644 --- a/gtsam/slam/tests/testDataset.cpp +++ b/gtsam/slam/tests/testDataset.cpp @@ -277,6 +277,17 @@ TEST(dataSet, readG2oCheckDeterminants) { EXPECT_LONGS_EQUAL(0, landmarks.size()); } +/* ************************************************************************* */ +TEST(dataSet, readG2oLandmarks) { + const string g2oFile = findExampleDataFile("example_with_vertices.g2o"); + + // Check number of poses and landmarks. Should be 8 each. + const map poses = parse3DPoses(g2oFile); + EXPECT_LONGS_EQUAL(8, poses.size()); + const map landmarks = parse3DLandmarks(g2oFile); + EXPECT_LONGS_EQUAL(8, landmarks.size()); +} + /* ************************************************************************* */ static NonlinearFactorGraph expectedGraph(const SharedNoiseModel& model) { NonlinearFactorGraph g; From 6660e2a532a76656e75507cdb10e46a12b8c4161 Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Fri, 24 Jul 2020 09:43:37 -0500 Subject: [PATCH 249/869] added axis labels and figure titles as optional params --- cython/gtsam/utils/plot.py | 68 ++++++++++++++++++++++++++++++-------- 1 file changed, 54 insertions(+), 14 deletions(-) diff --git a/cython/gtsam/utils/plot.py b/cython/gtsam/utils/plot.py index 93d8ba47b..1e976a69e 100644 --- a/cython/gtsam/utils/plot.py +++ b/cython/gtsam/utils/plot.py @@ -135,7 +135,8 @@ def plot_pose2_on_axes(axes, pose, axis_length=0.1, covariance=None): axes.add_patch(e1) -def plot_pose2(fignum, pose, axis_length=0.1, covariance=None): +def plot_pose2(fignum, pose, axis_length=0.1, covariance=None, + axis_labels=('X axis', 'Y axis', 'Z axis')): """ Plot a 2D pose on given figure with given `axis_length`. @@ -144,6 +145,7 @@ def plot_pose2(fignum, pose, axis_length=0.1, covariance=None): pose (gtsam.Pose2): The pose to be plotted. axis_length (float): The length of the camera axes. covariance (numpy.ndarray): Marginal covariance matrix to plot the uncertainty of the estimation. + axis_labels (iterable[string]): List of axis labels to set. """ # get figure object fig = plt.figure(fignum) @@ -151,6 +153,12 @@ def plot_pose2(fignum, pose, axis_length=0.1, covariance=None): plot_pose2_on_axes(axes, pose, axis_length=axis_length, covariance=covariance) + axes.set_xlabel(axis_labels[0]) + axes.set_ylabel(axis_labels[1]) + axes.set_zlabel(axis_labels[2]) + + return fig + def plot_point3_on_axes(axes, point, linespec, P=None): """ @@ -167,7 +175,8 @@ def plot_point3_on_axes(axes, point, linespec, P=None): plot_covariance_ellipse_3d(axes, point.vector(), P) -def plot_point3(fignum, point, linespec, P=None): +def plot_point3(fignum, point, linespec, P=None, + axis_labels=('X axis', 'Y axis', 'Z axis')): """ Plot a 3D point on given figure with given `linespec`. @@ -176,13 +185,25 @@ def plot_point3(fignum, point, linespec, P=None): point (gtsam.Point3): The point to be plotted. linespec (string): String representing formatting options for Matplotlib. P (numpy.ndarray): Marginal covariance matrix to plot the uncertainty of the estimation. + axis_labels (iterable[string]): List of axis labels to set. + + Returns: + fig: The matplotlib figure. + """ fig = plt.figure(fignum) axes = fig.gca(projection='3d') plot_point3_on_axes(axes, point, linespec, P) + axes.set_xlabel(axis_labels[0]) + axes.set_ylabel(axis_labels[1]) + axes.set_zlabel(axis_labels[2]) -def plot_3d_points(fignum, values, linespec="g*", marginals=None): + return fig + + +def plot_3d_points(fignum, values, linespec="g*", marginals=None, + title="3D Points", axis_labels=('X axis', 'Y axis', 'Z axis')): """ Plots the Point3s in `values`, with optional covariances. Finds all the Point3 objects in the given Values object and plots them. @@ -193,7 +214,9 @@ def plot_3d_points(fignum, values, linespec="g*", marginals=None): fignum (int): Integer representing the figure number to use for plotting. values (gtsam.Values): Values dictionary consisting of points to be plotted. linespec (string): String representing formatting options for Matplotlib. - covariance (numpy.ndarray): Marginal covariance matrix to plot the uncertainty of the estimation. + marginals (numpy.ndarray): Marginal covariance matrix to plot the uncertainty of the estimation. + title (string): The title of the plot. + axis_labels (iterable[string]): List of axis labels to set. """ keys = values.keys() @@ -208,12 +231,16 @@ def plot_3d_points(fignum, values, linespec="g*", marginals=None): else: covariance = None - plot_point3(fignum, point, linespec, covariance) + fig = plot_point3(fignum, point, linespec, covariance, + axis_labels=axis_labels) except RuntimeError: continue # I guess it's not a Point3 + fig.suptitle(title) + fig.canvas.set_window_title(title.lower()) + def plot_pose3_on_axes(axes, pose, axis_length=0.1, P=None, scale=1): """ @@ -251,7 +278,8 @@ def plot_pose3_on_axes(axes, pose, axis_length=0.1, P=None, scale=1): plot_covariance_ellipse_3d(axes, origin, gPp) -def plot_pose3(fignum, pose, axis_length=0.1, P=None): +def plot_pose3(fignum, pose, axis_length=0.1, P=None, + axis_labels=('X axis', 'Y axis', 'Z axis')): """ Plot a 3D pose on given figure with given `axis_length`. @@ -260,6 +288,10 @@ def plot_pose3(fignum, pose, axis_length=0.1, P=None): pose (gtsam.Pose3): 3D pose to be plotted. linespec (string): String representing formatting options for Matplotlib. P (numpy.ndarray): Marginal covariance matrix to plot the uncertainty of the estimation. + axis_labels (iterable[string]): List of axis labels to set. + + Returns: + fig: The matplotlib figure. """ # get figure object fig = plt.figure(fignum) @@ -267,12 +299,15 @@ def plot_pose3(fignum, pose, axis_length=0.1, P=None): plot_pose3_on_axes(axes, pose, P=P, axis_length=axis_length) - axes.set_xlabel('X axis') - axes.set_ylabel('Y axis') - axes.set_zlabel('Z axis') + axes.set_xlabel(axis_labels[0]) + axes.set_ylabel(axis_labels[1]) + axes.set_zlabel(axis_labels[2]) + + return fig -def plot_trajectory(fignum, values, scale=1, marginals=None): +def plot_trajectory(fignum, values, scale=1, marginals=None, + title="Plot Trajectory", axis_labels=('X axis', 'Y axis', 'Z axis')): """ Plot a complete 3D trajectory using poses in `values`. @@ -282,6 +317,8 @@ def plot_trajectory(fignum, values, scale=1, marginals=None): scale (float): Value to scale the poses by. marginals (gtsam.Marginals): Marginalized probability values of the estimation. Used to plot uncertainty bounds. + title (string): The title of the plot. + axis_labels (iterable[string]): List of axis labels to set. """ pose3Values = gtsam.utilities_allPose3s(values) keys = gtsam.KeyVector(pose3Values.keys()) @@ -307,8 +344,8 @@ def plot_trajectory(fignum, values, scale=1, marginals=None): else: covariance = None - plot_pose3(fignum, lastPose, P=covariance, - axis_length=scale) + fig = plot_pose3(fignum, lastPose, P=covariance, + axis_length=scale, axis_labels=axis_labels) lastIndex = i @@ -322,8 +359,11 @@ def plot_trajectory(fignum, values, scale=1, marginals=None): else: covariance = None - plot_pose3(fignum, lastPose, P=covariance, - axis_length=scale) + fig = plot_pose3(fignum, lastPose, P=covariance, + axis_length=scale, axis_labels=axis_labels) except: pass + + fig.suptitle(title) + fig.canvas.set_window_title(title.lower()) From a7afd9da70d04d3de7dbd11a473b8a55a365a727 Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Fri, 24 Jul 2020 11:24:46 -0500 Subject: [PATCH 250/869] increase number of build cores and remove sudo requirement --- .travis.yml | 3 +-- 1 file changed, 1 insertion(+), 2 deletions(-) diff --git a/.travis.yml b/.travis.yml index d8094ef4d..0c8c4bee5 100644 --- a/.travis.yml +++ b/.travis.yml @@ -1,6 +1,5 @@ language: cpp cache: ccache -sudo: required dist: xenial addons: @@ -33,7 +32,7 @@ stages: env: global: - - MAKEFLAGS="-j2" + - MAKEFLAGS="-j3" - CCACHE_SLOPPINESS=pch_defines,time_macros # Compile stage without building examples/tests to populate the caches. From d2063d928e855a326af6e806398b8b2afd97fd6e Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Fri, 24 Jul 2020 11:37:58 -0500 Subject: [PATCH 251/869] added backwards compatibility for parseVertex --- gtsam/slam/dataset.cpp | 7 +++++++ gtsam/slam/dataset.h | 10 ++++++++++ 2 files changed, 17 insertions(+) diff --git a/gtsam/slam/dataset.cpp b/gtsam/slam/dataset.cpp index cb15f84a8..4a95b4297 100644 --- a/gtsam/slam/dataset.cpp +++ b/gtsam/slam/dataset.cpp @@ -195,6 +195,13 @@ static SharedNoiseModel readNoiseModel(ifstream& is, bool smart, } } +#ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V41 +/* ************************************************************************* */ +boost::optional parseVertex(istream& is, const string& tag) { + return parseVertexPose(is, tag); +} +#endif + /* ************************************************************************* */ boost::optional parseVertexPose(istream& is, const string& tag) { if ((tag == "VERTEX2") || (tag == "VERTEX_SE2") || (tag == "VERTEX")) { diff --git a/gtsam/slam/dataset.h b/gtsam/slam/dataset.h index 439a69fdc..7029a7a9c 100644 --- a/gtsam/slam/dataset.h +++ b/gtsam/slam/dataset.h @@ -79,6 +79,16 @@ typedef std::pair IndexedPose; typedef std::pair IndexedLandmark; typedef std::pair, Pose2> IndexedEdge; +#ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V41 +/** + * Parse TORO/G2O vertex "id x y yaw" + * @param is input stream + * @param tag string parsed from input stream, will only parse if vertex type + */ +GTSAM_EXPORT boost::optional parseVertex(std::istream& is, + const std::string& tag); +#endif + /** * Parse TORO/G2O vertex "id x y yaw" * @param is input stream From bf07e7a4d476da8e31268e0fb466a2a57e022122 Mon Sep 17 00:00:00 2001 From: Frank dellaert Date: Fri, 24 Jul 2020 15:38:44 -0400 Subject: [PATCH 252/869] Improved comment --- CMakeLists.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index 69ff9e3a0..61730d45a 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -590,7 +590,7 @@ print_config_flag(${GTSAM_USE_QUATERNIONS} "Quaternions as default R print_config_flag(${GTSAM_ENABLE_CONSISTENCY_CHECKS} "Runtime consistency checking ") print_config_flag(${GTSAM_ROT3_EXPMAP} "Rot3 retract is full ExpMap ") print_config_flag(${GTSAM_POSE3_EXPMAP} "Pose3 retract is full ExpMap ") -print_config_flag(${GTSAM_ALLOW_DEPRECATED_SINCE_V41} "Deprecated in GTSAM 4.1 allowed ") +print_config_flag(${GTSAM_ALLOW_DEPRECATED_SINCE_V41} "Allow features deprecated in GTSAM 4.1") print_config_flag(${GTSAM_TYPEDEF_POINTS_TO_VECTORS} "Point3 is typedef to Vector3 ") print_config_flag(${GTSAM_SUPPORT_NESTED_DISSECTION} "Metis-based Nested Dissection ") print_config_flag(${GTSAM_TANGENT_PREINTEGRATION} "Use tangent-space preintegration") From 272a5115bdf82478e77c7901f4578ca0c5717709 Mon Sep 17 00:00:00 2001 From: Frank dellaert Date: Fri, 24 Jul 2020 15:39:02 -0400 Subject: [PATCH 253/869] Made params const --- gtsam/navigation/CombinedImuFactor.h | 4 ++-- gtsam/navigation/PreintegrationBase.cpp | 2 +- gtsam/navigation/PreintegrationBase.h | 8 ++++---- gtsam/navigation/TangentPreintegration.cpp | 2 +- gtsam/navigation/TangentPreintegration.h | 2 +- 5 files changed, 9 insertions(+), 9 deletions(-) diff --git a/gtsam/navigation/CombinedImuFactor.h b/gtsam/navigation/CombinedImuFactor.h index e1a38bc91..42180ca04 100644 --- a/gtsam/navigation/CombinedImuFactor.h +++ b/gtsam/navigation/CombinedImuFactor.h @@ -156,7 +156,7 @@ public: * @param biasHat Current estimate of acceleration and rotation rate biases */ PreintegratedCombinedMeasurements( - const boost::shared_ptr& p, + const boost::shared_ptr& p, const imuBias::ConstantBias& biasHat = imuBias::ConstantBias()) : PreintegrationType(p, biasHat) { preintMeasCov_.setZero(); @@ -184,7 +184,7 @@ public: void resetIntegration() override; /// const reference to params, shadows definition in base class - Params& p() const { return *boost::static_pointer_cast(this->p_); } + const Params& p() const { return *boost::static_pointer_cast(this->p_); } /// @} /// @name Access instance variables diff --git a/gtsam/navigation/PreintegrationBase.cpp b/gtsam/navigation/PreintegrationBase.cpp index 45560f34d..1c8fdd760 100644 --- a/gtsam/navigation/PreintegrationBase.cpp +++ b/gtsam/navigation/PreintegrationBase.cpp @@ -28,7 +28,7 @@ using namespace std; namespace gtsam { //------------------------------------------------------------------------------ -PreintegrationBase::PreintegrationBase(const boost::shared_ptr& p, +PreintegrationBase::PreintegrationBase(const boost::shared_ptr& p, const Bias& biasHat) : p_(p), biasHat_(biasHat), deltaTij_(0.0) { } diff --git a/gtsam/navigation/PreintegrationBase.h b/gtsam/navigation/PreintegrationBase.h index 3ef7ad5df..e4edbe562 100644 --- a/gtsam/navigation/PreintegrationBase.h +++ b/gtsam/navigation/PreintegrationBase.h @@ -44,7 +44,7 @@ class GTSAM_EXPORT PreintegrationBase { typedef PreintegrationParams Params; protected: - boost::shared_ptr p_; + boost::shared_ptr p_; /// Acceleration and gyro bias used for preintegration Bias biasHat_; @@ -67,7 +67,7 @@ class GTSAM_EXPORT PreintegrationBase { * @param p Parameters, typically fixed in a single application * @param bias Current estimate of acceleration and rotation rate biases */ - PreintegrationBase(const boost::shared_ptr& p, + PreintegrationBase(const boost::shared_ptr& p, const imuBias::ConstantBias& biasHat = imuBias::ConstantBias()); /// @} @@ -88,13 +88,13 @@ class GTSAM_EXPORT PreintegrationBase { } /// shared pointer to params - const boost::shared_ptr& params() const { + const boost::shared_ptr& params() const { return p_; } /// const reference to params const Params& p() const { - return *boost::static_pointer_cast(p_); + return *p_; } /// @} diff --git a/gtsam/navigation/TangentPreintegration.cpp b/gtsam/navigation/TangentPreintegration.cpp index 56d7aa6d3..0d39242b7 100644 --- a/gtsam/navigation/TangentPreintegration.cpp +++ b/gtsam/navigation/TangentPreintegration.cpp @@ -24,7 +24,7 @@ using namespace std; namespace gtsam { //------------------------------------------------------------------------------ -TangentPreintegration::TangentPreintegration(const boost::shared_ptr& p, +TangentPreintegration::TangentPreintegration(const boost::shared_ptr& p, const Bias& biasHat) : PreintegrationBase(p, biasHat) { resetIntegration(); diff --git a/gtsam/navigation/TangentPreintegration.h b/gtsam/navigation/TangentPreintegration.h index 1b51b4e1e..183c7262e 100644 --- a/gtsam/navigation/TangentPreintegration.h +++ b/gtsam/navigation/TangentPreintegration.h @@ -50,7 +50,7 @@ public: * @param p Parameters, typically fixed in a single application * @param bias Current estimate of acceleration and rotation rate biases */ - TangentPreintegration(const boost::shared_ptr& p, + TangentPreintegration(const boost::shared_ptr& p, const imuBias::ConstantBias& biasHat = imuBias::ConstantBias()); /// Virtual destructor From 15f581ce29157538f17ef9baf11e12d758e5ea6d Mon Sep 17 00:00:00 2001 From: acxz <17132214+acxz@users.noreply.github.com> Date: Fri, 24 Jul 2020 16:40:18 -0400 Subject: [PATCH 254/869] pass in expected Rot3 and parameter p --- timing/timeFrobeniusFactor.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/timing/timeFrobeniusFactor.cpp b/timing/timeFrobeniusFactor.cpp index 30ebff7bc..8bd754de6 100644 --- a/timing/timeFrobeniusFactor.cpp +++ b/timing/timeFrobeniusFactor.cpp @@ -74,7 +74,7 @@ int main(int argc, char* argv[]) { const auto& Tij = factor->measured(); const auto& model = factor->noiseModel(); graph.emplace_shared( - keys[0], keys[1], SO3(Tij.rotation().matrix()), model); + keys[0], keys[1], Rot3(Tij.rotation().matrix()), 4, model); } std::mt19937 rng(42); From a4b95d273f7af08387afea7d8dcd6f89cf9014cd Mon Sep 17 00:00:00 2001 From: Jose Luis Blanco Claraco Date: Sat, 25 Jul 2020 18:07:25 +0200 Subject: [PATCH 255/869] recover SLAM serialization test --- gtsam/linear/GaussianISAM.h | 5 +++ gtsam/nonlinear/PriorFactor.h | 5 +++ tests/testSerializationSLAM.cpp | 71 +-------------------------------- 3 files changed, 11 insertions(+), 70 deletions(-) diff --git a/gtsam/linear/GaussianISAM.h b/gtsam/linear/GaussianISAM.h index 55208d4d1..b77b26240 100644 --- a/gtsam/linear/GaussianISAM.h +++ b/gtsam/linear/GaussianISAM.h @@ -20,6 +20,7 @@ #include #include +#include namespace gtsam { @@ -43,4 +44,8 @@ namespace gtsam { }; + /// traits + template <> + struct traits : public Testable {}; + } diff --git a/gtsam/nonlinear/PriorFactor.h b/gtsam/nonlinear/PriorFactor.h index 0afbaa588..3198dab07 100644 --- a/gtsam/nonlinear/PriorFactor.h +++ b/gtsam/nonlinear/PriorFactor.h @@ -117,4 +117,9 @@ namespace gtsam { GTSAM_MAKE_ALIGNED_OPERATOR_NEW_IF(NeedsToAlign) }; + /// traits + template + struct traits > : public Testable > {}; + + } /// namespace gtsam diff --git a/tests/testSerializationSLAM.cpp b/tests/testSerializationSLAM.cpp index e3252a90b..84e521156 100644 --- a/tests/testSerializationSLAM.cpp +++ b/tests/testSerializationSLAM.cpp @@ -18,15 +18,10 @@ #include -#if 0 - #include -//#include #include #include -//#include #include -//#include #include #include #include @@ -34,8 +29,6 @@ #include #include #include -#include -#include #include #include #include @@ -49,6 +42,7 @@ #include #include #include +#include #include @@ -57,8 +51,6 @@ using namespace gtsam; using namespace gtsam::serializationTestHelpers; // Creating as many permutations of factors as possible -typedef PriorFactor PriorFactorLieVector; -typedef PriorFactor PriorFactorLieMatrix; typedef PriorFactor PriorFactorPoint2; typedef PriorFactor PriorFactorStereoPoint2; typedef PriorFactor PriorFactorPoint3; @@ -69,12 +61,9 @@ typedef PriorFactor PriorFactorPose3; typedef PriorFactor PriorFactorCal3_S2; typedef PriorFactor PriorFactorCal3DS2; typedef PriorFactor PriorFactorCalibratedCamera; -typedef PriorFactor PriorFactorSimpleCamera; typedef PriorFactor PriorFactorPinholeCameraCal3_S2; typedef PriorFactor PriorFactorStereoCamera; -typedef BetweenFactor BetweenFactorLieVector; -typedef BetweenFactor BetweenFactorLieMatrix; typedef BetweenFactor BetweenFactorPoint2; typedef BetweenFactor BetweenFactorPoint3; typedef BetweenFactor BetweenFactorRot2; @@ -82,8 +71,6 @@ typedef BetweenFactor BetweenFactorRot3; typedef BetweenFactor BetweenFactorPose2; typedef BetweenFactor BetweenFactorPose3; -typedef NonlinearEquality NonlinearEqualityLieVector; -typedef NonlinearEquality NonlinearEqualityLieMatrix; typedef NonlinearEquality NonlinearEqualityPoint2; typedef NonlinearEquality NonlinearEqualityStereoPoint2; typedef NonlinearEquality NonlinearEqualityPoint3; @@ -94,7 +81,6 @@ typedef NonlinearEquality NonlinearEqualityPose3; typedef NonlinearEquality NonlinearEqualityCal3_S2; typedef NonlinearEquality NonlinearEqualityCal3DS2; typedef NonlinearEquality NonlinearEqualityCalibratedCamera; -typedef NonlinearEquality NonlinearEqualitySimpleCamera; typedef NonlinearEquality NonlinearEqualityPinholeCameraCal3_S2; typedef NonlinearEquality NonlinearEqualityStereoCamera; @@ -148,8 +134,6 @@ BOOST_CLASS_EXPORT_GUID(gtsam::SharedDiagonal, "gtsam_SharedDiagonal"); /* Create GUIDs for geometry */ /* ************************************************************************* */ -GTSAM_VALUE_EXPORT(gtsam::LieVector); -GTSAM_VALUE_EXPORT(gtsam::LieMatrix); GTSAM_VALUE_EXPORT(gtsam::Point2); GTSAM_VALUE_EXPORT(gtsam::StereoPoint2); GTSAM_VALUE_EXPORT(gtsam::Point3); @@ -170,8 +154,6 @@ GTSAM_VALUE_EXPORT(gtsam::StereoCamera); BOOST_CLASS_EXPORT_GUID(gtsam::JacobianFactor, "gtsam::JacobianFactor"); BOOST_CLASS_EXPORT_GUID(gtsam::HessianFactor , "gtsam::HessianFactor"); -BOOST_CLASS_EXPORT_GUID(PriorFactorLieVector, "gtsam::PriorFactorLieVector"); -BOOST_CLASS_EXPORT_GUID(PriorFactorLieMatrix, "gtsam::PriorFactorLieMatrix"); BOOST_CLASS_EXPORT_GUID(PriorFactorPoint2, "gtsam::PriorFactorPoint2"); BOOST_CLASS_EXPORT_GUID(PriorFactorStereoPoint2, "gtsam::PriorFactorStereoPoint2"); BOOST_CLASS_EXPORT_GUID(PriorFactorPoint3, "gtsam::PriorFactorPoint3"); @@ -182,11 +164,8 @@ BOOST_CLASS_EXPORT_GUID(PriorFactorPose3, "gtsam::PriorFactorPose3"); BOOST_CLASS_EXPORT_GUID(PriorFactorCal3_S2, "gtsam::PriorFactorCal3_S2"); BOOST_CLASS_EXPORT_GUID(PriorFactorCal3DS2, "gtsam::PriorFactorCal3DS2"); BOOST_CLASS_EXPORT_GUID(PriorFactorCalibratedCamera, "gtsam::PriorFactorCalibratedCamera"); -BOOST_CLASS_EXPORT_GUID(PriorFactorSimpleCamera, "gtsam::PriorFactorSimpleCamera"); BOOST_CLASS_EXPORT_GUID(PriorFactorStereoCamera, "gtsam::PriorFactorStereoCamera"); -BOOST_CLASS_EXPORT_GUID(BetweenFactorLieVector, "gtsam::BetweenFactorLieVector"); -BOOST_CLASS_EXPORT_GUID(BetweenFactorLieMatrix, "gtsam::BetweenFactorLieMatrix"); BOOST_CLASS_EXPORT_GUID(BetweenFactorPoint2, "gtsam::BetweenFactorPoint2"); BOOST_CLASS_EXPORT_GUID(BetweenFactorPoint3, "gtsam::BetweenFactorPoint3"); BOOST_CLASS_EXPORT_GUID(BetweenFactorRot2, "gtsam::BetweenFactorRot2"); @@ -194,8 +173,6 @@ BOOST_CLASS_EXPORT_GUID(BetweenFactorRot3, "gtsam::BetweenFactorRot3"); BOOST_CLASS_EXPORT_GUID(BetweenFactorPose2, "gtsam::BetweenFactorPose2"); BOOST_CLASS_EXPORT_GUID(BetweenFactorPose3, "gtsam::BetweenFactorPose3"); -BOOST_CLASS_EXPORT_GUID(NonlinearEqualityLieVector, "gtsam::NonlinearEqualityLieVector"); -BOOST_CLASS_EXPORT_GUID(NonlinearEqualityLieMatrix, "gtsam::NonlinearEqualityLieMatrix"); BOOST_CLASS_EXPORT_GUID(NonlinearEqualityPoint2, "gtsam::NonlinearEqualityPoint2"); BOOST_CLASS_EXPORT_GUID(NonlinearEqualityStereoPoint2, "gtsam::NonlinearEqualityStereoPoint2"); BOOST_CLASS_EXPORT_GUID(NonlinearEqualityPoint3, "gtsam::NonlinearEqualityPoint3"); @@ -206,7 +183,6 @@ BOOST_CLASS_EXPORT_GUID(NonlinearEqualityPose3, "gtsam::NonlinearEqualityPose3") BOOST_CLASS_EXPORT_GUID(NonlinearEqualityCal3_S2, "gtsam::NonlinearEqualityCal3_S2"); BOOST_CLASS_EXPORT_GUID(NonlinearEqualityCal3DS2, "gtsam::NonlinearEqualityCal3DS2"); BOOST_CLASS_EXPORT_GUID(NonlinearEqualityCalibratedCamera, "gtsam::NonlinearEqualityCalibratedCamera"); -BOOST_CLASS_EXPORT_GUID(NonlinearEqualitySimpleCamera, "gtsam::NonlinearEqualitySimpleCamera"); BOOST_CLASS_EXPORT_GUID(NonlinearEqualityStereoCamera, "gtsam::NonlinearEqualityStereoCamera"); BOOST_CLASS_EXPORT_GUID(RangeFactor2D, "gtsam::RangeFactor2D"); @@ -286,8 +262,6 @@ TEST (testSerializationSLAM, smallExample_nonlinear) { /* ************************************************************************* */ TEST (testSerializationSLAM, factors) { - LieVector lieVector((Vector(4) << 1.0, 2.0, 3.0, 4.0).finished()); - LieMatrix lieMatrix((Matrix(2, 3) << 1.0, 2.0, 3.0, 4.0, 5.0 ,6.0).finished()); Point2 point2(1.0, 2.0); StereoPoint2 stereoPoint2(1.0, 2.0, 3.0); Point3 point3(1.0, 2.0, 3.0); @@ -311,8 +285,6 @@ TEST (testSerializationSLAM, factors) { b11('b',11), b12('b',12), b13('b',13), b14('b',14), b15('b',15); Values values; - values.insert(a01, lieVector); - values.insert(a02, lieMatrix); values.insert(a03, point2); values.insert(a04, stereoPoint2); values.insert(a05, point3); @@ -344,8 +316,6 @@ TEST (testSerializationSLAM, factors) { EXPECT(equalsDereferencedXML(robust1)); EXPECT(equalsDereferencedBinary(robust1)); - PriorFactorLieVector priorFactorLieVector(a01, lieVector, model4); - PriorFactorLieMatrix priorFactorLieMatrix(a02, lieMatrix, model6); PriorFactorPoint2 priorFactorPoint2(a03, point2, model2); PriorFactorStereoPoint2 priorFactorStereoPoint2(a04, stereoPoint2, model3); PriorFactorPoint3 priorFactorPoint3(a05, point3, model3); @@ -356,11 +326,8 @@ TEST (testSerializationSLAM, factors) { PriorFactorCal3_S2 priorFactorCal3_S2(a10, cal3_s2, model5); PriorFactorCal3DS2 priorFactorCal3DS2(a11, cal3ds2, model9); PriorFactorCalibratedCamera priorFactorCalibratedCamera(a12, calibratedCamera, model6); - PriorFactorSimpleCamera priorFactorSimpleCamera(a13, simpleCamera, model11); PriorFactorStereoCamera priorFactorStereoCamera(a14, stereoCamera, model11); - BetweenFactorLieVector betweenFactorLieVector(a01, b01, lieVector, model4); - BetweenFactorLieMatrix betweenFactorLieMatrix(a02, b02, lieMatrix, model6); BetweenFactorPoint2 betweenFactorPoint2(a03, b03, point2, model2); BetweenFactorPoint3 betweenFactorPoint3(a05, b05, point3, model3); BetweenFactorRot2 betweenFactorRot2(a06, b06, rot2, model1); @@ -368,8 +335,6 @@ TEST (testSerializationSLAM, factors) { BetweenFactorPose2 betweenFactorPose2(a08, b08, pose2, model3); BetweenFactorPose3 betweenFactorPose3(a09, b09, pose3, model6); - NonlinearEqualityLieVector nonlinearEqualityLieVector(a01, lieVector); - NonlinearEqualityLieMatrix nonlinearEqualityLieMatrix(a02, lieMatrix); NonlinearEqualityPoint2 nonlinearEqualityPoint2(a03, point2); NonlinearEqualityStereoPoint2 nonlinearEqualityStereoPoint2(a04, stereoPoint2); NonlinearEqualityPoint3 nonlinearEqualityPoint3(a05, point3); @@ -380,7 +345,6 @@ TEST (testSerializationSLAM, factors) { NonlinearEqualityCal3_S2 nonlinearEqualityCal3_S2(a10, cal3_s2); NonlinearEqualityCal3DS2 nonlinearEqualityCal3DS2(a11, cal3ds2); NonlinearEqualityCalibratedCamera nonlinearEqualityCalibratedCamera(a12, calibratedCamera); - NonlinearEqualitySimpleCamera nonlinearEqualitySimpleCamera(a13, simpleCamera); NonlinearEqualityStereoCamera nonlinearEqualityStereoCamera(a14, stereoCamera); RangeFactor2D rangeFactor2D(a08, a03, 2.0, model1); @@ -405,8 +369,6 @@ TEST (testSerializationSLAM, factors) { NonlinearFactorGraph graph; - graph += priorFactorLieVector; - graph += priorFactorLieMatrix; graph += priorFactorPoint2; graph += priorFactorStereoPoint2; graph += priorFactorPoint3; @@ -417,11 +379,8 @@ TEST (testSerializationSLAM, factors) { graph += priorFactorCal3_S2; graph += priorFactorCal3DS2; graph += priorFactorCalibratedCamera; - graph += priorFactorSimpleCamera; graph += priorFactorStereoCamera; - graph += betweenFactorLieVector; - graph += betweenFactorLieMatrix; graph += betweenFactorPoint2; graph += betweenFactorPoint3; graph += betweenFactorRot2; @@ -429,8 +388,6 @@ TEST (testSerializationSLAM, factors) { graph += betweenFactorPose2; graph += betweenFactorPose3; - graph += nonlinearEqualityLieVector; - graph += nonlinearEqualityLieMatrix; graph += nonlinearEqualityPoint2; graph += nonlinearEqualityStereoPoint2; graph += nonlinearEqualityPoint3; @@ -441,7 +398,6 @@ TEST (testSerializationSLAM, factors) { graph += nonlinearEqualityCal3_S2; graph += nonlinearEqualityCal3DS2; graph += nonlinearEqualityCalibratedCamera; - graph += nonlinearEqualitySimpleCamera; graph += nonlinearEqualityStereoCamera; graph += rangeFactor2D; @@ -471,8 +427,6 @@ TEST (testSerializationSLAM, factors) { EXPECT(equalsObj(values)); EXPECT(equalsObj(graph)); - EXPECT(equalsObj(priorFactorLieVector)); - EXPECT(equalsObj(priorFactorLieMatrix)); EXPECT(equalsObj(priorFactorPoint2)); EXPECT(equalsObj(priorFactorStereoPoint2)); EXPECT(equalsObj(priorFactorPoint3)); @@ -483,11 +437,8 @@ TEST (testSerializationSLAM, factors) { EXPECT(equalsObj(priorFactorCal3_S2)); EXPECT(equalsObj(priorFactorCal3DS2)); EXPECT(equalsObj(priorFactorCalibratedCamera)); - EXPECT(equalsObj(priorFactorSimpleCamera)); EXPECT(equalsObj(priorFactorStereoCamera)); - EXPECT(equalsObj(betweenFactorLieVector)); - EXPECT(equalsObj(betweenFactorLieMatrix)); EXPECT(equalsObj(betweenFactorPoint2)); EXPECT(equalsObj(betweenFactorPoint3)); EXPECT(equalsObj(betweenFactorRot2)); @@ -495,8 +446,6 @@ TEST (testSerializationSLAM, factors) { EXPECT(equalsObj(betweenFactorPose2)); EXPECT(equalsObj(betweenFactorPose3)); - EXPECT(equalsObj(nonlinearEqualityLieVector)); - EXPECT(equalsObj(nonlinearEqualityLieMatrix)); EXPECT(equalsObj(nonlinearEqualityPoint2)); EXPECT(equalsObj(nonlinearEqualityStereoPoint2)); EXPECT(equalsObj(nonlinearEqualityPoint3)); @@ -507,7 +456,6 @@ TEST (testSerializationSLAM, factors) { EXPECT(equalsObj(nonlinearEqualityCal3_S2)); EXPECT(equalsObj(nonlinearEqualityCal3DS2)); EXPECT(equalsObj(nonlinearEqualityCalibratedCamera)); - EXPECT(equalsObj(nonlinearEqualitySimpleCamera)); EXPECT(equalsObj(nonlinearEqualityStereoCamera)); EXPECT(equalsObj(rangeFactor2D)); @@ -537,8 +485,6 @@ TEST (testSerializationSLAM, factors) { EXPECT(equalsXML(values)); EXPECT(equalsXML(graph)); - EXPECT(equalsXML(priorFactorLieVector)); - EXPECT(equalsXML(priorFactorLieMatrix)); EXPECT(equalsXML(priorFactorPoint2)); EXPECT(equalsXML(priorFactorStereoPoint2)); EXPECT(equalsXML(priorFactorPoint3)); @@ -549,11 +495,8 @@ TEST (testSerializationSLAM, factors) { EXPECT(equalsXML(priorFactorCal3_S2)); EXPECT(equalsXML(priorFactorCal3DS2)); EXPECT(equalsXML(priorFactorCalibratedCamera)); - EXPECT(equalsXML(priorFactorSimpleCamera)); EXPECT(equalsXML(priorFactorStereoCamera)); - EXPECT(equalsXML(betweenFactorLieVector)); - EXPECT(equalsXML(betweenFactorLieMatrix)); EXPECT(equalsXML(betweenFactorPoint2)); EXPECT(equalsXML(betweenFactorPoint3)); EXPECT(equalsXML(betweenFactorRot2)); @@ -561,8 +504,6 @@ TEST (testSerializationSLAM, factors) { EXPECT(equalsXML(betweenFactorPose2)); EXPECT(equalsXML(betweenFactorPose3)); - EXPECT(equalsXML(nonlinearEqualityLieVector)); - EXPECT(equalsXML(nonlinearEqualityLieMatrix)); EXPECT(equalsXML(nonlinearEqualityPoint2)); EXPECT(equalsXML(nonlinearEqualityStereoPoint2)); EXPECT(equalsXML(nonlinearEqualityPoint3)); @@ -573,7 +514,6 @@ TEST (testSerializationSLAM, factors) { EXPECT(equalsXML(nonlinearEqualityCal3_S2)); EXPECT(equalsXML(nonlinearEqualityCal3DS2)); EXPECT(equalsXML(nonlinearEqualityCalibratedCamera)); - EXPECT(equalsXML(nonlinearEqualitySimpleCamera)); EXPECT(equalsXML(nonlinearEqualityStereoCamera)); EXPECT(equalsXML(rangeFactor2D)); @@ -603,8 +543,6 @@ TEST (testSerializationSLAM, factors) { EXPECT(equalsBinary(values)); EXPECT(equalsBinary(graph)); - EXPECT(equalsBinary(priorFactorLieVector)); - EXPECT(equalsBinary(priorFactorLieMatrix)); EXPECT(equalsBinary(priorFactorPoint2)); EXPECT(equalsBinary(priorFactorStereoPoint2)); EXPECT(equalsBinary(priorFactorPoint3)); @@ -615,11 +553,8 @@ TEST (testSerializationSLAM, factors) { EXPECT(equalsBinary(priorFactorCal3_S2)); EXPECT(equalsBinary(priorFactorCal3DS2)); EXPECT(equalsBinary(priorFactorCalibratedCamera)); - EXPECT(equalsBinary(priorFactorSimpleCamera)); EXPECT(equalsBinary(priorFactorStereoCamera)); - EXPECT(equalsBinary(betweenFactorLieVector)); - EXPECT(equalsBinary(betweenFactorLieMatrix)); EXPECT(equalsBinary(betweenFactorPoint2)); EXPECT(equalsBinary(betweenFactorPoint3)); EXPECT(equalsBinary(betweenFactorRot2)); @@ -627,8 +562,6 @@ TEST (testSerializationSLAM, factors) { EXPECT(equalsBinary(betweenFactorPose2)); EXPECT(equalsBinary(betweenFactorPose3)); - EXPECT(equalsBinary(nonlinearEqualityLieVector)); - EXPECT(equalsBinary(nonlinearEqualityLieMatrix)); EXPECT(equalsBinary(nonlinearEqualityPoint2)); EXPECT(equalsBinary(nonlinearEqualityStereoPoint2)); EXPECT(equalsBinary(nonlinearEqualityPoint3)); @@ -639,7 +572,6 @@ TEST (testSerializationSLAM, factors) { EXPECT(equalsBinary(nonlinearEqualityCal3_S2)); EXPECT(equalsBinary(nonlinearEqualityCal3DS2)); EXPECT(equalsBinary(nonlinearEqualityCalibratedCamera)); - EXPECT(equalsBinary(nonlinearEqualitySimpleCamera)); EXPECT(equalsBinary(nonlinearEqualityStereoCamera)); EXPECT(equalsBinary(rangeFactor2D)); @@ -663,7 +595,6 @@ TEST (testSerializationSLAM, factors) { EXPECT(equalsBinary(genericStereoFactor3D)); } -#endif /* ************************************************************************* */ int main() { TestResult tr; return TestRegistry::runAllTests(tr); } From b25809d5a3d373a4f43d40174e988d3d0e51363a Mon Sep 17 00:00:00 2001 From: akrishnan86 Date: Sat, 25 Jul 2020 13:39:58 -0700 Subject: [PATCH 256/869] changes after review - removing positiveEdgeWeights --- gtsam/sfm/MFAS.cpp | 17 +++++++++-- gtsam/sfm/MFAS.h | 55 ++++++++++++++++++++++++------------ gtsam/sfm/tests/testMFAS.cpp | 7 +++++ 3 files changed, 59 insertions(+), 20 deletions(-) diff --git a/gtsam/sfm/MFAS.cpp b/gtsam/sfm/MFAS.cpp index e3288387e..b784e7efe 100644 --- a/gtsam/sfm/MFAS.cpp +++ b/gtsam/sfm/MFAS.cpp @@ -1,3 +1,10 @@ +/** + * @file MFAS.cpp + * @brief Source file for the MFAS class + * @author Akshay Krishnan + * @date July 2020 + */ + #include using namespace gtsam; @@ -26,14 +33,20 @@ std::vector MFAS::computeOrdering() const { FastMap ordered_positions; // map from node to its position in the output order // populate neighbors and weights + // Since the weights could be obtained by projection, they can be either + // negative or positive. Ideally, the weights should be positive in the + // direction of the edge. So, we define the direction of the edge as + // edge.first -> edge.second if weight is positive and + // edge.second -> edge.first if weight is negative. Once we know the + // direction, we only use the magnitude of the weights. for (auto it = edgeWeights_.begin(); it != edgeWeights_.end(); it++) { const KeyPair &edge = it->first; const double weight = it->second; Key edge_source = weight >= 0 ? edge.first : edge.second; Key edge_dest = weight >= 0 ? edge.second : edge.first; - in_weights[edge_dest] += weight; - out_weights[edge_source] += weight; + in_weights[edge_dest] += std::abs(weight); + out_weights[edge_source] += std::abs(weight); in_neighbors[edge_dest].push_back(edge_source); out_neighbors[edge_source].push_back(edge_dest); } diff --git a/gtsam/sfm/MFAS.h b/gtsam/sfm/MFAS.h index c8ea4f45d..c910e5621 100644 --- a/gtsam/sfm/MFAS.h +++ b/gtsam/sfm/MFAS.h @@ -11,6 +11,13 @@ #pragma once +/** + * @file MFAS.h + * @brief MFAS class to solve Minimum Feedback Arc Set graph problem + * @author Akshay Krishnan + * @date July 2020 + */ + #include #include @@ -29,13 +36,24 @@ namespace gtsam { Given a weighted directed graph, the objective in a Minimum feedback arc set problem is to obtain a directed acyclic graph by removing edges such that the total weight of removed edges is minimum. + + Although MFAS is a general graph problem and can be applied in many areas, this + classed was designed for the purpose of outlier rejection in a + translation averaging for SfM setting. For more details, refer to the above paper. + The nodes of the graph in this context represents cameras in 3D and the edges + between them represent unit translations in the world coordinate frame, i.e + w_aZb is the unit translation from a to b expressed in the world coordinate frame. + The weights for the edges are obtained by projecting the unit translations in a + projection direction. @addtogroup SFM */ class MFAS { public: - // used to represent edges between two nodes in the graph + // used to represent edges between two nodes in the graph. When used in + // translation averaging for global SfM using KeyPair = std::pair; using TranslationEdges = std::map; + private: // pointer to nodes in the graph const std::shared_ptr> nodes_; @@ -47,44 +65,45 @@ class MFAS { public: /** * @brief Construct from the nodes in a graph and weighted directed edges - * between the graph. A shared pointer to the nodes is used as input parameter. - * This is because, MFAS ordering is usually used to compute the ordering of a - * large graph that is already stored in memory. It is unnecessary to copy the - * set of nodes in this class. + * between the nodes. Each node is identified by a Key. + * A shared pointer to the nodes is used as input parameter + * because, MFAS ordering is usually used to compute the ordering of a + * large graph that is already stored in memory. It is unnecessary make a + * copy of the nodes in this class. * @param nodes: Nodes in the graph - * @param edgeWeights: weights of edges in the graph (map from pair of keys - * to signed double) + * @param edgeWeights: weights of edges in the graph */ MFAS(const std::shared_ptr> &nodes, const std::map &edgeWeights) : nodes_(nodes), edgeWeights_(edgeWeights) {} /** - * @brief Constructor for using in the context of translation averaging. Here, + * @brief Constructor to be used in the context of translation averaging. Here, * the nodes of the graph are cameras in 3D and the edges have a unit translation * direction between them. The weights of the edges is computed by projecting * them along a projection direction. - * @param nodes Nodes in the graph - * @param relativeTranslations translation directions between nodes + * @param nodes cameras in the epipolar graph (each camera is identified by a Key) + * @param relativeTranslations translation directions between the cameras * @param projectionDirection direction in which edges are to be projected */ MFAS(const std::shared_ptr> &nodes, const TranslationEdges& relativeTranslations, const Unit3 &projectionDirection); - /** - * @brief Computes the "outlier weights" of the graph. We define the outlier weight - * of a edge to be zero if the edge is an inlier and the magnitude of its edgeWeight - * if it is an outlier. - * @return outlierWeights: map from an edge to its outlier weight. - */ - std::map computeOutlierWeights() const; - /** * @brief Computes the 1D MFAS ordering of nodes in the graph * @return orderedNodes: vector of nodes in the obtained order */ std::vector computeOrdering() const; + + /** + * @brief Computes the "outlier weights" of the graph. We define the outlier weight + * of a edge to be zero if the edge is an inlier and the magnitude of its edgeWeight + * if it is an outlier. This function internally calls computeOrdering and uses the + * obtained ordering to identify outlier edges. + * @return outlierWeights: map from an edge to its outlier weight. + */ + std::map computeOutlierWeights() const; }; } // namespace gtsam diff --git a/gtsam/sfm/tests/testMFAS.cpp b/gtsam/sfm/tests/testMFAS.cpp index 8819493be..923d75a45 100644 --- a/gtsam/sfm/tests/testMFAS.cpp +++ b/gtsam/sfm/tests/testMFAS.cpp @@ -1,3 +1,10 @@ +/** + * @file testMFAS.cpp + * @brief Unit tests for the MFAS class + * @author Akshay Krishnan + * @date July 2020 + */ + #include #include #include From 8a5097d726764674f4df38ffc953aad51210c967 Mon Sep 17 00:00:00 2001 From: Jose Luis Blanco Claraco Date: Sun, 26 Jul 2020 08:22:40 +0200 Subject: [PATCH 257/869] Add docs on serializing expressions. --- gtsam/nonlinear/ExpressionFactor.h | 9 +++++++-- 1 file changed, 7 insertions(+), 2 deletions(-) diff --git a/gtsam/nonlinear/ExpressionFactor.h b/gtsam/nonlinear/ExpressionFactor.h index c42b2bdfc..e39a65a0e 100644 --- a/gtsam/nonlinear/ExpressionFactor.h +++ b/gtsam/nonlinear/ExpressionFactor.h @@ -27,8 +27,13 @@ namespace gtsam { /** - - * Factor that supports arbitrary expressions via AD + * Factor that supports arbitrary expressions via AD. + * + * Arbitrary instances of this template can be directly inserted into a factor + * graph for optimization. However, to enable the correct (de)serialization of + * such instances, the user should declare derived classes from this template, + * implementing expresion(), serialize(), clone(), print(), and defining the + * corresponding `struct traits : public Testable {}`. */ template class ExpressionFactor: public NoiseModelFactor { From 4e3638f6a72cfbb384d9c240e1aa57b71ad5b838 Mon Sep 17 00:00:00 2001 From: Jose Luis Blanco Claraco Date: Sun, 26 Jul 2020 08:41:57 +0200 Subject: [PATCH 258/869] enable compiler warnings and errors for safer code --- cmake/GtsamBuildTypes.cmake | 13 +++++++++++-- 1 file changed, 11 insertions(+), 2 deletions(-) diff --git a/cmake/GtsamBuildTypes.cmake b/cmake/GtsamBuildTypes.cmake index 088ba7ad2..a233e562c 100644 --- a/cmake/GtsamBuildTypes.cmake +++ b/cmake/GtsamBuildTypes.cmake @@ -104,8 +104,17 @@ if(MSVC) set(GTSAM_COMPILE_OPTIONS_PRIVATE_TIMING /MD /O2 CACHE STRING "(User editable) Private compiler flags for Timing configuration.") else() # Common to all configurations, next for each configuration: - # "-fPIC" is to ensure proper code generation for shared libraries - set(GTSAM_COMPILE_OPTIONS_PRIVATE_COMMON -Wall -fPIC CACHE STRING "(User editable) Private compiler flags for all configurations.") + + set(GTSAM_COMPILE_OPTIONS_PRIVATE_COMMON + -Wall # Enable common warnings + -fPIC # ensure proper code generation for shared libraries + $<$:-Wreturn-local-addr -Werror=return-local-addr> # Error: return local address + $<$:-Wreturn-stack-address -Werror=return-stack-address> # Error: return local address + -Wreturn-type -Werror=return-type # Error on missing return() + -Wformat -Werror=format-security # Error on wrong printf() arguments + -Wsuggest-override -Werror=suggest-override # Enforce the use of the override keyword + # + CACHE STRING "(User editable) Private compiler flags for all configurations.") set(GTSAM_COMPILE_OPTIONS_PRIVATE_DEBUG -g -fno-inline CACHE STRING "(User editable) Private compiler flags for Debug configuration.") set(GTSAM_COMPILE_OPTIONS_PRIVATE_RELWITHDEBINFO -g -O3 CACHE STRING "(User editable) Private compiler flags for RelWithDebInfo configuration.") set(GTSAM_COMPILE_OPTIONS_PRIVATE_RELEASE -O3 CACHE STRING "(User editable) Private compiler flags for Release configuration.") From 0198c648e3f5b162717704658ab9d28ccdbe5563 Mon Sep 17 00:00:00 2001 From: Jose Luis Blanco Claraco Date: Sun, 26 Jul 2020 09:57:54 +0200 Subject: [PATCH 259/869] Fix all new gcc warnings/errors: make explicit virtual/override methods. Rules are: - use "virtual" in base classes only. - use "override" in all derived classes. --- CppUnitLite/Test.h | 4 +- cmake/GtsamBuildTypes.cmake | 2 +- examples/CameraResectioning.cpp | 4 +- examples/LocalizationExample.cpp | 4 +- gtsam/base/GenericValue.h | 18 ++--- gtsam/base/ThreadsafeException.h | 10 +-- .../treeTraversal/parallelTraversalTasks.h | 4 +- gtsam/discrete/DecisionTree-inl.h | 48 +++++------ gtsam/discrete/DecisionTreeFactor.h | 12 +-- gtsam/discrete/DiscreteConditional.h | 6 +- gtsam/geometry/Cal3DS2.h | 4 +- gtsam/geometry/Cal3DS2_Base.h | 2 +- gtsam/geometry/Cal3Unified.h | 2 +- gtsam/geometry/PinholeCamera.h | 2 +- gtsam/geometry/PinholePose.h | 2 +- gtsam/geometry/PinholeSet.h | 2 +- gtsam/inference/BayesTree.h | 2 +- gtsam/inference/BayesTreeCliqueBase.h | 2 +- gtsam/inference/inferenceExceptions.h | 6 +- gtsam/linear/BinaryJacobianFactor.h | 2 +- gtsam/linear/ConjugateGradientSolver.h | 2 +- gtsam/linear/GaussianConditional.h | 4 +- gtsam/linear/GaussianDensity.h | 2 +- gtsam/linear/LossFunctions.h | 8 +- gtsam/linear/PCGSolver.h | 6 +- gtsam/linear/Preconditioner.h | 16 ++-- gtsam/linear/RegularHessianFactor.h | 8 +- gtsam/linear/RegularJacobianFactor.h | 10 +-- gtsam/linear/SubgraphSolver.h | 2 +- gtsam/linear/linearExceptions.cpp | 6 +- gtsam/linear/linearExceptions.h | 14 ++-- gtsam/navigation/AHRSFactor.h | 10 +-- gtsam/navigation/AttitudeFactor.h | 24 +++--- gtsam/navigation/CombinedImuFactor.h | 14 ++-- gtsam/navigation/GPSFactor.h | 20 ++--- gtsam/navigation/ImuFactor.h | 20 ++--- gtsam/navigation/MagFactor.h | 8 +- gtsam/navigation/PreintegrationParams.h | 4 +- gtsam/nonlinear/ExpressionFactor.h | 14 ++-- gtsam/nonlinear/FunctorizedFactor.h | 8 +- gtsam/nonlinear/ISAM2Clique.h | 2 +- gtsam/nonlinear/LinearContainerFactor.h | 12 +-- gtsam/nonlinear/NonlinearEquality.h | 26 +++--- gtsam/nonlinear/NonlinearFactor.h | 26 +++--- gtsam/nonlinear/PriorFactor.h | 10 +-- gtsam/nonlinear/Values.cpp | 8 +- gtsam/nonlinear/Values.h | 36 ++++----- gtsam/nonlinear/WhiteNoiseFactor.h | 10 +-- gtsam/nonlinear/internal/CallRecord.h | 30 +++---- gtsam/nonlinear/internal/ExpressionNode.h | 80 +++++++++---------- gtsam/nonlinear/nonlinearExceptions.h | 6 +- gtsam/sam/BearingFactor.h | 4 +- gtsam/sam/BearingRangeFactor.h | 8 +- gtsam/sam/RangeFactor.h | 12 +-- gtsam/slam/AntiFactor.h | 14 ++-- gtsam/slam/BetweenFactor.h | 10 +-- gtsam/slam/BoundingConstraint.h | 8 +- gtsam/slam/EssentialMatrixConstraint.h | 12 +-- gtsam/slam/EssentialMatrixFactor.h | 24 +++--- gtsam/slam/FrobeniusFactor.h | 8 +- gtsam/slam/GeneralSFMFactor.h | 18 ++--- gtsam/slam/OrientedPlane3Factor.h | 18 ++--- gtsam/slam/PoseRotationPrior.h | 8 +- gtsam/slam/PoseTranslationPrior.h | 8 +- gtsam/slam/ProjectionFactor.h | 8 +- gtsam/slam/ReferenceFrameFactor.h | 10 +-- gtsam/slam/RotateFactor.h | 16 ++-- gtsam/slam/SmartFactorBase.h | 6 +- gtsam/slam/SmartProjectionFactor.h | 10 +-- gtsam/slam/SmartProjectionPoseFactor.h | 8 +- gtsam/slam/StereoFactor.h | 8 +- gtsam/slam/TriangulationFactor.h | 10 +-- gtsam/slam/tests/testSmartFactorBase.cpp | 12 +-- gtsam/symbolic/SymbolicConditional.h | 2 +- gtsam_unstable/discrete/AllDiff.h | 18 ++--- gtsam_unstable/discrete/BinaryAllDiff.h | 20 ++--- gtsam_unstable/discrete/Domain.h | 21 +++-- gtsam_unstable/discrete/SingleValue.h | 21 +++-- gtsam_unstable/dynamics/FullIMUFactor.h | 10 +-- gtsam_unstable/dynamics/IMUFactor.h | 10 +-- gtsam_unstable/dynamics/Pendulum.h | 16 ++-- gtsam_unstable/dynamics/SimpleHelicopter.h | 8 +- gtsam_unstable/dynamics/VelocityConstraint.h | 8 +- gtsam_unstable/dynamics/VelocityConstraint3.h | 4 +- .../linear/InfeasibleInitialValues.h | 4 +- .../linear/InfeasibleOrUnboundedProblem.h | 4 +- gtsam_unstable/linear/LinearCost.h | 10 +-- gtsam_unstable/linear/LinearEquality.h | 10 +-- gtsam_unstable/linear/LinearInequality.h | 10 +-- gtsam_unstable/linear/QPSParserException.h | 4 +- .../nonlinear/BatchFixedLagSmoother.h | 4 +- .../nonlinear/ConcurrentBatchFilter.h | 14 ++-- .../nonlinear/ConcurrentBatchSmoother.h | 14 ++-- .../nonlinear/ConcurrentIncrementalFilter.h | 14 ++-- .../nonlinear/ConcurrentIncrementalSmoother.h | 14 ++-- gtsam_unstable/nonlinear/LinearizedFactor.h | 24 +++--- gtsam_unstable/slam/BetweenFactorEM.h | 8 +- gtsam_unstable/slam/BiasedGPSFactor.h | 6 +- gtsam_unstable/slam/DummyFactor.h | 12 +-- .../slam/EquivInertialNavFactor_GlobalVel.h | 6 +- .../EquivInertialNavFactor_GlobalVel_NoBias.h | 2 +- .../slam/GaussMarkov1stOrderFactor.h | 6 +- .../slam/InertialNavFactor_GlobalVelocity.h | 6 +- gtsam_unstable/slam/InvDepthFactor3.h | 6 +- gtsam_unstable/slam/InvDepthFactorVariant1.h | 6 +- gtsam_unstable/slam/InvDepthFactorVariant2.h | 6 +- gtsam_unstable/slam/InvDepthFactorVariant3.h | 12 +-- gtsam_unstable/slam/MultiProjectionFactor.h | 8 +- gtsam_unstable/slam/PartialPriorFactor.h | 8 +- gtsam_unstable/slam/PoseBetweenFactor.h | 8 +- gtsam_unstable/slam/PosePriorFactor.h | 8 +- gtsam_unstable/slam/ProjectionFactorPPP.h | 8 +- gtsam_unstable/slam/ProjectionFactorPPPC.h | 8 +- gtsam_unstable/slam/RelativeElevationFactor.h | 8 +- gtsam_unstable/slam/SmartRangeFactor.h | 12 +-- .../slam/SmartStereoProjectionFactor.h | 14 ++-- .../slam/SmartStereoProjectionPoseFactor.h | 8 +- gtsam_unstable/slam/TSAMFactors.h | 6 +- .../slam/TransformBtwRobotsUnaryFactor.h | 12 +-- .../slam/TransformBtwRobotsUnaryFactorEM.h | 12 +-- tests/simulated2D.h | 12 +-- tests/simulated2DConstraints.h | 18 ++--- tests/simulated2DOriented.h | 4 +- tests/simulated3D.h | 4 +- tests/smallExample.h | 2 +- tests/testExtendedKalmanFilter.cpp | 24 +++--- tests/testNonlinearFactor.cpp | 14 ++-- tests/testNonlinearOptimizer.cpp | 4 +- wrap/Method.h | 8 +- wrap/ReturnType.h | 2 +- wrap/StaticMethod.h | 6 +- wrap/utilities.h | 12 +-- 132 files changed, 696 insertions(+), 698 deletions(-) diff --git a/CppUnitLite/Test.h b/CppUnitLite/Test.h index b1fb0cf08..a898c83ef 100644 --- a/CppUnitLite/Test.h +++ b/CppUnitLite/Test.h @@ -64,7 +64,7 @@ protected: class testGroup##testName##Test : public Test \ { public: testGroup##testName##Test () : Test (#testName "Test", __FILE__, __LINE__, true) {} \ virtual ~testGroup##testName##Test () {};\ - void run (TestResult& result_);} \ + void run (TestResult& result_) override;} \ testGroup##testName##Instance; \ void testGroup##testName##Test::run (TestResult& result_) @@ -82,7 +82,7 @@ protected: class testGroup##testName##Test : public Test \ { public: testGroup##testName##Test () : Test (#testName "Test", __FILE__, __LINE__, false) {} \ virtual ~testGroup##testName##Test () {};\ - void run (TestResult& result_);} \ + void run (TestResult& result_) override;} \ testGroup##testName##Instance; \ void testGroup##testName##Test::run (TestResult& result_) diff --git a/cmake/GtsamBuildTypes.cmake b/cmake/GtsamBuildTypes.cmake index a233e562c..bffe97904 100644 --- a/cmake/GtsamBuildTypes.cmake +++ b/cmake/GtsamBuildTypes.cmake @@ -112,7 +112,7 @@ else() $<$:-Wreturn-stack-address -Werror=return-stack-address> # Error: return local address -Wreturn-type -Werror=return-type # Error on missing return() -Wformat -Werror=format-security # Error on wrong printf() arguments - -Wsuggest-override -Werror=suggest-override # Enforce the use of the override keyword + $<$:-Wsuggest-override -Werror=suggest-override> # Enforce the use of the override keyword # CACHE STRING "(User editable) Private compiler flags for all configurations.") set(GTSAM_COMPILE_OPTIONS_PRIVATE_DEBUG -g -fno-inline CACHE STRING "(User editable) Private compiler flags for Debug configuration.") diff --git a/examples/CameraResectioning.cpp b/examples/CameraResectioning.cpp index b12418098..7ac2de8b1 100644 --- a/examples/CameraResectioning.cpp +++ b/examples/CameraResectioning.cpp @@ -46,8 +46,8 @@ public: } /// evaluate the error - virtual Vector evaluateError(const Pose3& pose, boost::optional H = - boost::none) const { + Vector evaluateError(const Pose3& pose, boost::optional H = + boost::none) const override { PinholeCamera camera(pose, *K_); return camera.project(P_, H, boost::none, boost::none) - p_; } diff --git a/examples/LocalizationExample.cpp b/examples/LocalizationExample.cpp index a28ead5fe..e6a0f6622 100644 --- a/examples/LocalizationExample.cpp +++ b/examples/LocalizationExample.cpp @@ -85,7 +85,7 @@ class UnaryFactor: public NoiseModelFactor1 { // function, returning a vector of errors when evaluated at the provided variable value. It // must also calculate the Jacobians for this measurement function, if requested. Vector evaluateError(const Pose2& q, - boost::optional H = boost::none) const { + boost::optional H = boost::none) const override { // The measurement function for a GPS-like measurement is simple: // error_x = pose.x - measurement.x // error_y = pose.y - measurement.y @@ -99,7 +99,7 @@ class UnaryFactor: public NoiseModelFactor1 { // The second is a 'clone' function that allows the factor to be copied. Under most // circumstances, the following code that employs the default copy constructor should // work fine. - virtual gtsam::NonlinearFactor::shared_ptr clone() const { + gtsam::NonlinearFactor::shared_ptr clone() const override { return boost::static_pointer_cast( gtsam::NonlinearFactor::shared_ptr(new UnaryFactor(*this))); } diff --git a/gtsam/base/GenericValue.h b/gtsam/base/GenericValue.h index 2ac3eb80c..98425adde 100644 --- a/gtsam/base/GenericValue.h +++ b/gtsam/base/GenericValue.h @@ -70,7 +70,7 @@ public: } /// equals implementing generic Value interface - virtual bool equals_(const Value& p, double tol = 1e-9) const { + bool equals_(const Value& p, double tol = 1e-9) const override { // Cast the base class Value pointer to a templated generic class pointer const GenericValue& genericValue2 = static_cast(p); // Return the result of using the equals traits for the derived class @@ -83,7 +83,7 @@ public: } /// Virtual print function, uses traits - virtual void print(const std::string& str) const { + void print(const std::string& str) const override { std::cout << "(" << demangle(typeid(T).name()) << ") "; traits::Print(value_, str); } @@ -91,7 +91,7 @@ public: /** * Create a duplicate object returned as a pointer to the generic Value interface. */ - virtual Value* clone_() const { + Value* clone_() const override { GenericValue* ptr = new GenericValue(*this); // calls copy constructor to fill in return ptr; } @@ -99,19 +99,19 @@ public: /** * Destroy and deallocate this object, only if it was originally allocated using clone_(). */ - virtual void deallocate_() const { + void deallocate_() const override { delete this; } /** * Clone this value (normal clone on the heap, delete with 'delete' operator) */ - virtual boost::shared_ptr clone() const { + boost::shared_ptr clone() const override { return boost::allocate_shared(Eigen::aligned_allocator(), *this); } /// Generic Value interface version of retract - virtual Value* retract_(const Vector& delta) const { + Value* retract_(const Vector& delta) const override { // Call retract on the derived class using the retract trait function const T retractResult = traits::Retract(GenericValue::value(), delta); @@ -122,7 +122,7 @@ public: } /// Generic Value interface version of localCoordinates - virtual Vector localCoordinates_(const Value& value2) const { + Vector localCoordinates_(const Value& value2) const override { // Cast the base class Value pointer to a templated generic class pointer const GenericValue& genericValue2 = static_cast&>(value2); @@ -142,12 +142,12 @@ public: } /// Return run-time dimensionality - virtual size_t dim() const { + size_t dim() const override { return traits::GetDimension(value_); } /// Assignment operator - virtual Value& operator=(const Value& rhs) { + Value& operator=(const Value& rhs) override { // Cast the base class Value pointer to a derived class pointer const GenericValue& derivedRhs = static_cast(rhs); diff --git a/gtsam/base/ThreadsafeException.h b/gtsam/base/ThreadsafeException.h index 0f7c6131d..744759f5b 100644 --- a/gtsam/base/ThreadsafeException.h +++ b/gtsam/base/ThreadsafeException.h @@ -71,12 +71,12 @@ protected: String(description.begin(), description.end())) { } - /// Default destructor doesn't have the throw() - virtual ~ThreadsafeException() throw () { + /// Default destructor doesn't have the noexcept + virtual ~ThreadsafeException() noexcept { } public: - virtual const char* what() const throw () { + const char* what() const noexcept override { return description_ ? description_->c_str() : ""; } }; @@ -113,8 +113,8 @@ public: class CholeskyFailed : public gtsam::ThreadsafeException { public: - CholeskyFailed() throw() {} - virtual ~CholeskyFailed() throw() {} + CholeskyFailed() noexcept {} + virtual ~CholeskyFailed() noexcept {} }; } // namespace gtsam diff --git a/gtsam/base/treeTraversal/parallelTraversalTasks.h b/gtsam/base/treeTraversal/parallelTraversalTasks.h index b52d44e2a..87d5b0d4c 100644 --- a/gtsam/base/treeTraversal/parallelTraversalTasks.h +++ b/gtsam/base/treeTraversal/parallelTraversalTasks.h @@ -57,7 +57,7 @@ namespace gtsam { makeNewTasks(makeNewTasks), isPostOrderPhase(false) {} - tbb::task* execute() + tbb::task* execute() override { if(isPostOrderPhase) { @@ -144,7 +144,7 @@ namespace gtsam { roots(roots), myData(myData), visitorPre(visitorPre), visitorPost(visitorPost), problemSizeThreshold(problemSizeThreshold) {} - tbb::task* execute() + tbb::task* execute() override { typedef PreOrderTask PreOrderTask; // Create data and tasks for our children diff --git a/gtsam/discrete/DecisionTree-inl.h b/gtsam/discrete/DecisionTree-inl.h index 2efd069cc..dd10500e6 100644 --- a/gtsam/discrete/DecisionTree-inl.h +++ b/gtsam/discrete/DecisionTree-inl.h @@ -66,42 +66,42 @@ namespace gtsam { } /// Leaf-Leaf equality - bool sameLeaf(const Leaf& q) const { + bool sameLeaf(const Leaf& q) const override { return constant_ == q.constant_; } /// polymorphic equality: is q is a leaf, could be - bool sameLeaf(const Node& q) const { + bool sameLeaf(const Node& q) const override { return (q.isLeaf() && q.sameLeaf(*this)); } /** equality up to tolerance */ - bool equals(const Node& q, double tol) const { + bool equals(const Node& q, double tol) const override { const Leaf* other = dynamic_cast (&q); if (!other) return false; return std::abs(double(this->constant_ - other->constant_)) < tol; } /** print */ - void print(const std::string& s) const { + void print(const std::string& s) const override { bool showZero = true; if (showZero || constant_) std::cout << s << " Leaf " << constant_ << std::endl; } /** to graphviz file */ - void dot(std::ostream& os, bool showZero) const { + void dot(std::ostream& os, bool showZero) const override { if (showZero || constant_) os << "\"" << this->id() << "\" [label=\"" << boost::format("%4.2g") % constant_ << "\", shape=box, rank=sink, height=0.35, fixedsize=true]\n"; // width=0.55, } /** evaluate */ - const Y& operator()(const Assignment& x) const { + const Y& operator()(const Assignment& x) const override { return constant_; } /** apply unary operator */ - NodePtr apply(const Unary& op) const { + NodePtr apply(const Unary& op) const override { NodePtr f(new Leaf(op(constant_))); return f; } @@ -111,27 +111,27 @@ namespace gtsam { // Simply calls apply on argument to call correct virtual method: // fL.apply_f_op_g(gL) -> gL.apply_g_op_fL(fL) (below) // fL.apply_f_op_g(gC) -> gC.apply_g_op_fL(fL) (Choice) - NodePtr apply_f_op_g(const Node& g, const Binary& op) const { + NodePtr apply_f_op_g(const Node& g, const Binary& op) const override { return g.apply_g_op_fL(*this, op); } // Applying binary operator to two leaves results in a leaf - NodePtr apply_g_op_fL(const Leaf& fL, const Binary& op) const { + NodePtr apply_g_op_fL(const Leaf& fL, const Binary& op) const override { NodePtr h(new Leaf(op(fL.constant_, constant_))); // fL op gL return h; } // If second argument is a Choice node, call it's apply with leaf as second - NodePtr apply_g_op_fC(const Choice& fC, const Binary& op) const { + NodePtr apply_g_op_fC(const Choice& fC, const Binary& op) const override { return fC.apply_fC_op_gL(*this, op); // operand order back to normal } /** choose a branch, create new memory ! */ - NodePtr choose(const L& label, size_t index) const { + NodePtr choose(const L& label, size_t index) const override { return NodePtr(new Leaf(constant())); } - bool isLeaf() const { return true; } + bool isLeaf() const override { return true; } }; // Leaf @@ -175,7 +175,7 @@ namespace gtsam { return f; } - bool isLeaf() const { return false; } + bool isLeaf() const override { return false; } /** Constructor, given choice label and mandatory expected branch count */ Choice(const L& label, size_t count) : @@ -236,7 +236,7 @@ namespace gtsam { } /** print (as a tree) */ - void print(const std::string& s) const { + void print(const std::string& s) const override { std::cout << s << " Choice("; // std::cout << this << ","; std::cout << label_ << ") " << std::endl; @@ -245,7 +245,7 @@ namespace gtsam { } /** output to graphviz (as a a graph) */ - void dot(std::ostream& os, bool showZero) const { + void dot(std::ostream& os, bool showZero) const override { os << "\"" << this->id() << "\" [shape=circle, label=\"" << label_ << "\"]\n"; for (size_t i = 0; i < branches_.size(); i++) { @@ -266,17 +266,17 @@ namespace gtsam { } /// Choice-Leaf equality: always false - bool sameLeaf(const Leaf& q) const { + bool sameLeaf(const Leaf& q) const override { return false; } /// polymorphic equality: if q is a leaf, could be... - bool sameLeaf(const Node& q) const { + bool sameLeaf(const Node& q) const override { return (q.isLeaf() && q.sameLeaf(*this)); } /** equality up to tolerance */ - bool equals(const Node& q, double tol) const { + bool equals(const Node& q, double tol) const override { const Choice* other = dynamic_cast (&q); if (!other) return false; if (this->label_ != other->label_) return false; @@ -288,7 +288,7 @@ namespace gtsam { } /** evaluate */ - const Y& operator()(const Assignment& x) const { + const Y& operator()(const Assignment& x) const override { #ifndef NDEBUG typename Assignment::const_iterator it = x.find(label_); if (it == x.end()) { @@ -314,7 +314,7 @@ namespace gtsam { } /** apply unary operator */ - NodePtr apply(const Unary& op) const { + NodePtr apply(const Unary& op) const override { boost::shared_ptr r(new Choice(label_, *this, op)); return Unique(r); } @@ -324,12 +324,12 @@ namespace gtsam { // Simply calls apply on argument to call correct virtual method: // fC.apply_f_op_g(gL) -> gL.apply_g_op_fC(fC) -> (Leaf) // fC.apply_f_op_g(gC) -> gC.apply_g_op_fC(fC) -> (below) - NodePtr apply_f_op_g(const Node& g, const Binary& op) const { + NodePtr apply_f_op_g(const Node& g, const Binary& op) const override { return g.apply_g_op_fC(*this, op); } // If second argument of binary op is Leaf node, recurse on branches - NodePtr apply_g_op_fL(const Leaf& fL, const Binary& op) const { + NodePtr apply_g_op_fL(const Leaf& fL, const Binary& op) const override { boost::shared_ptr h(new Choice(label(), nrChoices())); for(NodePtr branch: branches_) h->push_back(fL.apply_f_op_g(*branch, op)); @@ -337,7 +337,7 @@ namespace gtsam { } // If second argument of binary op is Choice, call constructor - NodePtr apply_g_op_fC(const Choice& fC, const Binary& op) const { + NodePtr apply_g_op_fC(const Choice& fC, const Binary& op) const override { boost::shared_ptr h(new Choice(fC, *this, op)); return Unique(h); } @@ -352,7 +352,7 @@ namespace gtsam { } /** choose a branch, recursively */ - NodePtr choose(const L& label, size_t index) const { + NodePtr choose(const L& label, size_t index) const override { if (label_ == label) return branches_[index]; // choose branch diff --git a/gtsam/discrete/DecisionTreeFactor.h b/gtsam/discrete/DecisionTreeFactor.h index 54cce56be..d1696a281 100644 --- a/gtsam/discrete/DecisionTreeFactor.h +++ b/gtsam/discrete/DecisionTreeFactor.h @@ -69,23 +69,23 @@ namespace gtsam { /// @{ /// equality - bool equals(const DiscreteFactor& other, double tol = 1e-9) const; + bool equals(const DiscreteFactor& other, double tol = 1e-9) const override; // print - virtual void print(const std::string& s = "DecisionTreeFactor:\n", - const KeyFormatter& formatter = DefaultKeyFormatter) const; + void print(const std::string& s = "DecisionTreeFactor:\n", + const KeyFormatter& formatter = DefaultKeyFormatter) const override; /// @} /// @name Standard Interface /// @{ /// Value is just look up in AlgebraicDecisonTree - virtual double operator()(const Values& values) const { + double operator()(const Values& values) const override { return Potentials::operator()(values); } /// multiply two factors - DecisionTreeFactor operator*(const DecisionTreeFactor& f) const { + DecisionTreeFactor operator*(const DecisionTreeFactor& f) const override { return apply(f, ADT::Ring::mul); } @@ -95,7 +95,7 @@ namespace gtsam { } /// Convert into a decisiontree - virtual DecisionTreeFactor toDecisionTreeFactor() const { + DecisionTreeFactor toDecisionTreeFactor() const override { return *this; } diff --git a/gtsam/discrete/DiscreteConditional.h b/gtsam/discrete/DiscreteConditional.h index 225e6e1d3..8299fab2c 100644 --- a/gtsam/discrete/DiscreteConditional.h +++ b/gtsam/discrete/DiscreteConditional.h @@ -85,10 +85,10 @@ public: /// GTSAM-style print void print(const std::string& s = "Discrete Conditional: ", - const KeyFormatter& formatter = DefaultKeyFormatter) const; + const KeyFormatter& formatter = DefaultKeyFormatter) const override; /// GTSAM-style equals - bool equals(const DiscreteFactor& other, double tol = 1e-9) const; + bool equals(const DiscreteFactor& other, double tol = 1e-9) const override; /// @} /// @name Standard Interface @@ -102,7 +102,7 @@ public: } /// Evaluate, just look up in AlgebraicDecisonTree - virtual double operator()(const Values& values) const { + double operator()(const Values& values) const override { return Potentials::operator()(values); } diff --git a/gtsam/geometry/Cal3DS2.h b/gtsam/geometry/Cal3DS2.h index 3e62f758d..7fd453d45 100644 --- a/gtsam/geometry/Cal3DS2.h +++ b/gtsam/geometry/Cal3DS2.h @@ -60,7 +60,7 @@ public: /// @{ /// print with optional string - virtual void print(const std::string& s = "") const ; + void print(const std::string& s = "") const override; /// assert equality up to a tolerance bool equals(const Cal3DS2& K, double tol = 10e-9) const; @@ -86,7 +86,7 @@ public: /// @{ /// @return a deep copy of this object - virtual boost::shared_ptr clone() const { + boost::shared_ptr clone() const override { return boost::shared_ptr(new Cal3DS2(*this)); } diff --git a/gtsam/geometry/Cal3DS2_Base.h b/gtsam/geometry/Cal3DS2_Base.h index 4da5d1360..a0ece8bdb 100644 --- a/gtsam/geometry/Cal3DS2_Base.h +++ b/gtsam/geometry/Cal3DS2_Base.h @@ -69,7 +69,7 @@ public: /// @{ /// print with optional string - virtual void print(const std::string& s = "") const ; + virtual void print(const std::string& s = "") const; /// assert equality up to a tolerance bool equals(const Cal3DS2_Base& K, double tol = 10e-9) const; diff --git a/gtsam/geometry/Cal3Unified.h b/gtsam/geometry/Cal3Unified.h index ae75c3916..381405d20 100644 --- a/gtsam/geometry/Cal3Unified.h +++ b/gtsam/geometry/Cal3Unified.h @@ -75,7 +75,7 @@ public: /// @{ /// print with optional string - virtual void print(const std::string& s = "") const ; + void print(const std::string& s = "") const override; /// assert equality up to a tolerance bool equals(const Cal3Unified& K, double tol = 10e-9) const; diff --git a/gtsam/geometry/PinholeCamera.h b/gtsam/geometry/PinholeCamera.h index 9a80b937b..cf449ce8c 100644 --- a/gtsam/geometry/PinholeCamera.h +++ b/gtsam/geometry/PinholeCamera.h @@ -175,7 +175,7 @@ public: } /// return calibration - const Calibration& calibration() const { + const Calibration& calibration() const override { return K_; } diff --git a/gtsam/geometry/PinholePose.h b/gtsam/geometry/PinholePose.h index 79dbb9ce9..3bf96c08b 100644 --- a/gtsam/geometry/PinholePose.h +++ b/gtsam/geometry/PinholePose.h @@ -361,7 +361,7 @@ public: } /// return calibration - virtual const CALIBRATION& calibration() const { + const CALIBRATION& calibration() const override { return *K_; } diff --git a/gtsam/geometry/PinholeSet.h b/gtsam/geometry/PinholeSet.h index a2896ca8d..7e3dae56f 100644 --- a/gtsam/geometry/PinholeSet.h +++ b/gtsam/geometry/PinholeSet.h @@ -45,7 +45,7 @@ public: /// @{ /// print - virtual void print(const std::string& s = "") const { + void print(const std::string& s = "") const override { Base::print(s); } diff --git a/gtsam/inference/BayesTree.h b/gtsam/inference/BayesTree.h index 9d632ff06..10fc513ee 100644 --- a/gtsam/inference/BayesTree.h +++ b/gtsam/inference/BayesTree.h @@ -299,7 +299,7 @@ namespace gtsam { this->keys_.assign(clique->conditional()->beginParents(), clique->conditional()->endParents()); } - void print(const std::string& s="", const KeyFormatter& formatter = DefaultKeyFormatter) const { + void print(const std::string& s="", const KeyFormatter& formatter = DefaultKeyFormatter) const override { clique->print(s + "stored clique", formatter); } }; diff --git a/gtsam/inference/BayesTreeCliqueBase.h b/gtsam/inference/BayesTreeCliqueBase.h index 6266e961c..7aca84635 100644 --- a/gtsam/inference/BayesTreeCliqueBase.h +++ b/gtsam/inference/BayesTreeCliqueBase.h @@ -100,7 +100,7 @@ namespace gtsam { bool equals(const DERIVED& other, double tol = 1e-9) const; /** print this node */ - void print(const std::string& s = "", const KeyFormatter& keyFormatter = DefaultKeyFormatter) const; + virtual void print(const std::string& s = "", const KeyFormatter& keyFormatter = DefaultKeyFormatter) const; /// @} /// @name Standard Interface diff --git a/gtsam/inference/inferenceExceptions.h b/gtsam/inference/inferenceExceptions.h index edd0e0aa5..4409b16c7 100644 --- a/gtsam/inference/inferenceExceptions.h +++ b/gtsam/inference/inferenceExceptions.h @@ -28,9 +28,9 @@ namespace gtsam { * with an ordering that does not include all of the variables. */ class InconsistentEliminationRequested : public std::exception { public: - InconsistentEliminationRequested() throw() {} - virtual ~InconsistentEliminationRequested() throw() {} - virtual const char* what() const throw() { + InconsistentEliminationRequested() noexcept {} + virtual ~InconsistentEliminationRequested() noexcept {} + const char* what() const noexcept override { return "An inference algorithm was called with inconsistent arguments. The\n" "factor graph, ordering, or variable index were inconsistent with each\n" diff --git a/gtsam/linear/BinaryJacobianFactor.h b/gtsam/linear/BinaryJacobianFactor.h index 343548613..8b53c34dd 100644 --- a/gtsam/linear/BinaryJacobianFactor.h +++ b/gtsam/linear/BinaryJacobianFactor.h @@ -49,7 +49,7 @@ struct BinaryJacobianFactor: JacobianFactor { // Fixed-size matrix update void updateHessian(const KeyVector& infoKeys, - SymmetricBlockMatrix* info) const { + SymmetricBlockMatrix* info) const override { gttic(updateHessian_BinaryJacobianFactor); // Whiten the factor if it has a noise model const SharedDiagonal& model = get_model(); diff --git a/gtsam/linear/ConjugateGradientSolver.h b/gtsam/linear/ConjugateGradientSolver.h index 2596a7403..c92390491 100644 --- a/gtsam/linear/ConjugateGradientSolver.h +++ b/gtsam/linear/ConjugateGradientSolver.h @@ -80,7 +80,7 @@ public: void print() const { Base::print(); } - virtual void print(std::ostream &os) const; + void print(std::ostream &os) const override; static std::string blasTranslator(const BLASKernel k) ; static BLASKernel blasTranslator(const std::string &s) ; diff --git a/gtsam/linear/GaussianConditional.h b/gtsam/linear/GaussianConditional.h index 8b41a4def..fdbe511f8 100644 --- a/gtsam/linear/GaussianConditional.h +++ b/gtsam/linear/GaussianConditional.h @@ -88,10 +88,10 @@ namespace gtsam { /** print */ void print(const std::string& = "GaussianConditional", - const KeyFormatter& formatter = DefaultKeyFormatter) const; + const KeyFormatter& formatter = DefaultKeyFormatter) const override; /** equals function */ - bool equals(const GaussianFactor&cg, double tol = 1e-9) const; + bool equals(const GaussianFactor&cg, double tol = 1e-9) const override; /** Return a view of the upper-triangular R block of the conditional */ constABlock R() const { return Ab_.range(0, nrFrontals()); } diff --git a/gtsam/linear/GaussianDensity.h b/gtsam/linear/GaussianDensity.h index 03ffe9326..71af704ab 100644 --- a/gtsam/linear/GaussianDensity.h +++ b/gtsam/linear/GaussianDensity.h @@ -57,7 +57,7 @@ namespace gtsam { /// print void print(const std::string& = "GaussianDensity", - const KeyFormatter& formatter = DefaultKeyFormatter) const; + const KeyFormatter& formatter = DefaultKeyFormatter) const override; /// Mean \f$ \mu = R^{-1} d \f$ Vector mean() const; diff --git a/gtsam/linear/LossFunctions.h b/gtsam/linear/LossFunctions.h index 6a5dc5a26..a126b37db 100644 --- a/gtsam/linear/LossFunctions.h +++ b/gtsam/linear/LossFunctions.h @@ -134,10 +134,10 @@ class GTSAM_EXPORT Null : public Base { Null(const ReweightScheme reweight = Block) : Base(reweight) {} ~Null() {} - double weight(double /*error*/) const { return 1.0; } - double loss(double distance) const { return 0.5 * distance * distance; } - void print(const std::string &s) const; - bool equals(const Base & /*expected*/, double /*tol*/) const { return true; } + double weight(double /*error*/) const override { return 1.0; } + double loss(double distance) const override { return 0.5 * distance * distance; } + void print(const std::string &s) const override; + bool equals(const Base & /*expected*/, double /*tol*/) const override { return true; } static shared_ptr Create(); private: diff --git a/gtsam/linear/PCGSolver.h b/gtsam/linear/PCGSolver.h index 7752902ba..515f2eed2 100644 --- a/gtsam/linear/PCGSolver.h +++ b/gtsam/linear/PCGSolver.h @@ -41,7 +41,7 @@ public: PCGSolverParameters() { } - virtual void print(std::ostream &os) const; + void print(std::ostream &os) const override; /* interface to preconditioner parameters */ inline const PreconditionerParameters& preconditioner() const { @@ -77,9 +77,9 @@ public: using IterativeSolver::optimize; - virtual VectorValues optimize(const GaussianFactorGraph &gfg, + VectorValues optimize(const GaussianFactorGraph &gfg, const KeyInfo &keyInfo, const std::map &lambda, - const VectorValues &initial); + const VectorValues &initial) override; }; diff --git a/gtsam/linear/Preconditioner.h b/gtsam/linear/Preconditioner.h index 31901db3f..eceb19982 100644 --- a/gtsam/linear/Preconditioner.h +++ b/gtsam/linear/Preconditioner.h @@ -111,13 +111,13 @@ public: virtual ~DummyPreconditioner() {} /* Computation Interfaces for raw vector */ - virtual void solve(const Vector& y, Vector &x) const { x = y; } - virtual void transposeSolve(const Vector& y, Vector& x) const { x = y; } - virtual void build( + void solve(const Vector& y, Vector &x) const override { x = y; } + void transposeSolve(const Vector& y, Vector& x) const override { x = y; } + void build( const GaussianFactorGraph &gfg, const KeyInfo &info, const std::map &lambda - ) {} + ) override {} }; /*******************************************************************************************/ @@ -135,13 +135,13 @@ public: virtual ~BlockJacobiPreconditioner() ; /* Computation Interfaces for raw vector */ - virtual void solve(const Vector& y, Vector &x) const; - virtual void transposeSolve(const Vector& y, Vector& x) const ; - virtual void build( + void solve(const Vector& y, Vector &x) const override; + void transposeSolve(const Vector& y, Vector& x) const override; + void build( const GaussianFactorGraph &gfg, const KeyInfo &info, const std::map &lambda - ) ; + ) override; protected: diff --git a/gtsam/linear/RegularHessianFactor.h b/gtsam/linear/RegularHessianFactor.h index a24acfacd..707f519ca 100644 --- a/gtsam/linear/RegularHessianFactor.h +++ b/gtsam/linear/RegularHessianFactor.h @@ -109,8 +109,8 @@ private: public: /** y += alpha * A'*A*x */ - virtual void multiplyHessianAdd(double alpha, const VectorValues& x, - VectorValues& y) const { + void multiplyHessianAdd(double alpha, const VectorValues& x, + VectorValues& y) const override { HessianFactor::multiplyHessianAdd(alpha, x, y); } @@ -182,7 +182,7 @@ public: } /** Return the diagonal of the Hessian for this factor (raw memory version) */ - virtual void hessianDiagonal(double* d) const { + void hessianDiagonal(double* d) const override { // Loop over all variables in the factor for (DenseIndex pos = 0; pos < (DenseIndex) size(); ++pos) { @@ -193,7 +193,7 @@ public: } /// Add gradient at zero to d TODO: is it really the goal to add ?? - virtual void gradientAtZero(double* d) const { + void gradientAtZero(double* d) const override { // Loop over all variables in the factor for (DenseIndex pos = 0; pos < (DenseIndex) size(); ++pos) { diff --git a/gtsam/linear/RegularJacobianFactor.h b/gtsam/linear/RegularJacobianFactor.h index 0312efe78..1c465da03 100644 --- a/gtsam/linear/RegularJacobianFactor.h +++ b/gtsam/linear/RegularJacobianFactor.h @@ -70,8 +70,8 @@ public: using JacobianFactor::multiplyHessianAdd; /** y += alpha * A'*A*x */ - virtual void multiplyHessianAdd(double alpha, const VectorValues& x, - VectorValues& y) const { + void multiplyHessianAdd(double alpha, const VectorValues& x, + VectorValues& y) const override { JacobianFactor::multiplyHessianAdd(alpha, x, y); } @@ -106,7 +106,7 @@ public: using GaussianFactor::hessianDiagonal; /// Raw memory access version of hessianDiagonal - void hessianDiagonal(double* d) const { + void hessianDiagonal(double* d) const override { // Loop over all variables in the factor for (DenseIndex j = 0; j < (DenseIndex) size(); ++j) { // Get the diagonal block, and insert its diagonal @@ -125,12 +125,12 @@ public: } /// Expose base class gradientAtZero - virtual VectorValues gradientAtZero() const { + VectorValues gradientAtZero() const override { return JacobianFactor::gradientAtZero(); } /// Raw memory access version of gradientAtZero - void gradientAtZero(double* d) const { + void gradientAtZero(double* d) const override { // Get vector b not weighted Vector b = getb(); diff --git a/gtsam/linear/SubgraphSolver.h b/gtsam/linear/SubgraphSolver.h index 5ab1a8520..0f7eea06f 100644 --- a/gtsam/linear/SubgraphSolver.h +++ b/gtsam/linear/SubgraphSolver.h @@ -38,7 +38,7 @@ struct GTSAM_EXPORT SubgraphSolverParameters explicit SubgraphSolverParameters(const SubgraphBuilderParameters &p = SubgraphBuilderParameters()) : builderParams(p) {} void print() const { Base::print(); } - virtual void print(std::ostream &os) const { + void print(std::ostream &os) const override { Base::print(os); } }; diff --git a/gtsam/linear/linearExceptions.cpp b/gtsam/linear/linearExceptions.cpp index a4168af2d..ada3a298c 100644 --- a/gtsam/linear/linearExceptions.cpp +++ b/gtsam/linear/linearExceptions.cpp @@ -24,7 +24,7 @@ namespace gtsam { /* ************************************************************************* */ - const char* IndeterminantLinearSystemException::what() const throw() + const char* IndeterminantLinearSystemException::what() const noexcept { if(!description_) { description_ = String( @@ -43,7 +43,7 @@ more information."); } /* ************************************************************************* */ - const char* InvalidNoiseModel::what() const throw() { + const char* InvalidNoiseModel::what() const noexcept { if(description_.empty()) description_ = (boost::format( "A JacobianFactor was attempted to be constructed or modified to use a\n" @@ -54,7 +54,7 @@ more information."); } /* ************************************************************************* */ - const char* InvalidMatrixBlock::what() const throw() { + const char* InvalidMatrixBlock::what() const noexcept { if(description_.empty()) description_ = (boost::format( "A JacobianFactor was attempted to be constructed with a matrix block of\n" diff --git a/gtsam/linear/linearExceptions.h b/gtsam/linear/linearExceptions.h index 32db27fc9..f0ad0be39 100644 --- a/gtsam/linear/linearExceptions.h +++ b/gtsam/linear/linearExceptions.h @@ -94,10 +94,10 @@ namespace gtsam { class GTSAM_EXPORT IndeterminantLinearSystemException : public ThreadsafeException { Key j_; public: - IndeterminantLinearSystemException(Key j) throw() : j_(j) {} - virtual ~IndeterminantLinearSystemException() throw() {} + IndeterminantLinearSystemException(Key j) noexcept : j_(j) {} + virtual ~IndeterminantLinearSystemException() noexcept {} Key nearbyVariable() const { return j_; } - virtual const char* what() const throw(); + const char* what() const noexcept override; }; /* ************************************************************************* */ @@ -110,9 +110,9 @@ namespace gtsam { InvalidNoiseModel(DenseIndex factorDims, DenseIndex noiseModelDims) : factorDims(factorDims), noiseModelDims(noiseModelDims) {} - virtual ~InvalidNoiseModel() throw() {} + virtual ~InvalidNoiseModel() noexcept {} - virtual const char* what() const throw(); + const char* what() const noexcept override; private: mutable std::string description_; @@ -128,9 +128,9 @@ namespace gtsam { InvalidMatrixBlock(DenseIndex factorRows, DenseIndex blockRows) : factorRows(factorRows), blockRows(blockRows) {} - virtual ~InvalidMatrixBlock() throw() {} + virtual ~InvalidMatrixBlock() noexcept {} - virtual const char* what() const throw(); + const char* what() const noexcept override; private: mutable std::string description_; diff --git a/gtsam/navigation/AHRSFactor.h b/gtsam/navigation/AHRSFactor.h index 1418ab687..c3765b8cf 100644 --- a/gtsam/navigation/AHRSFactor.h +++ b/gtsam/navigation/AHRSFactor.h @@ -158,14 +158,14 @@ public: } /// @return a deep copy of this factor - virtual gtsam::NonlinearFactor::shared_ptr clone() const; + gtsam::NonlinearFactor::shared_ptr clone() const override; /// print - virtual void print(const std::string& s, const KeyFormatter& keyFormatter = - DefaultKeyFormatter) const; + void print(const std::string& s, const KeyFormatter& keyFormatter = + DefaultKeyFormatter) const override; /// equals - virtual bool equals(const NonlinearFactor&, double tol = 1e-9) const; + bool equals(const NonlinearFactor&, double tol = 1e-9) const override; /// Access the preintegrated measurements. const PreintegratedAhrsMeasurements& preintegratedMeasurements() const { @@ -178,7 +178,7 @@ public: Vector evaluateError(const Rot3& rot_i, const Rot3& rot_j, const Vector3& bias, boost::optional H1 = boost::none, boost::optional H2 = boost::none, boost::optional H3 = - boost::none) const; + boost::none) const override; /// predicted states from IMU /// TODO(frank): relationship with PIM predict ?? diff --git a/gtsam/navigation/AttitudeFactor.h b/gtsam/navigation/AttitudeFactor.h index 5a0031caf..9a0a11cfb 100644 --- a/gtsam/navigation/AttitudeFactor.h +++ b/gtsam/navigation/AttitudeFactor.h @@ -108,21 +108,21 @@ public: } /// @return a deep copy of this factor - virtual gtsam::NonlinearFactor::shared_ptr clone() const { + gtsam::NonlinearFactor::shared_ptr clone() const override { return boost::static_pointer_cast( gtsam::NonlinearFactor::shared_ptr(new This(*this))); } /** print */ - virtual void print(const std::string& s, const KeyFormatter& keyFormatter = - DefaultKeyFormatter) const; + void print(const std::string& s, const KeyFormatter& keyFormatter = + DefaultKeyFormatter) const override; /** equals */ - virtual bool equals(const NonlinearFactor& expected, double tol = 1e-9) const; + bool equals(const NonlinearFactor& expected, double tol = 1e-9) const override; /** vector of errors */ - virtual Vector evaluateError(const Rot3& nRb, // - boost::optional H = boost::none) const { + Vector evaluateError(const Rot3& nRb, // + boost::optional H = boost::none) const override { return attitudeError(nRb, H); } @@ -182,21 +182,21 @@ public: } /// @return a deep copy of this factor - virtual gtsam::NonlinearFactor::shared_ptr clone() const { + gtsam::NonlinearFactor::shared_ptr clone() const override { return boost::static_pointer_cast( gtsam::NonlinearFactor::shared_ptr(new This(*this))); } /** print */ - virtual void print(const std::string& s, const KeyFormatter& keyFormatter = - DefaultKeyFormatter) const; + void print(const std::string& s, const KeyFormatter& keyFormatter = + DefaultKeyFormatter) const override; /** equals */ - virtual bool equals(const NonlinearFactor& expected, double tol = 1e-9) const; + bool equals(const NonlinearFactor& expected, double tol = 1e-9) const override; /** vector of errors */ - virtual Vector evaluateError(const Pose3& nTb, // - boost::optional H = boost::none) const { + Vector evaluateError(const Pose3& nTb, // + boost::optional H = boost::none) const override { Vector e = attitudeError(nTb.rotation(), H); if (H) { Matrix H23 = *H; diff --git a/gtsam/navigation/CombinedImuFactor.h b/gtsam/navigation/CombinedImuFactor.h index a89568433..6181f3d0d 100644 --- a/gtsam/navigation/CombinedImuFactor.h +++ b/gtsam/navigation/CombinedImuFactor.h @@ -87,8 +87,8 @@ struct GTSAM_EXPORT PreintegrationCombinedParams : PreintegrationParams { return boost::shared_ptr(new PreintegrationCombinedParams(Vector3(0, 0, -g))); } - void print(const std::string& s="") const; - bool equals(const PreintegratedRotationParams& other, double tol) const; + void print(const std::string& s="") const override; + bool equals(const PreintegratedRotationParams& other, double tol) const override; void setBiasAccCovariance(const Matrix3& cov) { biasAccCovariance=cov; } void setBiasOmegaCovariance(const Matrix3& cov) { biasOmegaCovariance=cov; } @@ -305,7 +305,7 @@ public: virtual ~CombinedImuFactor() {} /// @return a deep copy of this factor - virtual gtsam::NonlinearFactor::shared_ptr clone() const; + gtsam::NonlinearFactor::shared_ptr clone() const override; /** implement functions needed for Testable */ @@ -314,11 +314,11 @@ public: GTSAM_EXPORT friend std::ostream& operator<<(std::ostream& os, const CombinedImuFactor&); /// print - virtual void print(const std::string& s, const KeyFormatter& keyFormatter = - DefaultKeyFormatter) const; + void print(const std::string& s, const KeyFormatter& keyFormatter = + DefaultKeyFormatter) const override; /// equals - virtual bool equals(const NonlinearFactor& expected, double tol = 1e-9) const; + bool equals(const NonlinearFactor& expected, double tol = 1e-9) const override; /// @} /** Access the preintegrated measurements. */ @@ -336,7 +336,7 @@ public: boost::optional H1 = boost::none, boost::optional H2 = boost::none, boost::optional H3 = boost::none, boost::optional H4 = boost::none, boost::optional H5 = - boost::none, boost::optional H6 = boost::none) const; + boost::none, boost::optional H6 = boost::none) const override; #ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V4 /// @deprecated typename diff --git a/gtsam/navigation/GPSFactor.h b/gtsam/navigation/GPSFactor.h index 2b5ea1f2f..e6d5b88a9 100644 --- a/gtsam/navigation/GPSFactor.h +++ b/gtsam/navigation/GPSFactor.h @@ -65,21 +65,21 @@ public: } /// @return a deep copy of this factor - virtual gtsam::NonlinearFactor::shared_ptr clone() const { + gtsam::NonlinearFactor::shared_ptr clone() const override { return boost::static_pointer_cast( gtsam::NonlinearFactor::shared_ptr(new This(*this))); } /// print - virtual void print(const std::string& s, const KeyFormatter& keyFormatter = - DefaultKeyFormatter) const; + void print(const std::string& s, const KeyFormatter& keyFormatter = + DefaultKeyFormatter) const override; /// equals - virtual bool equals(const NonlinearFactor& expected, double tol = 1e-9) const; + bool equals(const NonlinearFactor& expected, double tol = 1e-9) const override; /// vector of errors Vector evaluateError(const Pose3& p, - boost::optional H = boost::none) const; + boost::optional H = boost::none) const override; inline const Point3 & measurementIn() const { return nT_; @@ -137,21 +137,21 @@ public: } /// @return a deep copy of this factor - virtual gtsam::NonlinearFactor::shared_ptr clone() const { + gtsam::NonlinearFactor::shared_ptr clone() const override { return boost::static_pointer_cast( gtsam::NonlinearFactor::shared_ptr(new This(*this))); } /// print - virtual void print(const std::string& s, const KeyFormatter& keyFormatter = - DefaultKeyFormatter) const; + void print(const std::string& s, const KeyFormatter& keyFormatter = + DefaultKeyFormatter) const override; /// equals - virtual bool equals(const NonlinearFactor& expected, double tol = 1e-9) const; + bool equals(const NonlinearFactor& expected, double tol = 1e-9) const override; /// vector of errors Vector evaluateError(const NavState& p, - boost::optional H = boost::none) const; + boost::optional H = boost::none) const override; inline const Point3 & measurementIn() const { return nT_; diff --git a/gtsam/navigation/ImuFactor.h b/gtsam/navigation/ImuFactor.h index 7e080ffd5..65142af24 100644 --- a/gtsam/navigation/ImuFactor.h +++ b/gtsam/navigation/ImuFactor.h @@ -217,14 +217,14 @@ public: } /// @return a deep copy of this factor - virtual gtsam::NonlinearFactor::shared_ptr clone() const; + gtsam::NonlinearFactor::shared_ptr clone() const override; /// @name Testable /// @{ GTSAM_EXPORT friend std::ostream& operator<<(std::ostream& os, const ImuFactor&); - virtual void print(const std::string& s, const KeyFormatter& keyFormatter = - DefaultKeyFormatter) const; - virtual bool equals(const NonlinearFactor& expected, double tol = 1e-9) const; + void print(const std::string& s, const KeyFormatter& keyFormatter = + DefaultKeyFormatter) const override; + bool equals(const NonlinearFactor& expected, double tol = 1e-9) const override; /// @} /** Access the preintegrated measurements. */ @@ -241,7 +241,7 @@ public: const imuBias::ConstantBias& bias_i, boost::optional H1 = boost::none, boost::optional H2 = boost::none, boost::optional H3 = boost::none, boost::optional H4 = - boost::none, boost::optional H5 = boost::none) const; + boost::none, boost::optional H5 = boost::none) const override; #ifdef GTSAM_TANGENT_PREINTEGRATION /// Merge two pre-integrated measurement classes @@ -315,14 +315,14 @@ public: } /// @return a deep copy of this factor - virtual gtsam::NonlinearFactor::shared_ptr clone() const; + gtsam::NonlinearFactor::shared_ptr clone() const override; /// @name Testable /// @{ GTSAM_EXPORT friend std::ostream& operator<<(std::ostream& os, const ImuFactor2&); - virtual void print(const std::string& s, const KeyFormatter& keyFormatter = - DefaultKeyFormatter) const; - virtual bool equals(const NonlinearFactor& expected, double tol = 1e-9) const; + void print(const std::string& s, const KeyFormatter& keyFormatter = + DefaultKeyFormatter) const override; + bool equals(const NonlinearFactor& expected, double tol = 1e-9) const override; /// @} /** Access the preintegrated measurements. */ @@ -338,7 +338,7 @@ public: const imuBias::ConstantBias& bias_i, // boost::optional H1 = boost::none, boost::optional H2 = boost::none, - boost::optional H3 = boost::none) const; + boost::optional H3 = boost::none) const override; private: diff --git a/gtsam/navigation/MagFactor.h b/gtsam/navigation/MagFactor.h index 3875391d0..97a4c70ce 100644 --- a/gtsam/navigation/MagFactor.h +++ b/gtsam/navigation/MagFactor.h @@ -53,7 +53,7 @@ public: } /// @return a deep copy of this factor - virtual NonlinearFactor::shared_ptr clone() const { + NonlinearFactor::shared_ptr clone() const override { return boost::static_pointer_cast( NonlinearFactor::shared_ptr(new MagFactor(*this))); } @@ -102,7 +102,7 @@ public: } /// @return a deep copy of this factor - virtual NonlinearFactor::shared_ptr clone() const { + NonlinearFactor::shared_ptr clone() const override { return boost::static_pointer_cast( NonlinearFactor::shared_ptr(new MagFactor1(*this))); } @@ -138,7 +138,7 @@ public: } /// @return a deep copy of this factor - virtual NonlinearFactor::shared_ptr clone() const { + NonlinearFactor::shared_ptr clone() const override { return boost::static_pointer_cast( NonlinearFactor::shared_ptr(new MagFactor2(*this))); } @@ -179,7 +179,7 @@ public: } /// @return a deep copy of this factor - virtual NonlinearFactor::shared_ptr clone() const { + NonlinearFactor::shared_ptr clone() const override { return boost::static_pointer_cast( NonlinearFactor::shared_ptr(new MagFactor3(*this))); } diff --git a/gtsam/navigation/PreintegrationParams.h b/gtsam/navigation/PreintegrationParams.h index 9ae66e678..ce1f0e734 100644 --- a/gtsam/navigation/PreintegrationParams.h +++ b/gtsam/navigation/PreintegrationParams.h @@ -56,8 +56,8 @@ struct GTSAM_EXPORT PreintegrationParams: PreintegratedRotationParams { return boost::shared_ptr(new PreintegrationParams(Vector3(0, 0, -g))); } - void print(const std::string& s="") const; - bool equals(const PreintegratedRotationParams& other, double tol) const; + void print(const std::string& s="") const override; + bool equals(const PreintegratedRotationParams& other, double tol) const override; void setAccelerometerCovariance(const Matrix3& cov) { accelerometerCovariance = cov; } void setIntegrationCovariance(const Matrix3& cov) { integrationCovariance = cov; } diff --git a/gtsam/nonlinear/ExpressionFactor.h b/gtsam/nonlinear/ExpressionFactor.h index c42b2bdfc..2e78aafe2 100644 --- a/gtsam/nonlinear/ExpressionFactor.h +++ b/gtsam/nonlinear/ExpressionFactor.h @@ -68,13 +68,13 @@ protected: /// print relies on Testable traits being defined for T void print(const std::string& s = "", - const KeyFormatter& keyFormatter = DefaultKeyFormatter) const { + const KeyFormatter& keyFormatter = DefaultKeyFormatter) const override { NoiseModelFactor::print(s, keyFormatter); traits::Print(measured_, "ExpressionFactor with measurement: "); } /// equals relies on Testable traits being defined for T - bool equals(const NonlinearFactor& f, double tol) const { + bool equals(const NonlinearFactor& f, double tol) const override { const ExpressionFactor* p = dynamic_cast(&f); return p && NoiseModelFactor::equals(f, tol) && traits::Equals(measured_, p->measured_, tol) && @@ -86,8 +86,8 @@ protected: * We override this method to provide * both the function evaluation and its derivative(s) in H. */ - virtual Vector unwhitenedError(const Values& x, - boost::optional&> H = boost::none) const { + Vector unwhitenedError(const Values& x, + boost::optional&> H = boost::none) const override { if (H) { const T value = expression_.valueAndDerivatives(x, keys_, dims_, *H); // NOTE(hayk): Doing the reverse, AKA Local(measured_, value) is not correct here @@ -99,7 +99,7 @@ protected: } } - virtual boost::shared_ptr linearize(const Values& x) const { + boost::shared_ptr linearize(const Values& x) const override { // Only linearize if the factor is active if (!active(x)) return boost::shared_ptr(); @@ -138,7 +138,7 @@ protected: } /// @return a deep copy of this factor - virtual gtsam::NonlinearFactor::shared_ptr clone() const { + gtsam::NonlinearFactor::shared_ptr clone() const override { return boost::static_pointer_cast( gtsam::NonlinearFactor::shared_ptr(new This(*this))); } @@ -263,7 +263,7 @@ class ExpressionFactor2 : public ExpressionFactor { private: /// Return an expression that predicts the measurement given Values - virtual Expression expression() const { + Expression expression() const override { return expression(this->keys_[0], this->keys_[1]); } diff --git a/gtsam/nonlinear/FunctorizedFactor.h b/gtsam/nonlinear/FunctorizedFactor.h index 5351b126f..688b3aaa2 100644 --- a/gtsam/nonlinear/FunctorizedFactor.h +++ b/gtsam/nonlinear/FunctorizedFactor.h @@ -82,13 +82,13 @@ class GTSAM_EXPORT FunctorizedFactor : public NoiseModelFactor1 { virtual ~FunctorizedFactor() {} /// @return a deep copy of this factor - virtual NonlinearFactor::shared_ptr clone() const { + NonlinearFactor::shared_ptr clone() const override { return boost::static_pointer_cast( NonlinearFactor::shared_ptr(new FunctorizedFactor(*this))); } Vector evaluateError(const T ¶ms, - boost::optional H = boost::none) const { + boost::optional H = boost::none) const override { R x = func_(params, H); Vector error = traits::Local(measured_, x); return error; @@ -97,7 +97,7 @@ class GTSAM_EXPORT FunctorizedFactor : public NoiseModelFactor1 { /// @name Testable /// @{ void print(const std::string &s = "", - const KeyFormatter &keyFormatter = DefaultKeyFormatter) const { + const KeyFormatter &keyFormatter = DefaultKeyFormatter) const override { Base::print(s, keyFormatter); std::cout << s << (s != "" ? " " : "") << "FunctorizedFactor(" << keyFormatter(this->key()) << ")" << std::endl; @@ -106,7 +106,7 @@ class GTSAM_EXPORT FunctorizedFactor : public NoiseModelFactor1 { << std::endl; } - virtual bool equals(const NonlinearFactor &other, double tol = 1e-9) const { + bool equals(const NonlinearFactor &other, double tol = 1e-9) const override { const FunctorizedFactor *e = dynamic_cast *>(&other); return e && Base::equals(other, tol) && diff --git a/gtsam/nonlinear/ISAM2Clique.h b/gtsam/nonlinear/ISAM2Clique.h index 53bdaec81..467741d66 100644 --- a/gtsam/nonlinear/ISAM2Clique.h +++ b/gtsam/nonlinear/ISAM2Clique.h @@ -85,7 +85,7 @@ class GTSAM_EXPORT ISAM2Clique /** print this node */ void print(const std::string& s = "", - const KeyFormatter& formatter = DefaultKeyFormatter) const; + const KeyFormatter& formatter = DefaultKeyFormatter) const override; void optimizeWildfire(const KeySet& replaced, double threshold, KeySet* changed, VectorValues* delta, diff --git a/gtsam/nonlinear/LinearContainerFactor.h b/gtsam/nonlinear/LinearContainerFactor.h index 8a1f600ff..4540117b6 100644 --- a/gtsam/nonlinear/LinearContainerFactor.h +++ b/gtsam/nonlinear/LinearContainerFactor.h @@ -59,10 +59,10 @@ public: // Testable /** print */ - GTSAM_EXPORT void print(const std::string& s = "", const KeyFormatter& keyFormatter = gtsam::DefaultKeyFormatter) const; + GTSAM_EXPORT void print(const std::string& s = "", const KeyFormatter& keyFormatter = gtsam::DefaultKeyFormatter) const override; /** Check if two factors are equal */ - GTSAM_EXPORT bool equals(const NonlinearFactor& f, double tol = 1e-9) const; + GTSAM_EXPORT bool equals(const NonlinearFactor& f, double tol = 1e-9) const override; // NonlinearFactor @@ -74,10 +74,10 @@ public: * * @return nonlinear error if linearizationPoint present, zero otherwise */ - GTSAM_EXPORT double error(const Values& c) const; + GTSAM_EXPORT double error(const Values& c) const override; /** get the dimension of the factor: rows of linear factor */ - GTSAM_EXPORT size_t dim() const; + GTSAM_EXPORT size_t dim() const override; /** Extract the linearization point used in recalculating error */ const boost::optional& linearizationPoint() const { return linearizationPoint_; } @@ -98,7 +98,7 @@ public: * TODO: better approximation of relinearization * TODO: switchable modes for approximation technique */ - GTSAM_EXPORT GaussianFactor::shared_ptr linearize(const Values& c) const; + GTSAM_EXPORT GaussianFactor::shared_ptr linearize(const Values& c) const override; /** * Creates an anti-factor directly @@ -116,7 +116,7 @@ public: * * Clones the underlying linear factor */ - NonlinearFactor::shared_ptr clone() const { + NonlinearFactor::shared_ptr clone() const override { return NonlinearFactor::shared_ptr(new LinearContainerFactor(factor_,linearizationPoint_)); } diff --git a/gtsam/nonlinear/NonlinearEquality.h b/gtsam/nonlinear/NonlinearEquality.h index 1bba57051..6286b73da 100644 --- a/gtsam/nonlinear/NonlinearEquality.h +++ b/gtsam/nonlinear/NonlinearEquality.h @@ -107,15 +107,15 @@ public: /// @name Testable /// @{ - virtual void print(const std::string& s = "", - const KeyFormatter& keyFormatter = DefaultKeyFormatter) const { + void print(const std::string& s = "", + const KeyFormatter& keyFormatter = DefaultKeyFormatter) const override { std::cout << s << "Constraint: on [" << keyFormatter(this->key()) << "]\n"; traits::Print(feasible_, "Feasible Point:\n"); std::cout << "Variable Dimension: " << traits::GetDimension(feasible_) << std::endl; } /** Check if two factors are equal */ - virtual bool equals(const NonlinearFactor& f, double tol = 1e-9) const { + bool equals(const NonlinearFactor& f, double tol = 1e-9) const override { const This* e = dynamic_cast(&f); return e && Base::equals(f) && traits::Equals(feasible_,e->feasible_, tol) && std::abs(error_gain_ - e->error_gain_) < tol; @@ -126,7 +126,7 @@ public: /// @{ /** actual error function calculation */ - virtual double error(const Values& c) const { + double error(const Values& c) const override { const T& xj = c.at(this->key()); Vector e = this->unwhitenedError(c); if (allow_error_ || !compare_(xj, feasible_)) { @@ -138,7 +138,7 @@ public: /** error function */ Vector evaluateError(const T& xj, - boost::optional H = boost::none) const { + boost::optional H = boost::none) const override { const size_t nj = traits::GetDimension(feasible_); if (allow_error_) { if (H) @@ -158,7 +158,7 @@ public: } // Linearize is over-written, because base linearization tries to whiten - virtual GaussianFactor::shared_ptr linearize(const Values& x) const { + GaussianFactor::shared_ptr linearize(const Values& x) const override { const T& xj = x.at(this->key()); Matrix A; Vector b = evaluateError(xj, A); @@ -168,7 +168,7 @@ public: } /// @return a deep copy of this factor - virtual gtsam::NonlinearFactor::shared_ptr clone() const { + gtsam::NonlinearFactor::shared_ptr clone() const override { return boost::static_pointer_cast( gtsam::NonlinearFactor::shared_ptr(new This(*this))); } @@ -242,14 +242,14 @@ public: } /// @return a deep copy of this factor - virtual gtsam::NonlinearFactor::shared_ptr clone() const { + gtsam::NonlinearFactor::shared_ptr clone() const override { return boost::static_pointer_cast( gtsam::NonlinearFactor::shared_ptr(new This(*this))); } /** g(x) with optional derivative */ Vector evaluateError(const X& x1, - boost::optional H = boost::none) const { + boost::optional H = boost::none) const override { if (H) (*H) = Matrix::Identity(traits::GetDimension(x1),traits::GetDimension(x1)); // manifold equivalent of h(x)-z -> log(z,h(x)) @@ -257,8 +257,8 @@ public: } /** Print */ - virtual void print(const std::string& s = "", - const KeyFormatter& keyFormatter = DefaultKeyFormatter) const { + void print(const std::string& s = "", + const KeyFormatter& keyFormatter = DefaultKeyFormatter) const override { std::cout << s << ": NonlinearEquality1(" << keyFormatter(this->key()) << ")," << "\n"; this->noiseModel_->print(); @@ -317,14 +317,14 @@ public: } /// @return a deep copy of this factor - virtual gtsam::NonlinearFactor::shared_ptr clone() const { + gtsam::NonlinearFactor::shared_ptr clone() const override { return boost::static_pointer_cast( gtsam::NonlinearFactor::shared_ptr(new This(*this))); } /** g(x) with optional derivative2 */ Vector evaluateError(const X& x1, const X& x2, boost::optional H1 = - boost::none, boost::optional H2 = boost::none) const { + boost::none, boost::optional H2 = boost::none) const override { static const size_t p = traits::dimension; if (H1) *H1 = -Matrix::Identity(p,p); if (H2) *H2 = Matrix::Identity(p,p); diff --git a/gtsam/nonlinear/NonlinearFactor.h b/gtsam/nonlinear/NonlinearFactor.h index 63547a248..7bbd51236 100644 --- a/gtsam/nonlinear/NonlinearFactor.h +++ b/gtsam/nonlinear/NonlinearFactor.h @@ -31,7 +31,7 @@ #ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V4 #define ADD_CLONE_NONLINEAR_FACTOR(Derived) \ - virtual gtsam::NonlinearFactor::shared_ptr clone() const { \ + gtsam::NonlinearFactor::shared_ptr clone() const override { \ return boost::static_pointer_cast( \ gtsam::NonlinearFactor::shared_ptr(new Derived(*this))); } #endif @@ -195,14 +195,14 @@ protected: public: /** Print */ - virtual void print(const std::string& s = "", - const KeyFormatter& keyFormatter = DefaultKeyFormatter) const; + void print(const std::string& s = "", + const KeyFormatter& keyFormatter = DefaultKeyFormatter) const override; /** Check if two factors are equal */ - virtual bool equals(const NonlinearFactor& f, double tol = 1e-9) const; + bool equals(const NonlinearFactor& f, double tol = 1e-9) const override; /** get the dimension of the factor (number of rows on linearization) */ - virtual size_t dim() const { + size_t dim() const override { return noiseModel_->dim(); } @@ -242,14 +242,14 @@ public: * In this class, we take the raw prediction error \f$ h(x)-z \f$, ask the noise model * to transform it to \f$ (h(x)-z)^2/\sigma^2 \f$, and then multiply by 0.5. */ - virtual double error(const Values& c) const; + double error(const Values& c) const override; /** * Linearize a non-linearFactorN to get a GaussianFactor, * \f$ Ax-b \approx h(x+\delta x)-z = h(x) + A \delta x - z \f$ * Hence \f$ b = z - h(x) = - \mathtt{error\_vector}(x) \f$ */ - boost::shared_ptr linearize(const Values& x) const; + boost::shared_ptr linearize(const Values& x) const override; #ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V4 /// @name Deprecated @@ -315,7 +315,7 @@ public: /** Calls the 1-key specific version of evaluateError, which is pure virtual * so must be implemented in the derived class. */ - virtual Vector unwhitenedError(const Values& x, boost::optional&> H = boost::none) const { + Vector unwhitenedError(const Values& x, boost::optional&> H = boost::none) const override { if(this->active(x)) { const X& x1 = x.at(keys_[0]); if(H) { @@ -389,7 +389,7 @@ public: /** Calls the 2-key specific version of evaluateError, which is pure virtual * so must be implemented in the derived class. */ - virtual Vector unwhitenedError(const Values& x, boost::optional&> H = boost::none) const { + Vector unwhitenedError(const Values& x, boost::optional&> H = boost::none) const override { if(this->active(x)) { const X1& x1 = x.at(keys_[0]); const X2& x2 = x.at(keys_[1]); @@ -467,7 +467,7 @@ public: /** Calls the 3-key specific version of evaluateError, which is pure virtual * so must be implemented in the derived class. */ - virtual Vector unwhitenedError(const Values& x, boost::optional&> H = boost::none) const { + Vector unwhitenedError(const Values& x, boost::optional&> H = boost::none) const override { if(this->active(x)) { if(H) return evaluateError(x.at(keys_[0]), x.at(keys_[1]), x.at(keys_[2]), (*H)[0], (*H)[1], (*H)[2]); @@ -547,7 +547,7 @@ public: /** Calls the 4-key specific version of evaluateError, which is pure virtual * so must be implemented in the derived class. */ - virtual Vector unwhitenedError(const Values& x, boost::optional&> H = boost::none) const { + Vector unwhitenedError(const Values& x, boost::optional&> H = boost::none) const override { if(this->active(x)) { if(H) return evaluateError(x.at(keys_[0]), x.at(keys_[1]), x.at(keys_[2]), x.at(keys_[3]), (*H)[0], (*H)[1], (*H)[2], (*H)[3]); @@ -631,7 +631,7 @@ public: /** Calls the 5-key specific version of evaluateError, which is pure virtual * so must be implemented in the derived class. */ - virtual Vector unwhitenedError(const Values& x, boost::optional&> H = boost::none) const { + Vector unwhitenedError(const Values& x, boost::optional&> H = boost::none) const override { if(this->active(x)) { if(H) return evaluateError(x.at(keys_[0]), x.at(keys_[1]), x.at(keys_[2]), x.at(keys_[3]), x.at(keys_[4]), (*H)[0], (*H)[1], (*H)[2], (*H)[3], (*H)[4]); @@ -719,7 +719,7 @@ public: /** Calls the 6-key specific version of evaluateError, which is pure virtual * so must be implemented in the derived class. */ - virtual Vector unwhitenedError(const Values& x, boost::optional&> H = boost::none) const { + Vector unwhitenedError(const Values& x, boost::optional&> H = boost::none) const override { if(this->active(x)) { if(H) return evaluateError(x.at(keys_[0]), x.at(keys_[1]), x.at(keys_[2]), x.at(keys_[3]), x.at(keys_[4]), x.at(keys_[5]), (*H)[0], (*H)[1], (*H)[2], (*H)[3], (*H)[4], (*H)[5]); diff --git a/gtsam/nonlinear/PriorFactor.h b/gtsam/nonlinear/PriorFactor.h index 0afbaa588..4f7075f21 100644 --- a/gtsam/nonlinear/PriorFactor.h +++ b/gtsam/nonlinear/PriorFactor.h @@ -65,15 +65,15 @@ namespace gtsam { } /// @return a deep copy of this factor - virtual gtsam::NonlinearFactor::shared_ptr clone() const { + gtsam::NonlinearFactor::shared_ptr clone() const override { return boost::static_pointer_cast( gtsam::NonlinearFactor::shared_ptr(new This(*this))); } /** implement functions needed for Testable */ /** print */ - virtual void print(const std::string& s, const KeyFormatter& keyFormatter = - DefaultKeyFormatter) const { + void print(const std::string& s, + const KeyFormatter& keyFormatter = DefaultKeyFormatter) const override { std::cout << s << "PriorFactor on " << keyFormatter(this->key()) << "\n"; traits::Print(prior_, " prior mean: "); if (this->noiseModel_) @@ -83,7 +83,7 @@ namespace gtsam { } /** equals */ - virtual bool equals(const NonlinearFactor& expected, double tol=1e-9) const { + bool equals(const NonlinearFactor& expected, double tol=1e-9) const override { const This* e = dynamic_cast (&expected); return e != nullptr && Base::equals(*e, tol) && traits::Equals(prior_, e->prior_, tol); } @@ -91,7 +91,7 @@ namespace gtsam { /** implement functions needed to derive from Factor */ /** vector of errors */ - Vector evaluateError(const T& x, boost::optional H = boost::none) const { + Vector evaluateError(const T& x, boost::optional H = boost::none) const override { if (H) (*H) = Matrix::Identity(traits::GetDimension(x),traits::GetDimension(x)); // manifold equivalent of z-x -> Local(x,z) // TODO(ASL) Add Jacobians. diff --git a/gtsam/nonlinear/Values.cpp b/gtsam/nonlinear/Values.cpp index 98790ccd9..7e13a072a 100644 --- a/gtsam/nonlinear/Values.cpp +++ b/gtsam/nonlinear/Values.cpp @@ -214,7 +214,7 @@ namespace gtsam { } /* ************************************************************************* */ - const char* ValuesKeyAlreadyExists::what() const throw() { + const char* ValuesKeyAlreadyExists::what() const noexcept { if(message_.empty()) message_ = "Attempting to add a key-value pair with key \"" + DefaultKeyFormatter(key_) + "\", key already exists."; @@ -222,7 +222,7 @@ namespace gtsam { } /* ************************************************************************* */ - const char* ValuesKeyDoesNotExist::what() const throw() { + const char* ValuesKeyDoesNotExist::what() const noexcept { if(message_.empty()) message_ = "Attempting to " + std::string(operation_) + " the key \"" + @@ -231,7 +231,7 @@ namespace gtsam { } /* ************************************************************************* */ - const char* ValuesIncorrectType::what() const throw() { + const char* ValuesIncorrectType::what() const noexcept { if(message_.empty()) { std::string storedTypeName = demangle(storedTypeId_.name()); std::string requestedTypeName = demangle(requestedTypeId_.name()); @@ -251,7 +251,7 @@ namespace gtsam { } /* ************************************************************************* */ - const char* NoMatchFoundForFixed::what() const throw() { + const char* NoMatchFoundForFixed::what() const noexcept { if(message_.empty()) { ostringstream oss; oss diff --git a/gtsam/nonlinear/Values.h b/gtsam/nonlinear/Values.h index 041aa3441..bc64f2612 100644 --- a/gtsam/nonlinear/Values.h +++ b/gtsam/nonlinear/Values.h @@ -432,16 +432,16 @@ namespace gtsam { public: /// Construct with the key-value pair attempted to be added - ValuesKeyAlreadyExists(Key key) throw() : + ValuesKeyAlreadyExists(Key key) noexcept : key_(key) {} - virtual ~ValuesKeyAlreadyExists() throw() {} + virtual ~ValuesKeyAlreadyExists() noexcept {} /// The duplicate key that was attempted to be added - Key key() const throw() { return key_; } + Key key() const noexcept { return key_; } /// The message to be displayed to the user - GTSAM_EXPORT virtual const char* what() const throw(); + GTSAM_EXPORT const char* what() const noexcept override; }; /* ************************************************************************* */ @@ -455,16 +455,16 @@ namespace gtsam { public: /// Construct with the key that does not exist in the values - ValuesKeyDoesNotExist(const char* operation, Key key) throw() : + ValuesKeyDoesNotExist(const char* operation, Key key) noexcept : operation_(operation), key_(key) {} - virtual ~ValuesKeyDoesNotExist() throw() {} + virtual ~ValuesKeyDoesNotExist() noexcept {} /// The key that was attempted to be accessed that does not exist - Key key() const throw() { return key_; } + Key key() const noexcept { return key_; } /// The message to be displayed to the user - GTSAM_EXPORT virtual const char* what() const throw(); + GTSAM_EXPORT const char* what() const noexcept override; }; /* ************************************************************************* */ @@ -480,13 +480,13 @@ namespace gtsam { public: /// Construct with the key that does not exist in the values ValuesIncorrectType(Key key, - const std::type_info& storedTypeId, const std::type_info& requestedTypeId) throw() : + const std::type_info& storedTypeId, const std::type_info& requestedTypeId) noexcept : key_(key), storedTypeId_(storedTypeId), requestedTypeId_(requestedTypeId) {} - virtual ~ValuesIncorrectType() throw() {} + virtual ~ValuesIncorrectType() noexcept {} /// The key that was attempted to be accessed that does not exist - Key key() const throw() { return key_; } + Key key() const noexcept { return key_; } /// The typeid of the value stores in the Values const std::type_info& storedTypeId() const { return storedTypeId_; } @@ -495,18 +495,18 @@ namespace gtsam { const std::type_info& requestedTypeId() const { return requestedTypeId_; } /// The message to be displayed to the user - GTSAM_EXPORT virtual const char* what() const throw(); + GTSAM_EXPORT const char* what() const noexcept override; }; /* ************************************************************************* */ class DynamicValuesMismatched : public std::exception { public: - DynamicValuesMismatched() throw() {} + DynamicValuesMismatched() noexcept {} - virtual ~DynamicValuesMismatched() throw() {} + virtual ~DynamicValuesMismatched() noexcept {} - virtual const char* what() const throw() { + const char* what() const noexcept override { return "The Values 'this' and the argument passed to Values::localCoordinates have mismatched keys and values"; } }; @@ -522,14 +522,14 @@ namespace gtsam { mutable std::string message_; public: - NoMatchFoundForFixed(size_t M1, size_t N1, size_t M2, size_t N2) throw () : + NoMatchFoundForFixed(size_t M1, size_t N1, size_t M2, size_t N2) noexcept : M1_(M1), N1_(N1), M2_(M2), N2_(N2) { } - virtual ~NoMatchFoundForFixed() throw () { + virtual ~NoMatchFoundForFixed() noexcept { } - GTSAM_EXPORT virtual const char* what() const throw (); + GTSAM_EXPORT const char* what() const noexcept override; }; /* ************************************************************************* */ diff --git a/gtsam/nonlinear/WhiteNoiseFactor.h b/gtsam/nonlinear/WhiteNoiseFactor.h index 634736800..974998830 100644 --- a/gtsam/nonlinear/WhiteNoiseFactor.h +++ b/gtsam/nonlinear/WhiteNoiseFactor.h @@ -109,7 +109,7 @@ namespace gtsam { /// Print void print(const std::string& p = "WhiteNoiseFactor", - const KeyFormatter& keyFormatter = DefaultKeyFormatter) const { + const KeyFormatter& keyFormatter = DefaultKeyFormatter) const override { Base::print(p, keyFormatter); std::cout << p + ".z: " << z_ << std::endl; } @@ -119,12 +119,12 @@ namespace gtsam { /// @{ /// get the dimension of the factor (number of rows on linearization) - virtual size_t dim() const { + size_t dim() const override { return 2; } /// Calculate the error of the factor, typically equal to log-likelihood - inline double error(const Values& x) const { + double error(const Values& x) const override { return f(z_, x.at(meanKey_), x.at(precisionKey_)); } @@ -153,7 +153,7 @@ namespace gtsam { /// @{ /// linearize returns a Hessianfactor that is an approximation of error(p) - virtual boost::shared_ptr linearize(const Values& x) const { + boost::shared_ptr linearize(const Values& x) const override { double u = x.at(meanKey_); double p = x.at(precisionKey_); Key j1 = meanKey_; @@ -163,7 +163,7 @@ namespace gtsam { // TODO: Frank commented this out for now, can it go? // /// @return a deep copy of this factor - // virtual gtsam::NonlinearFactor::shared_ptr clone() const { + // gtsam::NonlinearFactor::shared_ptr clone() const override { // return boost::static_pointer_cast( // gtsam::NonlinearFactor::shared_ptr(new This(*this))); } diff --git a/gtsam/nonlinear/internal/CallRecord.h b/gtsam/nonlinear/internal/CallRecord.h index 8bdc0652e..707c617ee 100644 --- a/gtsam/nonlinear/internal/CallRecord.h +++ b/gtsam/nonlinear/internal/CallRecord.h @@ -144,43 +144,43 @@ private: return static_cast(*this); } - virtual void _print(const std::string& indent) const { + void _print(const std::string& indent) const override { derived().print(indent); } // Called from base class non-virtual inline method startReverseAD2 // Calls non-virtual function startReverseAD4, implemented in Derived (ExpressionNode::Record) - virtual void _startReverseAD3(JacobianMap& jacobians) const { + void _startReverseAD3(JacobianMap& jacobians) const override { derived().startReverseAD4(jacobians); } - virtual void _reverseAD3(const Matrix & dFdT, JacobianMap& jacobians) const { + void _reverseAD3(const Matrix & dFdT, JacobianMap& jacobians) const override { derived().reverseAD4(dFdT, jacobians); } - virtual void _reverseAD3( + void _reverseAD3( const Eigen::Matrix & dFdT, - JacobianMap& jacobians) const { + JacobianMap& jacobians) const override { derived().reverseAD4(dFdT, jacobians); } - virtual void _reverseAD3(const Eigen::Matrix & dFdT, - JacobianMap& jacobians) const { + void _reverseAD3(const Eigen::Matrix & dFdT, + JacobianMap& jacobians) const override { derived().reverseAD4(dFdT, jacobians); } - virtual void _reverseAD3(const Eigen::Matrix & dFdT, - JacobianMap& jacobians) const { + void _reverseAD3(const Eigen::Matrix & dFdT, + JacobianMap& jacobians) const override { derived().reverseAD4(dFdT, jacobians); } - virtual void _reverseAD3(const Eigen::Matrix & dFdT, - JacobianMap& jacobians) const { + void _reverseAD3(const Eigen::Matrix & dFdT, + JacobianMap& jacobians) const override { derived().reverseAD4(dFdT, jacobians); } - virtual void _reverseAD3(const Eigen::Matrix & dFdT, - JacobianMap& jacobians) const { + void _reverseAD3(const Eigen::Matrix & dFdT, + JacobianMap& jacobians) const override { derived().reverseAD4(dFdT, jacobians); } - virtual void _reverseAD3(const Eigen::Matrix & dFdT, - JacobianMap& jacobians) const { + void _reverseAD3(const Eigen::Matrix & dFdT, + JacobianMap& jacobians) const override { derived().reverseAD4(dFdT, jacobians); } }; diff --git a/gtsam/nonlinear/internal/ExpressionNode.h b/gtsam/nonlinear/internal/ExpressionNode.h index 0ae37f130..ee3dc8929 100644 --- a/gtsam/nonlinear/internal/ExpressionNode.h +++ b/gtsam/nonlinear/internal/ExpressionNode.h @@ -135,18 +135,18 @@ public: } /// Print - virtual void print(const std::string& indent = "") const { + void print(const std::string& indent = "") const override { std::cout << indent << "Constant" << std::endl; } /// Return value - virtual T value(const Values& values) const { + T value(const Values& values) const override { return constant_; } /// Construct an execution trace for reverse AD - virtual T traceExecution(const Values& values, ExecutionTrace& trace, - ExecutionTraceStorage* traceStorage) const { + T traceExecution(const Values& values, ExecutionTrace& trace, + ExecutionTraceStorage* traceStorage) const override { return constant_; } @@ -176,30 +176,30 @@ public: } /// Print - virtual void print(const std::string& indent = "") const { + void print(const std::string& indent = "") const override { std::cout << indent << "Leaf, key = " << DefaultKeyFormatter(key_) << std::endl; } /// Return keys that play in this expression - virtual std::set keys() const { + std::set keys() const override { std::set keys; keys.insert(key_); return keys; } /// Return dimensions for each argument - virtual void dims(std::map& map) const { + void dims(std::map& map) const override { map[key_] = traits::dimension; } /// Return value - virtual T value(const Values& values) const { + T value(const Values& values) const override { return values.at(key_); } /// Construct an execution trace for reverse AD - virtual T traceExecution(const Values& values, ExecutionTrace& trace, - ExecutionTraceStorage* traceStorage) const { + T traceExecution(const Values& values, ExecutionTrace& trace, + ExecutionTraceStorage* traceStorage) const override { trace.setLeaf(key_); return values.at(key_); } @@ -248,23 +248,23 @@ public: } /// Print - virtual void print(const std::string& indent = "") const { + void print(const std::string& indent = "") const override { std::cout << indent << "UnaryExpression" << std::endl; expression1_->print(indent + " "); } /// Return value - virtual T value(const Values& values) const { + T value(const Values& values) const override { return function_(expression1_->value(values), boost::none); } /// Return keys that play in this expression - virtual std::set keys() const { + std::set keys() const override { return expression1_->keys(); } /// Return dimensions for each argument - virtual void dims(std::map& map) const { + void dims(std::map& map) const override { expression1_->dims(map); } @@ -307,8 +307,8 @@ public: }; /// Construct an execution trace for reverse AD - virtual T traceExecution(const Values& values, ExecutionTrace& trace, - ExecutionTraceStorage* ptr) const { + T traceExecution(const Values& values, ExecutionTrace& trace, + ExecutionTraceStorage* ptr) const override { assert(reinterpret_cast(ptr) % TraceAlignment == 0); // Create a Record in the memory pointed to by ptr @@ -357,21 +357,21 @@ public: } /// Print - virtual void print(const std::string& indent = "") const { + void print(const std::string& indent = "") const override { std::cout << indent << "BinaryExpression" << std::endl; expression1_->print(indent + " "); expression2_->print(indent + " "); } /// Return value - virtual T value(const Values& values) const { + T value(const Values& values) const override { using boost::none; return function_(expression1_->value(values), expression2_->value(values), none, none); } /// Return keys that play in this expression - virtual std::set keys() const { + std::set keys() const override { std::set keys = expression1_->keys(); std::set myKeys = expression2_->keys(); keys.insert(myKeys.begin(), myKeys.end()); @@ -379,7 +379,7 @@ public: } /// Return dimensions for each argument - virtual void dims(std::map& map) const { + void dims(std::map& map) const override { expression1_->dims(map); expression2_->dims(map); } @@ -426,8 +426,8 @@ public: }; /// Construct an execution trace for reverse AD, see UnaryExpression for explanation - virtual T traceExecution(const Values& values, ExecutionTrace& trace, - ExecutionTraceStorage* ptr) const { + T traceExecution(const Values& values, ExecutionTrace& trace, + ExecutionTraceStorage* ptr) const override { assert(reinterpret_cast(ptr) % TraceAlignment == 0); Record* record = new (ptr) Record(values, *expression1_, *expression2_, ptr); trace.setFunction(record); @@ -464,7 +464,7 @@ public: } /// Print - virtual void print(const std::string& indent = "") const { + void print(const std::string& indent = "") const override { std::cout << indent << "TernaryExpression" << std::endl; expression1_->print(indent + " "); expression2_->print(indent + " "); @@ -472,14 +472,14 @@ public: } /// Return value - virtual T value(const Values& values) const { + T value(const Values& values) const override { using boost::none; return function_(expression1_->value(values), expression2_->value(values), expression3_->value(values), none, none, none); } /// Return keys that play in this expression - virtual std::set keys() const { + std::set keys() const override { std::set keys = expression1_->keys(); std::set myKeys = expression2_->keys(); keys.insert(myKeys.begin(), myKeys.end()); @@ -489,7 +489,7 @@ public: } /// Return dimensions for each argument - virtual void dims(std::map& map) const { + void dims(std::map& map) const override { expression1_->dims(map); expression2_->dims(map); expression3_->dims(map); @@ -544,8 +544,8 @@ public: }; /// Construct an execution trace for reverse AD, see UnaryExpression for explanation - virtual T traceExecution(const Values& values, ExecutionTrace& trace, - ExecutionTraceStorage* ptr) const { + T traceExecution(const Values& values, ExecutionTrace& trace, + ExecutionTraceStorage* ptr) const override { assert(reinterpret_cast(ptr) % TraceAlignment == 0); Record* record = new (ptr) Record(values, *expression1_, *expression2_, *expression3_, ptr); trace.setFunction(record); @@ -574,23 +574,23 @@ class ScalarMultiplyNode : public ExpressionNode { virtual ~ScalarMultiplyNode() {} /// Print - virtual void print(const std::string& indent = "") const { + void print(const std::string& indent = "") const override { std::cout << indent << "ScalarMultiplyNode" << std::endl; expression_->print(indent + " "); } /// Return value - virtual T value(const Values& values) const { + T value(const Values& values) const override { return scalar_ * expression_->value(values); } /// Return keys that play in this expression - virtual std::set keys() const { + std::set keys() const override { return expression_->keys(); } /// Return dimensions for each argument - virtual void dims(std::map& map) const { + void dims(std::map& map) const override { expression_->dims(map); } @@ -624,8 +624,8 @@ class ScalarMultiplyNode : public ExpressionNode { }; /// Construct an execution trace for reverse AD - virtual T traceExecution(const Values& values, ExecutionTrace& trace, - ExecutionTraceStorage* ptr) const { + T traceExecution(const Values& values, ExecutionTrace& trace, + ExecutionTraceStorage* ptr) const override { assert(reinterpret_cast(ptr) % TraceAlignment == 0); Record* record = new (ptr) Record(); ptr += upAligned(sizeof(Record)); @@ -662,19 +662,19 @@ class BinarySumNode : public ExpressionNode { virtual ~BinarySumNode() {} /// Print - virtual void print(const std::string& indent = "") const { + void print(const std::string& indent = "") const override { std::cout << indent << "BinarySumNode" << std::endl; expression1_->print(indent + " "); expression2_->print(indent + " "); } /// Return value - virtual T value(const Values& values) const { + T value(const Values& values) const override { return expression1_->value(values) + expression2_->value(values); } /// Return keys that play in this expression - virtual std::set keys() const { + std::set keys() const override { std::set keys = expression1_->keys(); std::set myKeys = expression2_->keys(); keys.insert(myKeys.begin(), myKeys.end()); @@ -682,7 +682,7 @@ class BinarySumNode : public ExpressionNode { } /// Return dimensions for each argument - virtual void dims(std::map& map) const { + void dims(std::map& map) const override { expression1_->dims(map); expression2_->dims(map); } @@ -717,8 +717,8 @@ class BinarySumNode : public ExpressionNode { }; /// Construct an execution trace for reverse AD - virtual T traceExecution(const Values& values, ExecutionTrace& trace, - ExecutionTraceStorage* ptr) const { + T traceExecution(const Values& values, ExecutionTrace& trace, + ExecutionTraceStorage* ptr) const override { assert(reinterpret_cast(ptr) % TraceAlignment == 0); Record* record = new (ptr) Record(); trace.setFunction(record); diff --git a/gtsam/nonlinear/nonlinearExceptions.h b/gtsam/nonlinear/nonlinearExceptions.h index 8b32b6fdc..7b704ac39 100644 --- a/gtsam/nonlinear/nonlinearExceptions.h +++ b/gtsam/nonlinear/nonlinearExceptions.h @@ -35,11 +35,11 @@ namespace gtsam { KeyFormatter formatter_; mutable std::string what_; public: - MarginalizeNonleafException(Key key, KeyFormatter formatter = DefaultKeyFormatter) throw() : + MarginalizeNonleafException(Key key, KeyFormatter formatter = DefaultKeyFormatter) noexcept : key_(key), formatter_(formatter) {} - virtual ~MarginalizeNonleafException() throw() {} + virtual ~MarginalizeNonleafException() noexcept {} Key key() const { return key_; } - virtual const char* what() const throw() { + const char* what() const noexcept override { if(what_.empty()) what_ = "\nRequested to marginalize out variable " + formatter_(key_) + ", but this variable\n\ diff --git a/gtsam/sam/BearingFactor.h b/gtsam/sam/BearingFactor.h index a9ed5ef4b..530fcfdcd 100644 --- a/gtsam/sam/BearingFactor.h +++ b/gtsam/sam/BearingFactor.h @@ -48,7 +48,7 @@ struct BearingFactor : public ExpressionFactor2 { } // Return measurement expression - virtual Expression expression(Key key1, Key key2) const { + Expression expression(Key key1, Key key2) const override { Expression a1_(key1); Expression a2_(key2); return Expression(Bearing(), a1_, a2_); @@ -56,7 +56,7 @@ struct BearingFactor : public ExpressionFactor2 { /// print void print(const std::string& s = "", - const KeyFormatter& kf = DefaultKeyFormatter) const { + const KeyFormatter& kf = DefaultKeyFormatter) const override { std::cout << s << "BearingFactor" << std::endl; Base::print(s, kf); } diff --git a/gtsam/sam/BearingRangeFactor.h b/gtsam/sam/BearingRangeFactor.h index 44740f8ff..be645ef94 100644 --- a/gtsam/sam/BearingRangeFactor.h +++ b/gtsam/sam/BearingRangeFactor.h @@ -55,20 +55,20 @@ class BearingRangeFactor virtual ~BearingRangeFactor() {} /// @return a deep copy of this factor - virtual gtsam::NonlinearFactor::shared_ptr clone() const { + gtsam::NonlinearFactor::shared_ptr clone() const override { return boost::static_pointer_cast( gtsam::NonlinearFactor::shared_ptr(new This(*this))); } // Return measurement expression - virtual Expression expression(Key key1, Key key2) const { + Expression expression(Key key1, Key key2) const override { return Expression(T::Measure, Expression(key1), Expression(key2)); } /// print - virtual void print(const std::string& s = "", - const KeyFormatter& kf = DefaultKeyFormatter) const { + void print(const std::string& s = "", + const KeyFormatter& kf = DefaultKeyFormatter) const override { std::cout << s << "BearingRangeFactor" << std::endl; Base::print(s, kf); } diff --git a/gtsam/sam/RangeFactor.h b/gtsam/sam/RangeFactor.h index 40a9cf758..80b02404e 100644 --- a/gtsam/sam/RangeFactor.h +++ b/gtsam/sam/RangeFactor.h @@ -47,13 +47,13 @@ class RangeFactor : public ExpressionFactor2 { } /// @return a deep copy of this factor - virtual gtsam::NonlinearFactor::shared_ptr clone() const { + gtsam::NonlinearFactor::shared_ptr clone() const override { return boost::static_pointer_cast( gtsam::NonlinearFactor::shared_ptr(new This(*this))); } // Return measurement expression - virtual Expression expression(Key key1, Key key2) const { + Expression expression(Key key1, Key key2) const override { Expression a1_(key1); Expression a2_(key2); return Expression(Range(), a1_, a2_); @@ -61,7 +61,7 @@ class RangeFactor : public ExpressionFactor2 { /// print void print(const std::string& s = "", - const KeyFormatter& kf = DefaultKeyFormatter) const { + const KeyFormatter& kf = DefaultKeyFormatter) const override { std::cout << s << "RangeFactor" << std::endl; Base::print(s, kf); } @@ -107,13 +107,13 @@ class RangeFactorWithTransform : public ExpressionFactor2 { virtual ~RangeFactorWithTransform() {} /// @return a deep copy of this factor - virtual gtsam::NonlinearFactor::shared_ptr clone() const { + gtsam::NonlinearFactor::shared_ptr clone() const override { return boost::static_pointer_cast( gtsam::NonlinearFactor::shared_ptr(new This(*this))); } // Return measurement expression - virtual Expression expression(Key key1, Key key2) const { + Expression expression(Key key1, Key key2) const override { Expression body_T_sensor__(body_T_sensor_); Expression nav_T_body_(key1); Expression nav_T_sensor_(traits::Compose, nav_T_body_, @@ -124,7 +124,7 @@ class RangeFactorWithTransform : public ExpressionFactor2 { /** print contents */ void print(const std::string& s = "", - const KeyFormatter& keyFormatter = DefaultKeyFormatter) const { + const KeyFormatter& keyFormatter = DefaultKeyFormatter) const override { std::cout << s << "RangeFactorWithTransform" << std::endl; this->body_T_sensor_.print(" sensor pose in body frame: "); Base::print(s, keyFormatter); diff --git a/gtsam/slam/AntiFactor.h b/gtsam/slam/AntiFactor.h index 9e4f7db5a..277080b6b 100644 --- a/gtsam/slam/AntiFactor.h +++ b/gtsam/slam/AntiFactor.h @@ -52,20 +52,20 @@ namespace gtsam { virtual ~AntiFactor() {} /// @return a deep copy of this factor - virtual gtsam::NonlinearFactor::shared_ptr clone() const { + gtsam::NonlinearFactor::shared_ptr clone() const override { return boost::static_pointer_cast( gtsam::NonlinearFactor::shared_ptr(new This(*this))); } /** implement functions needed for Testable */ /** print */ - virtual void print(const std::string& s, const KeyFormatter& keyFormatter = DefaultKeyFormatter) const { + void print(const std::string& s, const KeyFormatter& keyFormatter = DefaultKeyFormatter) const override { std::cout << s << "AntiFactor version of:" << std::endl; factor_->print(s, keyFormatter); } /** equals */ - virtual bool equals(const NonlinearFactor& expected, double tol=1e-9) const { + bool equals(const NonlinearFactor& expected, double tol=1e-9) const override { const This *e = dynamic_cast (&expected); return e != nullptr && Base::equals(*e, tol) && this->factor_->equals(*e->factor_, tol); } @@ -77,16 +77,16 @@ namespace gtsam { * For the AntiFactor, this will have the same magnitude of the original factor, * but the opposite sign. */ - double error(const Values& c) const { return -factor_->error(c); } + double error(const Values& c) const override { return -factor_->error(c); } /** get the dimension of the factor (same as the original factor) */ - size_t dim() const { return factor_->dim(); } + size_t dim() const override { return factor_->dim(); } /** * Checks whether this factor should be used based on a set of values. * The AntiFactor will have the same 'active' profile as the original factor. */ - bool active(const Values& c) const { return factor_->active(c); } + bool active(const Values& c) const override { return factor_->active(c); } /** * Linearize to a GaussianFactor. The AntiFactor always returns a Hessian Factor @@ -94,7 +94,7 @@ namespace gtsam { * returns a Jacobian instead of a full Hessian), but with the opposite sign. This * effectively cancels the effect of the original factor on the factor graph. */ - boost::shared_ptr linearize(const Values& c) const { + boost::shared_ptr linearize(const Values& c) const override { // Generate the linearized factor from the contained nonlinear factor GaussianFactor::shared_ptr gaussianFactor = factor_->linearize(c); diff --git a/gtsam/slam/BetweenFactor.h b/gtsam/slam/BetweenFactor.h index b1d4904aa..0f5aa6a4c 100644 --- a/gtsam/slam/BetweenFactor.h +++ b/gtsam/slam/BetweenFactor.h @@ -63,14 +63,14 @@ namespace gtsam { virtual ~BetweenFactor() {} /// @return a deep copy of this factor - virtual gtsam::NonlinearFactor::shared_ptr clone() const { + gtsam::NonlinearFactor::shared_ptr clone() const override { return boost::static_pointer_cast( gtsam::NonlinearFactor::shared_ptr(new This(*this))); } /** implement functions needed for Testable */ /** print */ - virtual void print(const std::string& s, const KeyFormatter& keyFormatter = DefaultKeyFormatter) const { + void print(const std::string& s, const KeyFormatter& keyFormatter = DefaultKeyFormatter) const override { std::cout << s << "BetweenFactor(" << keyFormatter(this->key1()) << "," << keyFormatter(this->key2()) << ")\n"; @@ -79,7 +79,7 @@ namespace gtsam { } /** equals */ - virtual bool equals(const NonlinearFactor& expected, double tol=1e-9) const { + bool equals(const NonlinearFactor& expected, double tol=1e-9) const override { const This *e = dynamic_cast (&expected); return e != nullptr && Base::equals(*e, tol) && traits::Equals(this->measured_, e->measured_, tol); } @@ -87,8 +87,8 @@ namespace gtsam { /** implement functions needed to derive from Factor */ /** vector of errors */ - Vector evaluateError(const T& p1, const T& p2, boost::optional H1 = - boost::none, boost::optional H2 = boost::none) const { + Vector evaluateError(const T& p1, const T& p2, boost::optional H1 = + boost::none, boost::optional H2 = boost::none) const override { T hx = traits::Between(p1, p2, H1, H2); // h(x) // manifold equivalent of h(x)-z -> log(z,h(x)) #ifdef SLOW_BUT_CORRECT_BETWEENFACTOR diff --git a/gtsam/slam/BoundingConstraint.h b/gtsam/slam/BoundingConstraint.h index f6561807e..43cc6d292 100644 --- a/gtsam/slam/BoundingConstraint.h +++ b/gtsam/slam/BoundingConstraint.h @@ -58,14 +58,14 @@ struct BoundingConstraint1: public NoiseModelFactor1 { boost::none) const = 0; /** active when constraint *NOT* met */ - bool active(const Values& c) const { + bool active(const Values& c) const override { // note: still active at equality to avoid zigzagging double x = value(c.at(this->key())); return (isGreaterThan_) ? x <= threshold_ : x >= threshold_; } Vector evaluateError(const X& x, boost::optional H = - boost::none) const { + boost::none) const override { Matrix D; double error = value(x, D) - threshold_; if (H) { @@ -126,7 +126,7 @@ struct BoundingConstraint2: public NoiseModelFactor2 { boost::optional H2 = boost::none) const = 0; /** active when constraint *NOT* met */ - bool active(const Values& c) const { + bool active(const Values& c) const override { // note: still active at equality to avoid zigzagging double x = value(c.at(this->key1()), c.at(this->key2())); return (isGreaterThan_) ? x <= threshold_ : x >= threshold_; @@ -134,7 +134,7 @@ struct BoundingConstraint2: public NoiseModelFactor2 { Vector evaluateError(const X1& x1, const X2& x2, boost::optional H1 = boost::none, - boost::optional H2 = boost::none) const { + boost::optional H2 = boost::none) const override { Matrix D1, D2; double error = value(x1, x2, D1, D2) - threshold_; if (H1) { diff --git a/gtsam/slam/EssentialMatrixConstraint.h b/gtsam/slam/EssentialMatrixConstraint.h index e474ce5b3..943db7207 100644 --- a/gtsam/slam/EssentialMatrixConstraint.h +++ b/gtsam/slam/EssentialMatrixConstraint.h @@ -61,7 +61,7 @@ public: } /// @return a deep copy of this factor - virtual gtsam::NonlinearFactor::shared_ptr clone() const { + gtsam::NonlinearFactor::shared_ptr clone() const override { return boost::static_pointer_cast( gtsam::NonlinearFactor::shared_ptr(new This(*this))); } @@ -69,18 +69,18 @@ public: /** implement functions needed for Testable */ /** print */ - virtual void print(const std::string& s = "", - const KeyFormatter& keyFormatter = DefaultKeyFormatter) const; + void print(const std::string& s = "", + const KeyFormatter& keyFormatter = DefaultKeyFormatter) const override; /** equals */ - virtual bool equals(const NonlinearFactor& expected, double tol = 1e-9) const; + bool equals(const NonlinearFactor& expected, double tol = 1e-9) const override; /** implement functions needed to derive from Factor */ /** vector of errors */ - virtual Vector evaluateError(const Pose3& p1, const Pose3& p2, + Vector evaluateError(const Pose3& p1, const Pose3& p2, boost::optional Hp1 = boost::none, // - boost::optional Hp2 = boost::none) const; + boost::optional Hp2 = boost::none) const override; /** return the measured */ const EssentialMatrix& measured() const { diff --git a/gtsam/slam/EssentialMatrixFactor.h b/gtsam/slam/EssentialMatrixFactor.h index c214a2f48..a99ac9512 100644 --- a/gtsam/slam/EssentialMatrixFactor.h +++ b/gtsam/slam/EssentialMatrixFactor.h @@ -58,14 +58,14 @@ public: } /// @return a deep copy of this factor - virtual gtsam::NonlinearFactor::shared_ptr clone() const { + gtsam::NonlinearFactor::shared_ptr clone() const override { return boost::static_pointer_cast( gtsam::NonlinearFactor::shared_ptr(new This(*this))); } /// print - virtual void print(const std::string& s = "", - const KeyFormatter& keyFormatter = DefaultKeyFormatter) const { + void print(const std::string& s = "", + const KeyFormatter& keyFormatter = DefaultKeyFormatter) const override { Base::print(s); std::cout << " EssentialMatrixFactor with measurements\n (" << vA_.transpose() << ")' and (" << vB_.transpose() << ")'" @@ -74,7 +74,7 @@ public: /// vector of errors returns 1D vector Vector evaluateError(const EssentialMatrix& E, boost::optional H = - boost::none) const { + boost::none) const override { Vector error(1); error << E.error(vA_, vB_, H); return error; @@ -131,14 +131,14 @@ public: } /// @return a deep copy of this factor - virtual gtsam::NonlinearFactor::shared_ptr clone() const { + gtsam::NonlinearFactor::shared_ptr clone() const override { return boost::static_pointer_cast( gtsam::NonlinearFactor::shared_ptr(new This(*this))); } /// print - virtual void print(const std::string& s = "", - const KeyFormatter& keyFormatter = DefaultKeyFormatter) const { + void print(const std::string& s = "", + const KeyFormatter& keyFormatter = DefaultKeyFormatter) const override { Base::print(s); std::cout << " EssentialMatrixFactor2 with measurements\n (" << dP1_.transpose() << ")' and (" << pn_.transpose() @@ -152,7 +152,7 @@ public: */ Vector evaluateError(const EssentialMatrix& E, const double& d, boost::optional DE = boost::none, boost::optional Dd = - boost::none) const { + boost::none) const override { // We have point x,y in image 1 // Given a depth Z, the corresponding 3D point P1 = Z*(x,y,1) = (x,y,1)/d @@ -250,14 +250,14 @@ public: } /// @return a deep copy of this factor - virtual gtsam::NonlinearFactor::shared_ptr clone() const { + gtsam::NonlinearFactor::shared_ptr clone() const override { return boost::static_pointer_cast( gtsam::NonlinearFactor::shared_ptr(new This(*this))); } /// print - virtual void print(const std::string& s = "", - const KeyFormatter& keyFormatter = DefaultKeyFormatter) const { + void print(const std::string& s = "", + const KeyFormatter& keyFormatter = DefaultKeyFormatter) const override { Base::print(s); std::cout << " EssentialMatrixFactor3 with rotation " << cRb_ << std::endl; } @@ -269,7 +269,7 @@ public: */ Vector evaluateError(const EssentialMatrix& E, const double& d, boost::optional DE = boost::none, boost::optional Dd = - boost::none) const { + boost::none) const override { if (!DE) { // Convert E from body to camera frame EssentialMatrix cameraE = cRb_ * E; diff --git a/gtsam/slam/FrobeniusFactor.h b/gtsam/slam/FrobeniusFactor.h index a73445ae0..6b2ef67fc 100644 --- a/gtsam/slam/FrobeniusFactor.h +++ b/gtsam/slam/FrobeniusFactor.h @@ -56,7 +56,7 @@ class FrobeniusPrior : public NoiseModelFactor1 { /// Error is just Frobenius norm between Rot element and vectorized matrix M. Vector evaluateError(const Rot& R, - boost::optional H = boost::none) const { + boost::optional H = boost::none) const override { return R.vec(H) - vecM_; // Jacobian is computed only when needed. } }; @@ -78,7 +78,7 @@ class FrobeniusFactor : public NoiseModelFactor2 { /// Error is just Frobenius norm between rotation matrices. Vector evaluateError(const Rot& R1, const Rot& R2, boost::optional H1 = boost::none, - boost::optional H2 = boost::none) const { + boost::optional H2 = boost::none) const override { Vector error = R2.vec(H2) - R1.vec(H1); if (H1) *H1 = -*H1; return error; @@ -110,7 +110,7 @@ class FrobeniusBetweenFactor : public NoiseModelFactor2 { /// Error is Frobenius norm between R1*R12 and R2. Vector evaluateError(const Rot& R1, const Rot& R2, boost::optional H1 = boost::none, - boost::optional H2 = boost::none) const { + boost::optional H2 = boost::none) const override { const Rot R2hat = R1.compose(R12_); Eigen::Matrix vec_H_R2hat; Vector error = R2.vec(H2) - R2hat.vec(H1 ? &vec_H_R2hat : nullptr); @@ -139,7 +139,7 @@ class GTSAM_EXPORT FrobeniusWormholeFactor : public NoiseModelFactor2 /// projects down from SO(p) to the Stiefel manifold of px3 matrices. Vector evaluateError(const SOn& Q1, const SOn& Q2, boost::optional H1 = boost::none, - boost::optional H2 = boost::none) const; + boost::optional H2 = boost::none) const override; }; } // namespace gtsam diff --git a/gtsam/slam/GeneralSFMFactor.h b/gtsam/slam/GeneralSFMFactor.h index 0eb489f35..f848a56ca 100644 --- a/gtsam/slam/GeneralSFMFactor.h +++ b/gtsam/slam/GeneralSFMFactor.h @@ -96,7 +96,7 @@ public: virtual ~GeneralSFMFactor() {} ///< destructor /// @return a deep copy of this factor - virtual gtsam::NonlinearFactor::shared_ptr clone() const { + gtsam::NonlinearFactor::shared_ptr clone() const override { return boost::static_pointer_cast( gtsam::NonlinearFactor::shared_ptr(new This(*this)));} @@ -105,7 +105,7 @@ public: * @param s optional string naming the factor * @param keyFormatter optional formatter for printing out Symbols */ - void print(const std::string& s = "SFMFactor", const KeyFormatter& keyFormatter = DefaultKeyFormatter) const { + void print(const std::string& s = "SFMFactor", const KeyFormatter& keyFormatter = DefaultKeyFormatter) const override { Base::print(s, keyFormatter); traits::Print(measured_, s + ".z"); } @@ -113,14 +113,14 @@ public: /** * equals */ - bool equals(const NonlinearFactor &p, double tol = 1e-9) const { + bool equals(const NonlinearFactor &p, double tol = 1e-9) const override { const This* e = dynamic_cast(&p); return e && Base::equals(p, tol) && traits::Equals(this->measured_, e->measured_, tol); } /** h(x)-z */ Vector evaluateError(const CAMERA& camera, const LANDMARK& point, - boost::optional H1=boost::none, boost::optional H2=boost::none) const { + boost::optional H1=boost::none, boost::optional H2=boost::none) const override { try { return camera.project2(point,H1,H2) - measured_; } @@ -133,7 +133,7 @@ public: } /// Linearize using fixed-size matrices - boost::shared_ptr linearize(const Values& values) const { + boost::shared_ptr linearize(const Values& values) const override { // Only linearize if the factor is active if (!this->active(values)) return boost::shared_ptr(); @@ -230,7 +230,7 @@ public: virtual ~GeneralSFMFactor2() {} ///< destructor /// @return a deep copy of this factor - virtual gtsam::NonlinearFactor::shared_ptr clone() const { + gtsam::NonlinearFactor::shared_ptr clone() const override { return boost::static_pointer_cast( gtsam::NonlinearFactor::shared_ptr(new This(*this)));} @@ -239,7 +239,7 @@ public: * @param s optional string naming the factor * @param keyFormatter optional formatter useful for printing Symbols */ - void print(const std::string& s = "SFMFactor2", const KeyFormatter& keyFormatter = DefaultKeyFormatter) const { + void print(const std::string& s = "SFMFactor2", const KeyFormatter& keyFormatter = DefaultKeyFormatter) const override { Base::print(s, keyFormatter); traits::Print(measured_, s + ".z"); } @@ -247,7 +247,7 @@ public: /** * equals */ - bool equals(const NonlinearFactor &p, double tol = 1e-9) const { + bool equals(const NonlinearFactor &p, double tol = 1e-9) const override { const This* e = dynamic_cast(&p); return e && Base::equals(p, tol) && traits::Equals(this->measured_, e->measured_, tol); } @@ -256,7 +256,7 @@ public: Vector evaluateError(const Pose3& pose3, const Point3& point, const CALIBRATION &calib, boost::optional H1=boost::none, boost::optional H2=boost::none, - boost::optional H3=boost::none) const + boost::optional H3=boost::none) const override { try { Camera camera(pose3,calib); diff --git a/gtsam/slam/OrientedPlane3Factor.h b/gtsam/slam/OrientedPlane3Factor.h index 1f56adc45..e83464b1e 100644 --- a/gtsam/slam/OrientedPlane3Factor.h +++ b/gtsam/slam/OrientedPlane3Factor.h @@ -41,13 +41,13 @@ public: } /// print - virtual void print(const std::string& s = "OrientedPlane3Factor", - const KeyFormatter& keyFormatter = DefaultKeyFormatter) const; + void print(const std::string& s = "OrientedPlane3Factor", + const KeyFormatter& keyFormatter = DefaultKeyFormatter) const override; /// evaluateError - virtual Vector evaluateError(const Pose3& pose, const OrientedPlane3& plane, + Vector evaluateError(const Pose3& pose, const OrientedPlane3& plane, boost::optional H1 = boost::none, boost::optional H2 = - boost::none) const { + boost::none) const override { OrientedPlane3 predicted_plane = OrientedPlane3::Transform(plane, pose, H1, H2); Vector err(3); @@ -78,14 +78,14 @@ public: } /// print - virtual void print(const std::string& s = "OrientedPlane3DirectionPrior", - const KeyFormatter& keyFormatter = DefaultKeyFormatter) const; + void print(const std::string& s = "OrientedPlane3DirectionPrior", + const KeyFormatter& keyFormatter = DefaultKeyFormatter) const override; /// equals - virtual bool equals(const NonlinearFactor& expected, double tol = 1e-9) const; + bool equals(const NonlinearFactor& expected, double tol = 1e-9) const override; - virtual Vector evaluateError(const OrientedPlane3& plane, - boost::optional H = boost::none) const; + Vector evaluateError(const OrientedPlane3& plane, + boost::optional H = boost::none) const override; }; } // gtsam diff --git a/gtsam/slam/PoseRotationPrior.h b/gtsam/slam/PoseRotationPrior.h index f4ce1520a..7e8bdaa46 100644 --- a/gtsam/slam/PoseRotationPrior.h +++ b/gtsam/slam/PoseRotationPrior.h @@ -50,7 +50,7 @@ public: virtual ~PoseRotationPrior() {} /// @return a deep copy of this factor - virtual gtsam::NonlinearFactor::shared_ptr clone() const { + gtsam::NonlinearFactor::shared_ptr clone() const override { return boost::static_pointer_cast( gtsam::NonlinearFactor::shared_ptr(new This(*this))); } @@ -60,19 +60,19 @@ public: // testable /** equals specialized to this factor */ - virtual bool equals(const NonlinearFactor& expected, double tol=1e-9) const { + bool equals(const NonlinearFactor& expected, double tol=1e-9) const override { const This *e = dynamic_cast (&expected); return e != nullptr && Base::equals(*e, tol) && measured_.equals(e->measured_, tol); } /** print contents */ - void print(const std::string& s="", const KeyFormatter& keyFormatter = DefaultKeyFormatter) const { + void print(const std::string& s="", const KeyFormatter& keyFormatter = DefaultKeyFormatter) const override { Base::print(s + "PoseRotationPrior", keyFormatter); measured_.print("Measured Rotation"); } /** h(x)-z */ - Vector evaluateError(const Pose& pose, boost::optional H = boost::none) const { + Vector evaluateError(const Pose& pose, boost::optional H = boost::none) const override { const Rotation& newR = pose.rotation(); if (H) { *H = Matrix::Zero(rDim, xDim); diff --git a/gtsam/slam/PoseTranslationPrior.h b/gtsam/slam/PoseTranslationPrior.h index 516582d83..0c029c501 100644 --- a/gtsam/slam/PoseTranslationPrior.h +++ b/gtsam/slam/PoseTranslationPrior.h @@ -54,12 +54,12 @@ public: const Translation& measured() const { return measured_; } /// @return a deep copy of this factor - virtual gtsam::NonlinearFactor::shared_ptr clone() const { + gtsam::NonlinearFactor::shared_ptr clone() const override { return boost::static_pointer_cast( gtsam::NonlinearFactor::shared_ptr(new This(*this))); } /** h(x)-z */ - Vector evaluateError(const Pose& pose, boost::optional H = boost::none) const { + Vector evaluateError(const Pose& pose, boost::optional H = boost::none) const override { const Translation& newTrans = pose.translation(); const Rotation& R = pose.rotation(); const int tDim = traits::GetDimension(newTrans); @@ -74,13 +74,13 @@ public: } /** equals specialized to this factor */ - virtual bool equals(const NonlinearFactor& expected, double tol=1e-9) const { + bool equals(const NonlinearFactor& expected, double tol=1e-9) const override { const This *e = dynamic_cast (&expected); return e != nullptr && Base::equals(*e, tol) && traits::Equals(measured_, e->measured_, tol); } /** print contents */ - void print(const std::string& s="", const KeyFormatter& keyFormatter = DefaultKeyFormatter) const { + void print(const std::string& s="", const KeyFormatter& keyFormatter = DefaultKeyFormatter) const override { Base::print(s + "PoseTranslationPrior", keyFormatter); traits::Print(measured_, "Measured Translation"); } diff --git a/gtsam/slam/ProjectionFactor.h b/gtsam/slam/ProjectionFactor.h index 0bed15fdc..266037469 100644 --- a/gtsam/slam/ProjectionFactor.h +++ b/gtsam/slam/ProjectionFactor.h @@ -100,7 +100,7 @@ namespace gtsam { virtual ~GenericProjectionFactor() {} /// @return a deep copy of this factor - virtual gtsam::NonlinearFactor::shared_ptr clone() const { + gtsam::NonlinearFactor::shared_ptr clone() const override { return boost::static_pointer_cast( gtsam::NonlinearFactor::shared_ptr(new This(*this))); } @@ -109,7 +109,7 @@ namespace gtsam { * @param s optional string naming the factor * @param keyFormatter optional formatter useful for printing Symbols */ - void print(const std::string& s = "", const KeyFormatter& keyFormatter = DefaultKeyFormatter) const { + void print(const std::string& s = "", const KeyFormatter& keyFormatter = DefaultKeyFormatter) const override { std::cout << s << "GenericProjectionFactor, z = "; traits::Print(measured_); if(this->body_P_sensor_) @@ -118,7 +118,7 @@ namespace gtsam { } /// equals - virtual bool equals(const NonlinearFactor& p, double tol = 1e-9) const { + bool equals(const NonlinearFactor& p, double tol = 1e-9) const override { const This *e = dynamic_cast(&p); return e && Base::equals(p, tol) @@ -129,7 +129,7 @@ namespace gtsam { /// Evaluate error h(x)-z and optionally derivatives Vector evaluateError(const Pose3& pose, const Point3& point, - boost::optional H1 = boost::none, boost::optional H2 = boost::none) const { + boost::optional H1 = boost::none, boost::optional H2 = boost::none) const override { try { if(body_P_sensor_) { if(H1) { diff --git a/gtsam/slam/ReferenceFrameFactor.h b/gtsam/slam/ReferenceFrameFactor.h index 30f761934..e41b5f908 100644 --- a/gtsam/slam/ReferenceFrameFactor.h +++ b/gtsam/slam/ReferenceFrameFactor.h @@ -89,23 +89,23 @@ public: virtual ~ReferenceFrameFactor(){} - virtual NonlinearFactor::shared_ptr clone() const { + NonlinearFactor::shared_ptr clone() const override { return boost::static_pointer_cast( NonlinearFactor::shared_ptr(new This(*this))); } /** Combined cost and derivative function using boost::optional */ - virtual Vector evaluateError(const Point& global, const Transform& trans, const Point& local, + Vector evaluateError(const Point& global, const Transform& trans, const Point& local, boost::optional Dforeign = boost::none, boost::optional Dtrans = boost::none, - boost::optional Dlocal = boost::none) const { + boost::optional Dlocal = boost::none) const override { Point newlocal = transform_point(trans, global, Dtrans, Dforeign); if (Dlocal) *Dlocal = -1* Matrix::Identity(traits::dimension, traits::dimension); return traits::Local(local,newlocal); } - virtual void print(const std::string& s="", - const gtsam::KeyFormatter& keyFormatter = DefaultKeyFormatter) const { + void print(const std::string& s="", + const gtsam::KeyFormatter& keyFormatter = DefaultKeyFormatter) const override { std::cout << s << ": ReferenceFrameFactor(" << "Global: " << keyFormatter(this->key1()) << "," << " Transform: " << keyFormatter(this->key2()) << "," diff --git a/gtsam/slam/RotateFactor.h b/gtsam/slam/RotateFactor.h index 948fffe13..9e4091111 100644 --- a/gtsam/slam/RotateFactor.h +++ b/gtsam/slam/RotateFactor.h @@ -36,13 +36,13 @@ public: } /// @return a deep copy of this factor - virtual gtsam::NonlinearFactor::shared_ptr clone() const { + gtsam::NonlinearFactor::shared_ptr clone() const override { return boost::static_pointer_cast( gtsam::NonlinearFactor::shared_ptr(new This(*this))); } /// print - virtual void print(const std::string& s = "", - const KeyFormatter& keyFormatter = DefaultKeyFormatter) const { + void print(const std::string& s = "", + const KeyFormatter& keyFormatter = DefaultKeyFormatter) const override { Base::print(s); std::cout << "RotateFactor:]\n"; std::cout << "p: " << p_.transpose() << std::endl; @@ -51,7 +51,7 @@ public: /// vector of errors returns 2D vector Vector evaluateError(const Rot3& R, - boost::optional H = boost::none) const { + boost::optional H = boost::none) const override { // predict p_ as q = R*z_, derivative H will be filled if not none Point3 q = R.rotate(z_,H); // error is just difference, and note derivative of that wrpt q is I3 @@ -88,13 +88,13 @@ public: } /// @return a deep copy of this factor - virtual gtsam::NonlinearFactor::shared_ptr clone() const { + gtsam::NonlinearFactor::shared_ptr clone() const override { return boost::static_pointer_cast( gtsam::NonlinearFactor::shared_ptr(new This(*this))); } /// print - virtual void print(const std::string& s = "", - const KeyFormatter& keyFormatter = DefaultKeyFormatter) const { + void print(const std::string& s = "", + const KeyFormatter& keyFormatter = DefaultKeyFormatter) const override { Base::print(s); std::cout << "RotateDirectionsFactor:" << std::endl; i_p_.print("p"); @@ -102,7 +102,7 @@ public: } /// vector of errors returns 2D vector - Vector evaluateError(const Rot3& iRc, boost::optional H = boost::none) const { + Vector evaluateError(const Rot3& iRc, boost::optional H = boost::none) const override { Unit3 i_q = iRc * c_z_; Vector error = i_p_.error(i_q, H); if (H) { diff --git a/gtsam/slam/SmartFactorBase.h b/gtsam/slam/SmartFactorBase.h index 1c80b8744..d9f2b9c3d 100644 --- a/gtsam/slam/SmartFactorBase.h +++ b/gtsam/slam/SmartFactorBase.h @@ -150,7 +150,7 @@ protected: } /// get the dimension (number of rows!) of the factor - virtual size_t dim() const { + size_t dim() const override { return ZDim * this->measured_.size(); } @@ -173,7 +173,7 @@ protected: * @param keyFormatter optional formatter useful for printing Symbols */ void print(const std::string& s = "", const KeyFormatter& keyFormatter = - DefaultKeyFormatter) const { + DefaultKeyFormatter) const override { std::cout << s << "SmartFactorBase, z = \n"; for (size_t k = 0; k < measured_.size(); ++k) { std::cout << "measurement, p = " << measured_[k] << "\t"; @@ -185,7 +185,7 @@ protected: } /// equals - virtual bool equals(const NonlinearFactor& p, double tol = 1e-9) const { + bool equals(const NonlinearFactor& p, double tol = 1e-9) const override { const This *e = dynamic_cast(&p); bool areMeasurementsEqual = true; diff --git a/gtsam/slam/SmartProjectionFactor.h b/gtsam/slam/SmartProjectionFactor.h index 15d632cda..a7d85dd08 100644 --- a/gtsam/slam/SmartProjectionFactor.h +++ b/gtsam/slam/SmartProjectionFactor.h @@ -99,7 +99,7 @@ public: * @param keyFormatter optional formatter useful for printing Symbols */ void print(const std::string& s = "", const KeyFormatter& keyFormatter = - DefaultKeyFormatter) const { + DefaultKeyFormatter) const override { std::cout << s << "SmartProjectionFactor\n"; std::cout << "linearizationMode:\n" << params_.linearizationMode << std::endl; @@ -110,7 +110,7 @@ public: } /// equals - virtual bool equals(const NonlinearFactor& p, double tol = 1e-9) const { + bool equals(const NonlinearFactor& p, double tol = 1e-9) const override { const This *e = dynamic_cast(&p); return e && params_.linearizationMode == e->params_.linearizationMode && Base::equals(p, tol); @@ -305,8 +305,8 @@ public: } /// linearize - virtual boost::shared_ptr linearize( - const Values& values) const { + boost::shared_ptr linearize( + const Values& values) const override { return linearizeDamped(values); } @@ -409,7 +409,7 @@ public: } /// Calculate total reprojection error - virtual double error(const Values& values) const { + double error(const Values& values) const override { if (this->active(values)) { return totalReprojectionError(Base::cameras(values)); } else { // else of active flag diff --git a/gtsam/slam/SmartProjectionPoseFactor.h b/gtsam/slam/SmartProjectionPoseFactor.h index b5be46258..cccdf20d6 100644 --- a/gtsam/slam/SmartProjectionPoseFactor.h +++ b/gtsam/slam/SmartProjectionPoseFactor.h @@ -103,13 +103,13 @@ public: * @param keyFormatter optional formatter useful for printing Symbols */ void print(const std::string& s = "", const KeyFormatter& keyFormatter = - DefaultKeyFormatter) const { + DefaultKeyFormatter) const override { std::cout << s << "SmartProjectionPoseFactor, z = \n "; Base::print("", keyFormatter); } /// equals - virtual bool equals(const NonlinearFactor& p, double tol = 1e-9) const { + bool equals(const NonlinearFactor& p, double tol = 1e-9) const override { const This *e = dynamic_cast(&p); return e && Base::equals(p, tol); } @@ -117,7 +117,7 @@ public: /** * error calculates the error of the factor. */ - virtual double error(const Values& values) const { + double error(const Values& values) const override { if (this->active(values)) { return this->totalReprojectionError(cameras(values)); } else { // else of active flag @@ -136,7 +136,7 @@ public: * to keys involved in this factor * @return vector of Values */ - typename Base::Cameras cameras(const Values& values) const { + typename Base::Cameras cameras(const Values& values) const override { typename Base::Cameras cameras; for (const Key& k : this->keys_) { const Pose3 world_P_sensor_k = diff --git a/gtsam/slam/StereoFactor.h b/gtsam/slam/StereoFactor.h index 8828f5de7..6556723bd 100644 --- a/gtsam/slam/StereoFactor.h +++ b/gtsam/slam/StereoFactor.h @@ -91,7 +91,7 @@ public: virtual ~GenericStereoFactor() {} /// @return a deep copy of this factor - virtual gtsam::NonlinearFactor::shared_ptr clone() const { + gtsam::NonlinearFactor::shared_ptr clone() const override { return boost::static_pointer_cast( gtsam::NonlinearFactor::shared_ptr(new This(*this))); } @@ -100,7 +100,7 @@ public: * @param s optional string naming the factor * @param keyFormatter optional formatter useful for printing Symbols */ - void print(const std::string& s = "", const KeyFormatter& keyFormatter = DefaultKeyFormatter) const { + void print(const std::string& s = "", const KeyFormatter& keyFormatter = DefaultKeyFormatter) const override { Base::print(s, keyFormatter); measured_.print(s + ".z"); if(this->body_P_sensor_) @@ -110,7 +110,7 @@ public: /** * equals */ - virtual bool equals(const NonlinearFactor& f, double tol = 1e-9) const { + bool equals(const NonlinearFactor& f, double tol = 1e-9) const override { const GenericStereoFactor* e = dynamic_cast (&f); return e && Base::equals(f) @@ -120,7 +120,7 @@ public: /** h(x)-z */ Vector evaluateError(const Pose3& pose, const Point3& point, - boost::optional H1 = boost::none, boost::optional H2 = boost::none) const { + boost::optional H1 = boost::none, boost::optional H2 = boost::none) const override { try { if(body_P_sensor_) { if(H1) { diff --git a/gtsam/slam/TriangulationFactor.h b/gtsam/slam/TriangulationFactor.h index 811d92fbc..9d02ad321 100644 --- a/gtsam/slam/TriangulationFactor.h +++ b/gtsam/slam/TriangulationFactor.h @@ -90,7 +90,7 @@ public: } /// @return a deep copy of this factor - virtual gtsam::NonlinearFactor::shared_ptr clone() const { + gtsam::NonlinearFactor::shared_ptr clone() const override { return boost::static_pointer_cast( gtsam::NonlinearFactor::shared_ptr(new This(*this))); } @@ -101,7 +101,7 @@ public: * @param keyFormatter optional formatter useful for printing Symbols */ void print(const std::string& s = "", const KeyFormatter& keyFormatter = - DefaultKeyFormatter) const { + DefaultKeyFormatter) const override { std::cout << s << "TriangulationFactor,"; camera_.print("camera"); traits::Print(measured_, "z"); @@ -109,7 +109,7 @@ public: } /// equals - virtual bool equals(const NonlinearFactor& p, double tol = 1e-9) const { + bool equals(const NonlinearFactor& p, double tol = 1e-9) const override { const This *e = dynamic_cast(&p); return e && Base::equals(p, tol) && this->camera_.equals(e->camera_, tol) && traits::Equals(this->measured_, e->measured_, tol); @@ -117,7 +117,7 @@ public: /// Evaluate error h(x)-z and optionally derivatives Vector evaluateError(const Point3& point, boost::optional H2 = - boost::none) const { + boost::none) const override { try { return traits::Local(measured_, camera_.project2(point, boost::none, H2)); } catch (CheiralityException& e) { @@ -143,7 +143,7 @@ public: * \f$ Ax-b \approx h(x+\delta x)-z = h(x) + A \delta x - z \f$ * Hence \f$ b = z - h(x) = - \mathtt{error\_vector}(x) \f$ */ - boost::shared_ptr linearize(const Values& x) const { + boost::shared_ptr linearize(const Values& x) const override { // Only linearize if the factor is active if (!this->active(x)) return boost::shared_ptr(); diff --git a/gtsam/slam/tests/testSmartFactorBase.cpp b/gtsam/slam/tests/testSmartFactorBase.cpp index fd771f102..951cbf8f4 100644 --- a/gtsam/slam/tests/testSmartFactorBase.cpp +++ b/gtsam/slam/tests/testSmartFactorBase.cpp @@ -41,9 +41,9 @@ public: boost::optional body_P_sensor = boost::none, size_t expectedNumberCameras = 10) : Base(sharedNoiseModel, body_P_sensor, expectedNumberCameras) {} - virtual double error(const Values& values) const { return 0.0; } - virtual boost::shared_ptr linearize( - const Values& values) const { + double error(const Values& values) const override { return 0.0; } + boost::shared_ptr linearize( + const Values& values) const override { return boost::shared_ptr(new JacobianFactor()); } }; @@ -105,11 +105,11 @@ public: StereoFactor() {} StereoFactor(const SharedNoiseModel& sharedNoiseModel): Base(sharedNoiseModel) { } - virtual double error(const Values& values) const { + double error(const Values& values) const override { return 0.0; } - virtual boost::shared_ptr linearize( - const Values& values) const { + boost::shared_ptr linearize( + const Values& values) const override { return boost::shared_ptr(new JacobianFactor()); } }; diff --git a/gtsam/symbolic/SymbolicConditional.h b/gtsam/symbolic/SymbolicConditional.h index 0530af556..9163cdba6 100644 --- a/gtsam/symbolic/SymbolicConditional.h +++ b/gtsam/symbolic/SymbolicConditional.h @@ -105,7 +105,7 @@ namespace gtsam { /// @name Testable /** Print with optional formatter */ - void print(const std::string& str = "", const KeyFormatter& keyFormatter = DefaultKeyFormatter) const; + virtual void print(const std::string& str = "", const KeyFormatter& keyFormatter = DefaultKeyFormatter) const; /** Check equality */ bool equals(const This& c, double tol = 1e-9) const; diff --git a/gtsam_unstable/discrete/AllDiff.h b/gtsam_unstable/discrete/AllDiff.h index 3e7296593..80e700b29 100644 --- a/gtsam_unstable/discrete/AllDiff.h +++ b/gtsam_unstable/discrete/AllDiff.h @@ -34,11 +34,11 @@ namespace gtsam { AllDiff(const DiscreteKeys& dkeys); // print - virtual void print(const std::string& s = "", - const KeyFormatter& formatter = DefaultKeyFormatter) const; + void print(const std::string& s = "", + const KeyFormatter& formatter = DefaultKeyFormatter) const override; /// equals - bool equals(const DiscreteFactor& other, double tol) const { + bool equals(const DiscreteFactor& other, double tol) const override { if(!dynamic_cast(&other)) return false; else { @@ -50,13 +50,13 @@ namespace gtsam { } /// Calculate value = expensive ! - virtual double operator()(const Values& values) const; + double operator()(const Values& values) const override; /// Convert into a decisiontree, can be *very* expensive ! - virtual DecisionTreeFactor toDecisionTreeFactor() const; + DecisionTreeFactor toDecisionTreeFactor() const override; /// Multiply into a decisiontree - virtual DecisionTreeFactor operator*(const DecisionTreeFactor& f) const; + DecisionTreeFactor operator*(const DecisionTreeFactor& f) const override; /* * Ensure Arc-consistency @@ -65,13 +65,13 @@ namespace gtsam { * @param j domain to be checked * @param domains all other domains */ - bool ensureArcConsistency(size_t j, std::vector& domains) const; + bool ensureArcConsistency(size_t j, std::vector& domains) const override; /// Partially apply known values - virtual Constraint::shared_ptr partiallyApply(const Values&) const; + Constraint::shared_ptr partiallyApply(const Values&) const override; /// Partially apply known values, domain version - virtual Constraint::shared_ptr partiallyApply(const std::vector&) const; + Constraint::shared_ptr partiallyApply(const std::vector&) const override; }; } // namespace gtsam diff --git a/gtsam_unstable/discrete/BinaryAllDiff.h b/gtsam_unstable/discrete/BinaryAllDiff.h index 1ae5a008a..bbb60e2f1 100644 --- a/gtsam_unstable/discrete/BinaryAllDiff.h +++ b/gtsam_unstable/discrete/BinaryAllDiff.h @@ -33,14 +33,14 @@ namespace gtsam { } // print - virtual void print(const std::string& s = "", - const KeyFormatter& formatter = DefaultKeyFormatter) const { + void print(const std::string& s = "", + const KeyFormatter& formatter = DefaultKeyFormatter) const override { std::cout << s << "BinaryAllDiff on " << formatter(keys_[0]) << " and " << formatter(keys_[1]) << std::endl; } /// equals - bool equals(const DiscreteFactor& other, double tol) const { + bool equals(const DiscreteFactor& other, double tol) const override { if(!dynamic_cast(&other)) return false; else { @@ -50,12 +50,12 @@ namespace gtsam { } /// Calculate value - virtual double operator()(const Values& values) const { + double operator()(const Values& values) const override { return (double) (values.at(keys_[0]) != values.at(keys_[1])); } /// Convert into a decisiontree - virtual DecisionTreeFactor toDecisionTreeFactor() const { + DecisionTreeFactor toDecisionTreeFactor() const override { DiscreteKeys keys; keys.push_back(DiscreteKey(keys_[0],cardinality0_)); keys.push_back(DiscreteKey(keys_[1],cardinality1_)); @@ -68,7 +68,7 @@ namespace gtsam { } /// Multiply into a decisiontree - virtual DecisionTreeFactor operator*(const DecisionTreeFactor& f) const { + DecisionTreeFactor operator*(const DecisionTreeFactor& f) const override { // TODO: can we do this more efficiently? return toDecisionTreeFactor() * f; } @@ -79,20 +79,20 @@ namespace gtsam { * @param domains all other domains */ /// - bool ensureArcConsistency(size_t j, std::vector& domains) const { + bool ensureArcConsistency(size_t j, std::vector& domains) const override { // throw std::runtime_error( // "BinaryAllDiff::ensureArcConsistency not implemented"); return false; } /// Partially apply known values - virtual Constraint::shared_ptr partiallyApply(const Values&) const { + Constraint::shared_ptr partiallyApply(const Values&) const override { throw std::runtime_error("BinaryAllDiff::partiallyApply not implemented"); } /// Partially apply known values, domain version - virtual Constraint::shared_ptr partiallyApply( - const std::vector&) const { + Constraint::shared_ptr partiallyApply( + const std::vector&) const override { throw std::runtime_error("BinaryAllDiff::partiallyApply not implemented"); } }; diff --git a/gtsam_unstable/discrete/Domain.h b/gtsam_unstable/discrete/Domain.h index 5dd597e20..5acc5a08f 100644 --- a/gtsam_unstable/discrete/Domain.h +++ b/gtsam_unstable/discrete/Domain.h @@ -66,11 +66,11 @@ namespace gtsam { } // print - virtual void print(const std::string& s = "", - const KeyFormatter& formatter = DefaultKeyFormatter) const; + void print(const std::string& s = "", + const KeyFormatter& formatter = DefaultKeyFormatter) const override; /// equals - bool equals(const DiscreteFactor& other, double tol) const { + bool equals(const DiscreteFactor& other, double tol) const override { if(!dynamic_cast(&other)) return false; else { @@ -84,20 +84,20 @@ namespace gtsam { } /// Calculate value - virtual double operator()(const Values& values) const; + double operator()(const Values& values) const override; /// Convert into a decisiontree - virtual DecisionTreeFactor toDecisionTreeFactor() const; + DecisionTreeFactor toDecisionTreeFactor() const override; /// Multiply into a decisiontree - virtual DecisionTreeFactor operator*(const DecisionTreeFactor& f) const; + DecisionTreeFactor operator*(const DecisionTreeFactor& f) const override; /* * Ensure Arc-consistency * @param j domain to be checked * @param domains all other domains */ - bool ensureArcConsistency(size_t j, std::vector& domains) const; + bool ensureArcConsistency(size_t j, std::vector& domains) const override; /** * Check for a value in domain that does not occur in any other connected domain. @@ -107,12 +107,11 @@ namespace gtsam { bool checkAllDiff(const KeyVector keys, std::vector& domains); /// Partially apply known values - virtual Constraint::shared_ptr partiallyApply( - const Values& values) const; + Constraint::shared_ptr partiallyApply(const Values& values) const override; /// Partially apply known values, domain version - virtual Constraint::shared_ptr partiallyApply( - const std::vector& domains) const; + Constraint::shared_ptr partiallyApply( + const std::vector& domains) const override; }; } // namespace gtsam diff --git a/gtsam_unstable/discrete/SingleValue.h b/gtsam_unstable/discrete/SingleValue.h index 43f06956d..c4d2addec 100644 --- a/gtsam_unstable/discrete/SingleValue.h +++ b/gtsam_unstable/discrete/SingleValue.h @@ -42,11 +42,11 @@ namespace gtsam { } // print - virtual void print(const std::string& s = "", - const KeyFormatter& formatter = DefaultKeyFormatter) const; + void print(const std::string& s = "", + const KeyFormatter& formatter = DefaultKeyFormatter) const override; /// equals - bool equals(const DiscreteFactor& other, double tol) const { + bool equals(const DiscreteFactor& other, double tol) const override { if(!dynamic_cast(&other)) return false; else { @@ -56,28 +56,27 @@ namespace gtsam { } /// Calculate value - virtual double operator()(const Values& values) const; + double operator()(const Values& values) const override; /// Convert into a decisiontree - virtual DecisionTreeFactor toDecisionTreeFactor() const; + DecisionTreeFactor toDecisionTreeFactor() const override; /// Multiply into a decisiontree - virtual DecisionTreeFactor operator*(const DecisionTreeFactor& f) const; + DecisionTreeFactor operator*(const DecisionTreeFactor& f) const override; /* * Ensure Arc-consistency * @param j domain to be checked * @param domains all other domains */ - bool ensureArcConsistency(size_t j, std::vector& domains) const; + bool ensureArcConsistency(size_t j, std::vector& domains) const override; /// Partially apply known values - virtual Constraint::shared_ptr partiallyApply( - const Values& values) const; + Constraint::shared_ptr partiallyApply(const Values& values) const override; /// Partially apply known values, domain version - virtual Constraint::shared_ptr partiallyApply( - const std::vector& domains) const; + Constraint::shared_ptr partiallyApply( + const std::vector& domains) const override; }; } // namespace gtsam diff --git a/gtsam_unstable/dynamics/FullIMUFactor.h b/gtsam_unstable/dynamics/FullIMUFactor.h index 1c5ade5b6..c8c351d7a 100644 --- a/gtsam_unstable/dynamics/FullIMUFactor.h +++ b/gtsam_unstable/dynamics/FullIMUFactor.h @@ -51,12 +51,12 @@ public: virtual ~FullIMUFactor() {} /// @return a deep copy of this factor - virtual gtsam::NonlinearFactor::shared_ptr clone() const { + gtsam::NonlinearFactor::shared_ptr clone() const override { return boost::static_pointer_cast( gtsam::NonlinearFactor::shared_ptr(new This(*this))); } /** Check if two factors are equal */ - virtual bool equals(const NonlinearFactor& e, double tol = 1e-9) const { + bool equals(const NonlinearFactor& e, double tol = 1e-9) const override { const This* const f = dynamic_cast(&e); return f && Base::equals(e) && equal_with_abs_tol(accel_, f->accel_, tol) && @@ -64,7 +64,7 @@ public: std::abs(dt_ - f->dt_) < tol; } - void print(const std::string& s="", const gtsam::KeyFormatter& formatter = gtsam::DefaultKeyFormatter) const { + void print(const std::string& s="", const gtsam::KeyFormatter& formatter = gtsam::DefaultKeyFormatter) const override { std::string a = "FullIMUFactor: " + s; Base::print(a, formatter); gtsam::print((Vector)accel_, "accel"); @@ -81,9 +81,9 @@ public: * Error evaluation with optional derivatives - calculates * z - h(x1,x2) */ - virtual Vector evaluateError(const PoseRTV& x1, const PoseRTV& x2, + Vector evaluateError(const PoseRTV& x1, const PoseRTV& x2, boost::optional H1 = boost::none, - boost::optional H2 = boost::none) const { + boost::optional H2 = boost::none) const override { Vector9 z; z.head(3).operator=(accel_); // Strange syntax to work around ambiguous operator error with clang z.segment(3, 3).operator=(gyro_); // Strange syntax to work around ambiguous operator error with clang diff --git a/gtsam_unstable/dynamics/IMUFactor.h b/gtsam_unstable/dynamics/IMUFactor.h index bb0a354ee..fb864a78d 100644 --- a/gtsam_unstable/dynamics/IMUFactor.h +++ b/gtsam_unstable/dynamics/IMUFactor.h @@ -44,12 +44,12 @@ public: virtual ~IMUFactor() {} /// @return a deep copy of this factor - virtual gtsam::NonlinearFactor::shared_ptr clone() const { + gtsam::NonlinearFactor::shared_ptr clone() const override { return boost::static_pointer_cast( gtsam::NonlinearFactor::shared_ptr(new This(*this))); } /** Check if two factors are equal */ - virtual bool equals(const NonlinearFactor& e, double tol = 1e-9) const { + bool equals(const NonlinearFactor& e, double tol = 1e-9) const override { const This* const f = dynamic_cast(&e); return f && Base::equals(e) && equal_with_abs_tol(accel_, f->accel_, tol) && @@ -57,7 +57,7 @@ public: std::abs(dt_ - f->dt_) < tol; } - void print(const std::string& s="", const gtsam::KeyFormatter& formatter = gtsam::DefaultKeyFormatter) const { + void print(const std::string& s="", const gtsam::KeyFormatter& formatter = gtsam::DefaultKeyFormatter) const override { std::string a = "IMUFactor: " + s; Base::print(a, formatter); gtsam::print((Vector)accel_, "accel"); @@ -74,9 +74,9 @@ public: * Error evaluation with optional derivatives - calculates * z - h(x1,x2) */ - virtual Vector evaluateError(const PoseRTV& x1, const PoseRTV& x2, + Vector evaluateError(const PoseRTV& x1, const PoseRTV& x2, boost::optional H1 = boost::none, - boost::optional H2 = boost::none) const { + boost::optional H2 = boost::none) const override { const Vector6 meas = z(); if (H1) *H1 = numericalDerivative21( boost::bind(This::predict_proxy, _1, _2, dt_, meas), x1, x2, 1e-5); diff --git a/gtsam_unstable/dynamics/Pendulum.h b/gtsam_unstable/dynamics/Pendulum.h index 209456a62..470d7108b 100644 --- a/gtsam_unstable/dynamics/Pendulum.h +++ b/gtsam_unstable/dynamics/Pendulum.h @@ -40,7 +40,7 @@ public: : Base(noiseModel::Constrained::All(1, std::abs(mu)), k1, k, velKey), h_(h) {} /// @return a deep copy of this factor - virtual gtsam::NonlinearFactor::shared_ptr clone() const { + gtsam::NonlinearFactor::shared_ptr clone() const override { return boost::static_pointer_cast( gtsam::NonlinearFactor::shared_ptr(new PendulumFactor1(*this))); } @@ -48,7 +48,7 @@ public: Vector evaluateError(const double& qk1, const double& qk, const double& v, boost::optional H1 = boost::none, boost::optional H2 = boost::none, - boost::optional H3 = boost::none) const { + boost::optional H3 = boost::none) const override { const size_t p = 1; if (H1) *H1 = -Matrix::Identity(p,p); if (H2) *H2 = Matrix::Identity(p,p); @@ -88,7 +88,7 @@ public: : Base(noiseModel::Constrained::All(1, std::abs(mu)), vk1, vk, qkey), h_(h), g_(g), r_(r) {} /// @return a deep copy of this factor - virtual gtsam::NonlinearFactor::shared_ptr clone() const { + gtsam::NonlinearFactor::shared_ptr clone() const override { return boost::static_pointer_cast( gtsam::NonlinearFactor::shared_ptr(new PendulumFactor2(*this))); } @@ -96,7 +96,7 @@ public: Vector evaluateError(const double & vk1, const double & vk, const double & q, boost::optional H1 = boost::none, boost::optional H2 = boost::none, - boost::optional H3 = boost::none) const { + boost::optional H3 = boost::none) const override { const size_t p = 1; if (H1) *H1 = -Matrix::Identity(p,p); if (H2) *H2 = Matrix::Identity(p,p); @@ -139,7 +139,7 @@ public: h_(h), m_(m), r_(r), g_(g), alpha_(alpha) {} /// @return a deep copy of this factor - virtual gtsam::NonlinearFactor::shared_ptr clone() const { + gtsam::NonlinearFactor::shared_ptr clone() const override { return boost::static_pointer_cast( gtsam::NonlinearFactor::shared_ptr(new PendulumFactorPk(*this))); } @@ -147,7 +147,7 @@ public: Vector evaluateError(const double & pk, const double & qk, const double & qk1, boost::optional H1 = boost::none, boost::optional H2 = boost::none, - boost::optional H3 = boost::none) const { + boost::optional H3 = boost::none) const override { const size_t p = 1; double qmid = (1-alpha_)*qk + alpha_*qk1; @@ -195,7 +195,7 @@ public: h_(h), m_(m), r_(r), g_(g), alpha_(alpha) {} /// @return a deep copy of this factor - virtual gtsam::NonlinearFactor::shared_ptr clone() const { + gtsam::NonlinearFactor::shared_ptr clone() const override { return boost::static_pointer_cast( gtsam::NonlinearFactor::shared_ptr(new PendulumFactorPk1(*this))); } @@ -203,7 +203,7 @@ public: Vector evaluateError(const double & pk1, const double & qk, const double & qk1, boost::optional H1 = boost::none, boost::optional H2 = boost::none, - boost::optional H3 = boost::none) const { + boost::optional H3 = boost::none) const override { const size_t p = 1; double qmid = (1-alpha_)*qk + alpha_*qk1; diff --git a/gtsam_unstable/dynamics/SimpleHelicopter.h b/gtsam_unstable/dynamics/SimpleHelicopter.h index f38c256b1..42ef04f84 100644 --- a/gtsam_unstable/dynamics/SimpleHelicopter.h +++ b/gtsam_unstable/dynamics/SimpleHelicopter.h @@ -36,7 +36,7 @@ public: virtual ~Reconstruction() {} /// @return a deep copy of this factor - virtual gtsam::NonlinearFactor::shared_ptr clone() const { + gtsam::NonlinearFactor::shared_ptr clone() const override { return boost::static_pointer_cast( gtsam::NonlinearFactor::shared_ptr(new Reconstruction(*this))); } @@ -44,7 +44,7 @@ public: Vector evaluateError(const Pose3& gk1, const Pose3& gk, const Vector6& xik, boost::optional H1 = boost::none, boost::optional H2 = boost::none, - boost::optional H3 = boost::none) const { + boost::optional H3 = boost::none) const override { Matrix6 D_exphxi_xi; Pose3 exphxi = Pose3::Expmap(h_ * xik, H3 ? &D_exphxi_xi : 0); @@ -98,7 +98,7 @@ public: virtual ~DiscreteEulerPoincareHelicopter() {} /// @return a deep copy of this factor - virtual gtsam::NonlinearFactor::shared_ptr clone() const { + gtsam::NonlinearFactor::shared_ptr clone() const override { return boost::static_pointer_cast( gtsam::NonlinearFactor::shared_ptr(new DiscreteEulerPoincareHelicopter(*this))); } @@ -110,7 +110,7 @@ public: Vector evaluateError(const Vector6& xik, const Vector6& xik_1, const Pose3& gk, boost::optional H1 = boost::none, boost::optional H2 = boost::none, - boost::optional H3 = boost::none) const { + boost::optional H3 = boost::none) const override { Vector muk = Inertia_*xik; Vector muk_1 = Inertia_*xik_1; diff --git a/gtsam_unstable/dynamics/VelocityConstraint.h b/gtsam_unstable/dynamics/VelocityConstraint.h index ed3797015..986d8e271 100644 --- a/gtsam_unstable/dynamics/VelocityConstraint.h +++ b/gtsam_unstable/dynamics/VelocityConstraint.h @@ -73,16 +73,16 @@ public: virtual ~VelocityConstraint() {} /// @return a deep copy of this factor - virtual gtsam::NonlinearFactor::shared_ptr clone() const { + gtsam::NonlinearFactor::shared_ptr clone() const override { return boost::static_pointer_cast( gtsam::NonlinearFactor::shared_ptr(new VelocityConstraint(*this))); } /** * Calculates the error for trapezoidal model given */ - virtual gtsam::Vector evaluateError(const PoseRTV& x1, const PoseRTV& x2, + gtsam::Vector evaluateError(const PoseRTV& x1, const PoseRTV& x2, boost::optional H1=boost::none, - boost::optional H2=boost::none) const { + boost::optional H2=boost::none) const override { if (H1) *H1 = gtsam::numericalDerivative21( boost::bind(VelocityConstraint::evaluateError_, _1, _2, dt_, integration_mode_), x1, x2, 1e-5); if (H2) *H2 = gtsam::numericalDerivative22( @@ -90,7 +90,7 @@ public: return evaluateError_(x1, x2, dt_, integration_mode_); } - virtual void print(const std::string& s = "", const gtsam::KeyFormatter& formatter = gtsam::DefaultKeyFormatter) const { + void print(const std::string& s = "", const gtsam::KeyFormatter& formatter = gtsam::DefaultKeyFormatter) const override { std::string a = "VelocityConstraint: " + s; Base::print(a, formatter); switch(integration_mode_) { diff --git a/gtsam_unstable/dynamics/VelocityConstraint3.h b/gtsam_unstable/dynamics/VelocityConstraint3.h index 721d0265b..f6cd8ccc4 100644 --- a/gtsam_unstable/dynamics/VelocityConstraint3.h +++ b/gtsam_unstable/dynamics/VelocityConstraint3.h @@ -31,7 +31,7 @@ public: virtual ~VelocityConstraint3() {} /// @return a deep copy of this factor - virtual gtsam::NonlinearFactor::shared_ptr clone() const { + gtsam::NonlinearFactor::shared_ptr clone() const override { return boost::static_pointer_cast( gtsam::NonlinearFactor::shared_ptr(new VelocityConstraint3(*this))); } @@ -39,7 +39,7 @@ public: Vector evaluateError(const double& x1, const double& x2, const double& v, boost::optional H1 = boost::none, boost::optional H2 = boost::none, - boost::optional H3 = boost::none) const { + boost::optional H3 = boost::none) const override { const size_t p = 1; if (H1) *H1 = Matrix::Identity(p,p); if (H2) *H2 = -Matrix::Identity(p,p); diff --git a/gtsam_unstable/linear/InfeasibleInitialValues.h b/gtsam_unstable/linear/InfeasibleInitialValues.h index 60adb872e..6f589d0c3 100644 --- a/gtsam_unstable/linear/InfeasibleInitialValues.h +++ b/gtsam_unstable/linear/InfeasibleInitialValues.h @@ -29,10 +29,10 @@ public: InfeasibleInitialValues() { } - virtual ~InfeasibleInitialValues() throw () { + virtual ~InfeasibleInitialValues() noexcept { } - virtual const char *what() const throw () { + const char *what() const noexcept override { if (description_.empty()) description_ = "An infeasible initial value was provided for the solver.\n"; diff --git a/gtsam_unstable/linear/InfeasibleOrUnboundedProblem.h b/gtsam_unstable/linear/InfeasibleOrUnboundedProblem.h index 2184e9f52..25742d61f 100644 --- a/gtsam_unstable/linear/InfeasibleOrUnboundedProblem.h +++ b/gtsam_unstable/linear/InfeasibleOrUnboundedProblem.h @@ -25,10 +25,10 @@ class InfeasibleOrUnboundedProblem: public ThreadsafeException< public: InfeasibleOrUnboundedProblem() { } - virtual ~InfeasibleOrUnboundedProblem() throw () { + virtual ~InfeasibleOrUnboundedProblem() noexcept { } - virtual const char* what() const throw () { + const char* what() const noexcept override { if (description_.empty()) description_ = "The problem is either infeasible or unbounded.\n"; return description_.c_str(); diff --git a/gtsam_unstable/linear/LinearCost.h b/gtsam_unstable/linear/LinearCost.h index b489510af..c22c389be 100644 --- a/gtsam_unstable/linear/LinearCost.h +++ b/gtsam_unstable/linear/LinearCost.h @@ -88,18 +88,18 @@ public: } /** equals */ - virtual bool equals(const GaussianFactor& lf, double tol = 1e-9) const { + bool equals(const GaussianFactor& lf, double tol = 1e-9) const override { return Base::equals(lf, tol); } /** print */ - virtual void print(const std::string& s = "", const KeyFormatter& formatter = - DefaultKeyFormatter) const { + void print(const std::string& s = "", const KeyFormatter& formatter = + DefaultKeyFormatter) const override { Base::print(s + " LinearCost: ", formatter); } /** Clone this LinearCost */ - virtual GaussianFactor::shared_ptr clone() const { + GaussianFactor::shared_ptr clone() const override { return boost::static_pointer_cast < GaussianFactor > (boost::make_shared < LinearCost > (*this)); } @@ -110,7 +110,7 @@ public: } /** Special error for single-valued inequality constraints. */ - virtual double error(const VectorValues& c) const { + double error(const VectorValues& c) const override { return error_vector(c)[0]; } }; diff --git a/gtsam_unstable/linear/LinearEquality.h b/gtsam_unstable/linear/LinearEquality.h index 2463ef31c..d960d8336 100644 --- a/gtsam_unstable/linear/LinearEquality.h +++ b/gtsam_unstable/linear/LinearEquality.h @@ -89,18 +89,18 @@ public: } /** equals */ - virtual bool equals(const GaussianFactor& lf, double tol = 1e-9) const { + bool equals(const GaussianFactor& lf, double tol = 1e-9) const override { return Base::equals(lf, tol); } /** print */ - virtual void print(const std::string& s = "", const KeyFormatter& formatter = - DefaultKeyFormatter) const { + void print(const std::string& s = "", const KeyFormatter& formatter = + DefaultKeyFormatter) const override { Base::print(s, formatter); } /** Clone this LinearEquality */ - virtual GaussianFactor::shared_ptr clone() const { + GaussianFactor::shared_ptr clone() const override { return boost::static_pointer_cast < GaussianFactor > (boost::make_shared < LinearEquality > (*this)); } @@ -124,7 +124,7 @@ public: * I think it should be zero, as this function is meant for objective cost. * But the name "error" can be misleading. * TODO: confirm with Frank!! */ - virtual double error(const VectorValues& c) const { + double error(const VectorValues& c) const override { return 0.0; } diff --git a/gtsam_unstable/linear/LinearInequality.h b/gtsam_unstable/linear/LinearInequality.h index 1a31bd4e4..d353afc46 100644 --- a/gtsam_unstable/linear/LinearInequality.h +++ b/gtsam_unstable/linear/LinearInequality.h @@ -100,13 +100,13 @@ public: } /** equals */ - virtual bool equals(const GaussianFactor& lf, double tol = 1e-9) const { + bool equals(const GaussianFactor& lf, double tol = 1e-9) const override { return Base::equals(lf, tol); } /** print */ - virtual void print(const std::string& s = "", const KeyFormatter& formatter = - DefaultKeyFormatter) const { + void print(const std::string& s = "", const KeyFormatter& formatter = + DefaultKeyFormatter) const override { if (active()) Base::print(s + " Active", formatter); else @@ -114,7 +114,7 @@ public: } /** Clone this LinearInequality */ - virtual GaussianFactor::shared_ptr clone() const { + GaussianFactor::shared_ptr clone() const override { return boost::static_pointer_cast < GaussianFactor > (boost::make_shared < LinearInequality > (*this)); } @@ -145,7 +145,7 @@ public: } /** Special error for single-valued inequality constraints. */ - virtual double error(const VectorValues& c) const { + double error(const VectorValues& c) const override { return error_vector(c)[0]; } diff --git a/gtsam_unstable/linear/QPSParserException.h b/gtsam_unstable/linear/QPSParserException.h index ed4c79bdd..ef14ed430 100644 --- a/gtsam_unstable/linear/QPSParserException.h +++ b/gtsam_unstable/linear/QPSParserException.h @@ -25,10 +25,10 @@ public: QPSParserException() { } - virtual ~QPSParserException() throw () { + virtual ~QPSParserException() noexcept { } - virtual const char *what() const throw () { + const char *what() const noexcept override { if (description_.empty()) description_ = "There is a problem parsing the QPS file.\n"; return description_.c_str(); diff --git a/gtsam_unstable/nonlinear/BatchFixedLagSmoother.h b/gtsam_unstable/nonlinear/BatchFixedLagSmoother.h index d71cdd409..2291642aa 100644 --- a/gtsam_unstable/nonlinear/BatchFixedLagSmoother.h +++ b/gtsam_unstable/nonlinear/BatchFixedLagSmoother.h @@ -41,10 +41,10 @@ public: virtual ~BatchFixedLagSmoother() { }; /** Print the factor for debugging and testing (implementing Testable) */ - virtual void print(const std::string& s = "BatchFixedLagSmoother:\n", const KeyFormatter& keyFormatter = DefaultKeyFormatter) const override; + void print(const std::string& s = "BatchFixedLagSmoother:\n", const KeyFormatter& keyFormatter = DefaultKeyFormatter) const override; /** Check if two IncrementalFixedLagSmoother Objects are equal */ - virtual bool equals(const FixedLagSmoother& rhs, double tol = 1e-9) const override; + bool equals(const FixedLagSmoother& rhs, double tol = 1e-9) const override; /** Add new factors, updating the solution and relinearizing as needed. */ Result update(const NonlinearFactorGraph& newFactors = NonlinearFactorGraph(), diff --git a/gtsam_unstable/nonlinear/ConcurrentBatchFilter.h b/gtsam_unstable/nonlinear/ConcurrentBatchFilter.h index d04f579eb..c99c67492 100644 --- a/gtsam_unstable/nonlinear/ConcurrentBatchFilter.h +++ b/gtsam_unstable/nonlinear/ConcurrentBatchFilter.h @@ -67,10 +67,10 @@ public: virtual ~ConcurrentBatchFilter() {}; /** Implement a GTSAM standard 'print' function */ - virtual void print(const std::string& s = "Concurrent Batch Filter:\n", const KeyFormatter& keyFormatter = DefaultKeyFormatter) const; + void print(const std::string& s = "Concurrent Batch Filter:\n", const KeyFormatter& keyFormatter = DefaultKeyFormatter) const override; /** Check if two Concurrent Filters are equal */ - virtual bool equals(const ConcurrentFilter& rhs, double tol = 1e-9) const; + bool equals(const ConcurrentFilter& rhs, double tol = 1e-9) const override; /** Access the current set of factors */ const NonlinearFactorGraph& getFactors() const { @@ -130,7 +130,7 @@ public: * Perform any required operations before the synchronization process starts. * Called by 'synchronize' */ - virtual void presync(); + virtual void presync() override; /** * Populate the provided containers with factors that constitute the filter branch summarization @@ -139,7 +139,7 @@ public: * @param summarizedFactors The summarized factors for the filter branch * @param rootValues The linearization points of the root clique variables */ - virtual void getSummarizedFactors(NonlinearFactorGraph& filterSummarization, Values& filterSummarizationValues); + void getSummarizedFactors(NonlinearFactorGraph& filterSummarization, Values& filterSummarizationValues) override; /** * Populate the provided containers with factors being sent to the smoother from the filter. These @@ -149,20 +149,20 @@ public: * @param smootherFactors The new factors to be added to the smoother * @param smootherValues The linearization points of any new variables */ - virtual void getSmootherFactors(NonlinearFactorGraph& smootherFactors, Values& smootherValues); + void getSmootherFactors(NonlinearFactorGraph& smootherFactors, Values& smootherValues) override; /** * Apply the updated version of the smoother branch summarized factors. * * @param summarizedFactors An updated version of the smoother branch summarized factors */ - virtual void synchronize(const NonlinearFactorGraph& smootherSummarization, const Values& smootherSummarizationValues); + void synchronize(const NonlinearFactorGraph& smootherSummarization, const Values& smootherSummarizationValues) override; /** * Perform any required operations after the synchronization process finishes. * Called by 'synchronize' */ - virtual void postsync(); + virtual void postsync() override; protected: diff --git a/gtsam_unstable/nonlinear/ConcurrentBatchSmoother.h b/gtsam_unstable/nonlinear/ConcurrentBatchSmoother.h index 67a1ef4f3..364d02caf 100644 --- a/gtsam_unstable/nonlinear/ConcurrentBatchSmoother.h +++ b/gtsam_unstable/nonlinear/ConcurrentBatchSmoother.h @@ -60,10 +60,10 @@ public: virtual ~ConcurrentBatchSmoother() {}; /** Implement a GTSAM standard 'print' function */ - virtual void print(const std::string& s = "Concurrent Batch Smoother:\n", const KeyFormatter& keyFormatter = DefaultKeyFormatter) const; + void print(const std::string& s = "Concurrent Batch Smoother:\n", const KeyFormatter& keyFormatter = DefaultKeyFormatter) const override; /** Check if two Concurrent Smoothers are equal */ - virtual bool equals(const ConcurrentSmoother& rhs, double tol = 1e-9) const; + bool equals(const ConcurrentSmoother& rhs, double tol = 1e-9) const override; /** Access the current set of factors */ const NonlinearFactorGraph& getFactors() const { @@ -124,7 +124,7 @@ public: * Perform any required operations before the synchronization process starts. * Called by 'synchronize' */ - virtual void presync(); + virtual void presync() override; /** * Populate the provided containers with factors that constitute the smoother branch summarization @@ -132,7 +132,7 @@ public: * * @param summarizedFactors The summarized factors for the filter branch */ - virtual void getSummarizedFactors(NonlinearFactorGraph& summarizedFactors, Values& separatorValues); + void getSummarizedFactors(NonlinearFactorGraph& summarizedFactors, Values& separatorValues) override; /** * Apply the new smoother factors sent by the filter, and the updated version of the filter @@ -143,14 +143,14 @@ public: * @param summarizedFactors An updated version of the filter branch summarized factors * @param rootValues The linearization point of the root variables */ - virtual void synchronize(const NonlinearFactorGraph& smootherFactors, const Values& smootherValues, - const NonlinearFactorGraph& summarizedFactors, const Values& separatorValues); + void synchronize(const NonlinearFactorGraph& smootherFactors, const Values& smootherValues, + const NonlinearFactorGraph& summarizedFactors, const Values& separatorValues) override; /** * Perform any required operations after the synchronization process finishes. * Called by 'synchronize' */ - virtual void postsync(); + virtual void postsync() override; protected: diff --git a/gtsam_unstable/nonlinear/ConcurrentIncrementalFilter.h b/gtsam_unstable/nonlinear/ConcurrentIncrementalFilter.h index e01919048..d0525a4da 100644 --- a/gtsam_unstable/nonlinear/ConcurrentIncrementalFilter.h +++ b/gtsam_unstable/nonlinear/ConcurrentIncrementalFilter.h @@ -67,10 +67,10 @@ public: virtual ~ConcurrentIncrementalFilter() {}; /** Implement a GTSAM standard 'print' function */ - virtual void print(const std::string& s = "Concurrent Incremental Filter:\n", const KeyFormatter& keyFormatter = DefaultKeyFormatter) const; + void print(const std::string& s = "Concurrent Incremental Filter:\n", const KeyFormatter& keyFormatter = DefaultKeyFormatter) const override; /** Check if two Concurrent Filters are equal */ - virtual bool equals(const ConcurrentFilter& rhs, double tol = 1e-9) const; + bool equals(const ConcurrentFilter& rhs, double tol = 1e-9) const override; /** Access the current set of factors */ const NonlinearFactorGraph& getFactors() const { @@ -130,7 +130,7 @@ public: * Perform any required operations before the synchronization process starts. * Called by 'synchronize' */ - virtual void presync(); + void presync() override; /** * Populate the provided containers with factors that constitute the filter branch summarization @@ -139,7 +139,7 @@ public: * @param summarizedFactors The summarized factors for the filter branch * @param rootValues The linearization points of the root clique variables */ - virtual void getSummarizedFactors(NonlinearFactorGraph& filterSummarization, Values& filterSummarizationValues); + void getSummarizedFactors(NonlinearFactorGraph& filterSummarization, Values& filterSummarizationValues) override; /** * Populate the provided containers with factors being sent to the smoother from the filter. These @@ -149,20 +149,20 @@ public: * @param smootherFactors The new factors to be added to the smoother * @param smootherValues The linearization points of any new variables */ - virtual void getSmootherFactors(NonlinearFactorGraph& smootherFactors, Values& smootherValues); + void getSmootherFactors(NonlinearFactorGraph& smootherFactors, Values& smootherValues) override; /** * Apply the updated version of the smoother branch summarized factors. * * @param summarizedFactors An updated version of the smoother branch summarized factors */ - virtual void synchronize(const NonlinearFactorGraph& smootherSummarization, const Values& smootherSummarizationValues); + void synchronize(const NonlinearFactorGraph& smootherSummarization, const Values& smootherSummarizationValues) override; /** * Perform any required operations after the synchronization process finishes. * Called by 'synchronize' */ - virtual void postsync(); + void postsync() override; protected: diff --git a/gtsam_unstable/nonlinear/ConcurrentIncrementalSmoother.h b/gtsam_unstable/nonlinear/ConcurrentIncrementalSmoother.h index ec95e1ec8..8848b6a43 100644 --- a/gtsam_unstable/nonlinear/ConcurrentIncrementalSmoother.h +++ b/gtsam_unstable/nonlinear/ConcurrentIncrementalSmoother.h @@ -57,10 +57,10 @@ public: virtual ~ConcurrentIncrementalSmoother() {}; /** Implement a GTSAM standard 'print' function */ - virtual void print(const std::string& s = "Concurrent Incremental Smoother:\n", const KeyFormatter& keyFormatter = DefaultKeyFormatter) const; + void print(const std::string& s = "Concurrent Incremental Smoother:\n", const KeyFormatter& keyFormatter = DefaultKeyFormatter) const override; /** Check if two Concurrent Smoothers are equal */ - virtual bool equals(const ConcurrentSmoother& rhs, double tol = 1e-9) const; + bool equals(const ConcurrentSmoother& rhs, double tol = 1e-9) const override; /** Access the current set of factors */ const NonlinearFactorGraph& getFactors() const { @@ -115,7 +115,7 @@ public: * Perform any required operations before the synchronization process starts. * Called by 'synchronize' */ - virtual void presync(); + void presync() override; /** * Populate the provided containers with factors that constitute the smoother branch summarization @@ -123,7 +123,7 @@ public: * * @param summarizedFactors The summarized factors for the filter branch */ - virtual void getSummarizedFactors(NonlinearFactorGraph& summarizedFactors, Values& separatorValues); + void getSummarizedFactors(NonlinearFactorGraph& summarizedFactors, Values& separatorValues) override; /** * Apply the new smoother factors sent by the filter, and the updated version of the filter @@ -134,14 +134,14 @@ public: * @param summarizedFactors An updated version of the filter branch summarized factors * @param rootValues The linearization point of the root variables */ - virtual void synchronize(const NonlinearFactorGraph& smootherFactors, const Values& smootherValues, - const NonlinearFactorGraph& summarizedFactors, const Values& separatorValues); + void synchronize(const NonlinearFactorGraph& smootherFactors, const Values& smootherValues, + const NonlinearFactorGraph& summarizedFactors, const Values& separatorValues) override; /** * Perform any required operations after the synchronization process finishes. * Called by 'synchronize' */ - virtual void postsync(); + void postsync() override; protected: diff --git a/gtsam_unstable/nonlinear/LinearizedFactor.h b/gtsam_unstable/nonlinear/LinearizedFactor.h index 128889b82..caf67de21 100644 --- a/gtsam_unstable/nonlinear/LinearizedFactor.h +++ b/gtsam_unstable/nonlinear/LinearizedFactor.h @@ -112,17 +112,17 @@ public: virtual ~LinearizedJacobianFactor() {} /// @return a deep copy of this factor - virtual gtsam::NonlinearFactor::shared_ptr clone() const { + gtsam::NonlinearFactor::shared_ptr clone() const override { return boost::static_pointer_cast( gtsam::NonlinearFactor::shared_ptr(new This(*this))); } // Testable /** print function */ - virtual void print(const std::string& s="", const KeyFormatter& keyFormatter = DefaultKeyFormatter) const; + void print(const std::string& s="", const KeyFormatter& keyFormatter = DefaultKeyFormatter) const override; /** equals function with optional tolerance */ - virtual bool equals(const NonlinearFactor& expected, double tol = 1e-9) const; + bool equals(const NonlinearFactor& expected, double tol = 1e-9) const override; // access functions const constBVector b() const { return Ab_(size()).col(0); } @@ -130,17 +130,17 @@ public: const constABlock A(Key key) const { return Ab_(std::find(begin(), end(), key) - begin()); } /** get the dimension of the factor (number of rows on linearization) */ - size_t dim() const { return Ab_.rows(); }; + size_t dim() const override { return Ab_.rows(); }; /** Calculate the error of the factor */ - double error(const Values& c) const; + double error(const Values& c) const override; /** * linearize to a GaussianFactor * Reimplemented from NoiseModelFactor to directly copy out the * matrices and only update the RHS b with an updated residual */ - boost::shared_ptr linearize(const Values& c) const; + boost::shared_ptr linearize(const Values& c) const override; /** (A*x-b) */ Vector error_vector(const Values& c) const; @@ -202,17 +202,17 @@ public: virtual ~LinearizedHessianFactor() {} /// @return a deep copy of this factor - virtual gtsam::NonlinearFactor::shared_ptr clone() const { + gtsam::NonlinearFactor::shared_ptr clone() const override { return boost::static_pointer_cast( gtsam::NonlinearFactor::shared_ptr(new This(*this))); } // Testable /** print function */ - virtual void print(const std::string& s="", const KeyFormatter& keyFormatter = DefaultKeyFormatter) const; + void print(const std::string& s="", const KeyFormatter& keyFormatter = DefaultKeyFormatter) const override; /** equals function with optional tolerance */ - virtual bool equals(const NonlinearFactor& expected, double tol = 1e-9) const; + bool equals(const NonlinearFactor& expected, double tol = 1e-9) const override; /** Return the constant term \f$ f \f$ as described above * @return The constant term \f$ f \f$ @@ -261,17 +261,17 @@ public: } /** get the dimension of the factor (number of rows on linearization) */ - size_t dim() const { return info_.rows() - 1; } + size_t dim() const override { return info_.rows() - 1; } /** Calculate the error of the factor */ - double error(const Values& c) const; + double error(const Values& c) const override; /** * linearize to a GaussianFactor * Reimplemented from NoiseModelFactor to directly copy out the * matrices and only update the RHS b with an updated residual */ - boost::shared_ptr linearize(const Values& c) const; + boost::shared_ptr linearize(const Values& c) const override; private: /** Serialization function */ diff --git a/gtsam_unstable/slam/BetweenFactorEM.h b/gtsam_unstable/slam/BetweenFactorEM.h index 104b3209d..4104ba653 100644 --- a/gtsam_unstable/slam/BetweenFactorEM.h +++ b/gtsam_unstable/slam/BetweenFactorEM.h @@ -84,8 +84,8 @@ public: /** implement functions needed for Testable */ /** print */ - virtual void print(const std::string& s, const KeyFormatter& keyFormatter = - DefaultKeyFormatter) const { + void print(const std::string& s, const KeyFormatter& keyFormatter = + DefaultKeyFormatter) const override { std::cout << s << "BetweenFactorEM(" << keyFormatter(key1_) << "," << keyFormatter(key2_) << ")\n"; measured_.print(" measured: "); @@ -97,7 +97,7 @@ public: } /** equals */ - virtual bool equals(const NonlinearFactor& f, double tol = 1e-9) const { + bool equals(const NonlinearFactor& f, double tol = 1e-9) const override { const This *t = dynamic_cast(&f); if (t && Base::equals(f)) @@ -408,7 +408,7 @@ public: return 2; } - virtual size_t dim() const { + size_t dim() const override { return model_inlier_->R().rows() + model_inlier_->R().cols(); } diff --git a/gtsam_unstable/slam/BiasedGPSFactor.h b/gtsam_unstable/slam/BiasedGPSFactor.h index cf56afab2..c8bbdd78a 100644 --- a/gtsam_unstable/slam/BiasedGPSFactor.h +++ b/gtsam_unstable/slam/BiasedGPSFactor.h @@ -55,7 +55,7 @@ namespace gtsam { /** implement functions needed for Testable */ /** print */ - virtual void print(const std::string& s, const KeyFormatter& keyFormatter = DefaultKeyFormatter) const { + void print(const std::string& s, const KeyFormatter& keyFormatter = DefaultKeyFormatter) const override { std::cout << s << "BiasedGPSFactor(" << keyFormatter(this->key1()) << "," << keyFormatter(this->key2()) << ")\n" @@ -64,7 +64,7 @@ namespace gtsam { } /** equals */ - virtual bool equals(const NonlinearFactor& expected, double tol=1e-9) const { + bool equals(const NonlinearFactor& expected, double tol=1e-9) const override { const This *e = dynamic_cast (&expected); return e != nullptr && Base::equals(*e, tol) && traits::Equals(this->measured_, e->measured_, tol); } @@ -74,7 +74,7 @@ namespace gtsam { /** vector of errors */ Vector evaluateError(const Pose3& pose, const Point3& bias, boost::optional H1 = boost::none, boost::optional H2 = - boost::none) const { + boost::none) const override { if (H1 || H2){ H1->resize(3,6); // jacobian wrt pose diff --git a/gtsam_unstable/slam/DummyFactor.h b/gtsam_unstable/slam/DummyFactor.h index 574efabea..08b1c800a 100644 --- a/gtsam_unstable/slam/DummyFactor.h +++ b/gtsam_unstable/slam/DummyFactor.h @@ -34,10 +34,10 @@ public: // testable /** print */ - virtual void print(const std::string& s = "", const KeyFormatter& keyFormatter = DefaultKeyFormatter) const; + void print(const std::string& s = "", const KeyFormatter& keyFormatter = DefaultKeyFormatter) const override; /** Check if two factors are equal */ - virtual bool equals(const NonlinearFactor& f, double tol = 1e-9) const; + bool equals(const NonlinearFactor& f, double tol = 1e-9) const override; // access @@ -48,13 +48,13 @@ public: /** * Calculate the error of the factor - zero for dummy factors */ - virtual double error(const Values& c) const { return 0.0; } + double error(const Values& c) const override { return 0.0; } /** get the dimension of the factor (number of rows on linearization) */ - virtual size_t dim() const { return rowDim_; } + size_t dim() const override { return rowDim_; } /** linearize to a GaussianFactor */ - virtual boost::shared_ptr linearize(const Values& c) const; + boost::shared_ptr linearize(const Values& c) const override; /** * Creates a shared_ptr clone of the factor - needs to be specialized to allow @@ -62,7 +62,7 @@ public: * * By default, throws exception if subclass does not implement the function. */ - virtual NonlinearFactor::shared_ptr clone() const { + NonlinearFactor::shared_ptr clone() const override { return boost::static_pointer_cast( NonlinearFactor::shared_ptr(new DummyFactor(*this))); } diff --git a/gtsam_unstable/slam/EquivInertialNavFactor_GlobalVel.h b/gtsam_unstable/slam/EquivInertialNavFactor_GlobalVel.h index f499a0f4b..745605325 100644 --- a/gtsam_unstable/slam/EquivInertialNavFactor_GlobalVel.h +++ b/gtsam_unstable/slam/EquivInertialNavFactor_GlobalVel.h @@ -133,7 +133,7 @@ public: /** implement functions needed for Testable */ /** print */ - virtual void print(const std::string& s = "EquivInertialNavFactor_GlobalVel", const KeyFormatter& keyFormatter = DefaultKeyFormatter) const { + void print(const std::string& s = "EquivInertialNavFactor_GlobalVel", const KeyFormatter& keyFormatter = DefaultKeyFormatter) const override { std::cout << s << "(" << keyFormatter(this->key1()) << "," << keyFormatter(this->key2()) << "," @@ -153,7 +153,7 @@ public: } /** equals */ - virtual bool equals(const NonlinearFactor& expected, double tol=1e-9) const { + bool equals(const NonlinearFactor& expected, double tol=1e-9) const override { const This *e = dynamic_cast (&expected); return e != nullptr && Base::equals(*e, tol) && (delta_pos_in_t0_ - e->delta_pos_in_t0_).norm() < tol @@ -302,7 +302,7 @@ public: boost::optional H2 = boost::none, boost::optional H3 = boost::none, boost::optional H4 = boost::none, - boost::optional H5 = boost::none) const { + boost::optional H5 = boost::none) const override { // TODO: Write analytical derivative calculations // Jacobian w.r.t. Pose1 diff --git a/gtsam_unstable/slam/EquivInertialNavFactor_GlobalVel_NoBias.h b/gtsam_unstable/slam/EquivInertialNavFactor_GlobalVel_NoBias.h index 86efd10c1..9f5d800db 100644 --- a/gtsam_unstable/slam/EquivInertialNavFactor_GlobalVel_NoBias.h +++ b/gtsam_unstable/slam/EquivInertialNavFactor_GlobalVel_NoBias.h @@ -151,7 +151,7 @@ public: } /** equals */ - virtual bool equals(const NonlinearFactor& expected, double tol=1e-9) const { + bool equals(const NonlinearFactor& expected, double tol=1e-9) const override { const This *e = dynamic_cast (&expected); return e != nullptr && Base::equals(*e, tol) && (delta_pos_in_t0_ - e->delta_pos_in_t0_).norm() < tol diff --git a/gtsam_unstable/slam/GaussMarkov1stOrderFactor.h b/gtsam_unstable/slam/GaussMarkov1stOrderFactor.h index 762199753..f6de48625 100644 --- a/gtsam_unstable/slam/GaussMarkov1stOrderFactor.h +++ b/gtsam_unstable/slam/GaussMarkov1stOrderFactor.h @@ -71,7 +71,7 @@ public: /** implement functions needed for Testable */ /** print */ - virtual void print(const std::string& s, const KeyFormatter& keyFormatter = DefaultKeyFormatter) const { + void print(const std::string& s, const KeyFormatter& keyFormatter = DefaultKeyFormatter) const override { std::cout << s << "GaussMarkov1stOrderFactor(" << keyFormatter(this->key1()) << "," << keyFormatter(this->key2()) << ")\n"; @@ -79,7 +79,7 @@ public: } /** equals */ - virtual bool equals(const NonlinearFactor& expected, double tol=1e-9) const { + bool equals(const NonlinearFactor& expected, double tol=1e-9) const override { const This *e = dynamic_cast (&expected); return e != nullptr && Base::equals(*e, tol); } @@ -89,7 +89,7 @@ public: /** vector of errors */ Vector evaluateError(const VALUE& p1, const VALUE& p2, boost::optional H1 = boost::none, - boost::optional H2 = boost::none) const { + boost::optional H2 = boost::none) const override { Vector v1( traits::Logmap(p1) ); Vector v2( traits::Logmap(p2) ); diff --git a/gtsam_unstable/slam/InertialNavFactor_GlobalVelocity.h b/gtsam_unstable/slam/InertialNavFactor_GlobalVelocity.h index 4763c4263..e5a3e9118 100644 --- a/gtsam_unstable/slam/InertialNavFactor_GlobalVelocity.h +++ b/gtsam_unstable/slam/InertialNavFactor_GlobalVelocity.h @@ -114,7 +114,7 @@ public: /** implement functions needed for Testable */ /** print */ - virtual void print(const std::string& s = "InertialNavFactor_GlobalVelocity", const KeyFormatter& keyFormatter = DefaultKeyFormatter) const { + void print(const std::string& s = "InertialNavFactor_GlobalVelocity", const KeyFormatter& keyFormatter = DefaultKeyFormatter) const override { std::cout << s << "(" << keyFormatter(this->key1()) << "," << keyFormatter(this->key2()) << "," @@ -133,7 +133,7 @@ public: } /** equals */ - virtual bool equals(const NonlinearFactor& expected, double tol=1e-9) const { + bool equals(const NonlinearFactor& expected, double tol=1e-9) const override { const This *e = dynamic_cast (&expected); return e != nullptr && Base::equals(*e, tol) && (measurement_acc_ - e->measurement_acc_).norm() < tol @@ -229,7 +229,7 @@ public: boost::optional H2 = boost::none, boost::optional H3 = boost::none, boost::optional H4 = boost::none, - boost::optional H5 = boost::none) const { + boost::optional H5 = boost::none) const override { // TODO: Write analytical derivative calculations // Jacobian w.r.t. Pose1 diff --git a/gtsam_unstable/slam/InvDepthFactor3.h b/gtsam_unstable/slam/InvDepthFactor3.h index 0d10b0123..50b0c5980 100644 --- a/gtsam_unstable/slam/InvDepthFactor3.h +++ b/gtsam_unstable/slam/InvDepthFactor3.h @@ -70,13 +70,13 @@ public: * @param keyFormatter optional formatter useful for printing Symbols */ void print(const std::string& s = "InvDepthFactor3", - const KeyFormatter& keyFormatter = DefaultKeyFormatter) const { + const KeyFormatter& keyFormatter = DefaultKeyFormatter) const override { Base::print(s, keyFormatter); traits::Print(measured_, s + ".z"); } /// equals - virtual bool equals(const NonlinearFactor& p, double tol = 1e-9) const { + bool equals(const NonlinearFactor& p, double tol = 1e-9) const override { const This *e = dynamic_cast(&p); return e && Base::equals(p, tol) && traits::Equals(this->measured_, e->measured_, tol) && this->K_->equals(*e->K_, tol); } @@ -85,7 +85,7 @@ public: Vector evaluateError(const POSE& pose, const Vector5& point, const INVDEPTH& invDepth, boost::optional H1=boost::none, boost::optional H2=boost::none, - boost::optional H3=boost::none) const { + boost::optional H3=boost::none) const override { try { InvDepthCamera3 camera(pose, K_); return camera.project(point, invDepth, H1, H2, H3) - measured_; diff --git a/gtsam_unstable/slam/InvDepthFactorVariant1.h b/gtsam_unstable/slam/InvDepthFactorVariant1.h index ad66eee5b..785556750 100644 --- a/gtsam_unstable/slam/InvDepthFactorVariant1.h +++ b/gtsam_unstable/slam/InvDepthFactorVariant1.h @@ -66,13 +66,13 @@ public: * @param keyFormatter optional formatter useful for printing Symbols */ void print(const std::string& s = "InvDepthFactorVariant1", - const KeyFormatter& keyFormatter = DefaultKeyFormatter) const { + const KeyFormatter& keyFormatter = DefaultKeyFormatter) const override { Base::print(s, keyFormatter); traits::Print(measured_, s + ".z"); } /// equals - virtual bool equals(const NonlinearFactor& p, double tol = 1e-9) const { + bool equals(const NonlinearFactor& p, double tol = 1e-9) const override { const This *e = dynamic_cast(&p); return e && Base::equals(p, tol) @@ -102,7 +102,7 @@ public: /// Evaluate error h(x)-z and optionally derivatives Vector evaluateError(const Pose3& pose, const Vector6& landmark, boost::optional H1=boost::none, - boost::optional H2=boost::none) const { + boost::optional H2=boost::none) const override { if (H1) { (*H1) = numericalDerivative11( diff --git a/gtsam_unstable/slam/InvDepthFactorVariant2.h b/gtsam_unstable/slam/InvDepthFactorVariant2.h index c6b5d5af8..97ceb8a8b 100644 --- a/gtsam_unstable/slam/InvDepthFactorVariant2.h +++ b/gtsam_unstable/slam/InvDepthFactorVariant2.h @@ -69,13 +69,13 @@ public: * @param keyFormatter optional formatter useful for printing Symbols */ void print(const std::string& s = "InvDepthFactorVariant2", - const KeyFormatter& keyFormatter = DefaultKeyFormatter) const { + const KeyFormatter& keyFormatter = DefaultKeyFormatter) const override { Base::print(s, keyFormatter); traits::Print(measured_, s + ".z"); } /// equals - virtual bool equals(const NonlinearFactor& p, double tol = 1e-9) const { + bool equals(const NonlinearFactor& p, double tol = 1e-9) const override { const This *e = dynamic_cast(&p); return e && Base::equals(p, tol) @@ -105,7 +105,7 @@ public: /// Evaluate error h(x)-z and optionally derivatives Vector evaluateError(const Pose3& pose, const Vector3& landmark, boost::optional H1=boost::none, - boost::optional H2=boost::none) const { + boost::optional H2=boost::none) const override { if (H1) { (*H1) = numericalDerivative11( diff --git a/gtsam_unstable/slam/InvDepthFactorVariant3.h b/gtsam_unstable/slam/InvDepthFactorVariant3.h index 83df9e13b..21c7aa6de 100644 --- a/gtsam_unstable/slam/InvDepthFactorVariant3.h +++ b/gtsam_unstable/slam/InvDepthFactorVariant3.h @@ -68,13 +68,13 @@ public: * @param keyFormatter optional formatter useful for printing Symbols */ void print(const std::string& s = "InvDepthFactorVariant3a", - const KeyFormatter& keyFormatter = DefaultKeyFormatter) const { + const KeyFormatter& keyFormatter = DefaultKeyFormatter) const override { Base::print(s, keyFormatter); traits::Print(measured_, s + ".z"); } /// equals - virtual bool equals(const NonlinearFactor& p, double tol = 1e-9) const { + bool equals(const NonlinearFactor& p, double tol = 1e-9) const override { const This *e = dynamic_cast(&p); return e && Base::equals(p, tol) @@ -105,7 +105,7 @@ public: /// Evaluate error h(x)-z and optionally derivatives Vector evaluateError(const Pose3& pose, const Vector3& landmark, boost::optional H1=boost::none, - boost::optional H2=boost::none) const { + boost::optional H2=boost::none) const override { if(H1) { (*H1) = numericalDerivative11(boost::bind(&InvDepthFactorVariant3a::inverseDepthError, this, _1, landmark), pose); @@ -188,13 +188,13 @@ public: * @param keyFormatter optional formatter useful for printing Symbols */ void print(const std::string& s = "InvDepthFactorVariant3", - const KeyFormatter& keyFormatter = DefaultKeyFormatter) const { + const KeyFormatter& keyFormatter = DefaultKeyFormatter) const override { Base::print(s, keyFormatter); traits::Print(measured_, s + ".z"); } /// equals - virtual bool equals(const NonlinearFactor& p, double tol = 1e-9) const { + bool equals(const NonlinearFactor& p, double tol = 1e-9) const override { const This *e = dynamic_cast(&p); return e && Base::equals(p, tol) @@ -226,7 +226,7 @@ public: Vector evaluateError(const Pose3& pose1, const Pose3& pose2, const Vector3& landmark, boost::optional H1=boost::none, boost::optional H2=boost::none, - boost::optional H3=boost::none) const { + boost::optional H3=boost::none) const override { if(H1) (*H1) = numericalDerivative11(boost::bind(&InvDepthFactorVariant3b::inverseDepthError, this, _1, pose2, landmark), pose1); diff --git a/gtsam_unstable/slam/MultiProjectionFactor.h b/gtsam_unstable/slam/MultiProjectionFactor.h index 5bef97bcf..b6bf2a9c7 100644 --- a/gtsam_unstable/slam/MultiProjectionFactor.h +++ b/gtsam_unstable/slam/MultiProjectionFactor.h @@ -101,7 +101,7 @@ namespace gtsam { virtual ~MultiProjectionFactor() {} /// @return a deep copy of this factor - virtual NonlinearFactor::shared_ptr clone() const { + NonlinearFactor::shared_ptr clone() const override { return boost::static_pointer_cast( NonlinearFactor::shared_ptr(new This(*this))); } @@ -110,7 +110,7 @@ namespace gtsam { * @param s optional string naming the factor * @param keyFormatter optional formatter useful for printing Symbols */ - void print(const std::string& s = "", const KeyFormatter& keyFormatter = DefaultKeyFormatter) const { + void print(const std::string& s = "", const KeyFormatter& keyFormatter = DefaultKeyFormatter) const override { std::cout << s << "MultiProjectionFactor, z = "; std::cout << measured_ << "measurements, z = "; if(this->body_P_sensor_) @@ -119,7 +119,7 @@ namespace gtsam { } /// equals - virtual bool equals(const NonlinearFactor& p, double tol = 1e-9) const { + bool equals(const NonlinearFactor& p, double tol = 1e-9) const override { const This *e = dynamic_cast(&p); return e && Base::equals(p, tol) @@ -129,7 +129,7 @@ namespace gtsam { } /// Evaluate error h(x)-z and optionally derivatives - Vector unwhitenedError(const Values& x, boost::optional&> H = boost::none) const{ + Vector unwhitenedError(const Values& x, boost::optional&> H = boost::none) const override { Vector a; return a; diff --git a/gtsam_unstable/slam/PartialPriorFactor.h b/gtsam_unstable/slam/PartialPriorFactor.h index c6d892e93..d284366e8 100644 --- a/gtsam_unstable/slam/PartialPriorFactor.h +++ b/gtsam_unstable/slam/PartialPriorFactor.h @@ -85,20 +85,20 @@ namespace gtsam { } /// @return a deep copy of this factor - virtual gtsam::NonlinearFactor::shared_ptr clone() const { + gtsam::NonlinearFactor::shared_ptr clone() const override { return boost::static_pointer_cast( gtsam::NonlinearFactor::shared_ptr(new This(*this))); } /** implement functions needed for Testable */ /** print */ - virtual void print(const std::string& s, const KeyFormatter& keyFormatter = DefaultKeyFormatter) const { + void print(const std::string& s, const KeyFormatter& keyFormatter = DefaultKeyFormatter) const override { Base::print(s, keyFormatter); gtsam::print(prior_, "prior"); } /** equals */ - virtual bool equals(const NonlinearFactor& expected, double tol=1e-9) const { + bool equals(const NonlinearFactor& expected, double tol=1e-9) const override { const This *e = dynamic_cast (&expected); return e != nullptr && Base::equals(*e, tol) && gtsam::equal_with_abs_tol(this->prior_, e->prior_, tol) && @@ -108,7 +108,7 @@ namespace gtsam { /** implement functions needed to derive from Factor */ /** vector of errors */ - Vector evaluateError(const T& p, boost::optional H = boost::none) const { + Vector evaluateError(const T& p, boost::optional H = boost::none) const override { if (H) (*H) = H_; // FIXME: this was originally the generic retraction - may not produce same results Vector full_logmap = T::Logmap(p); diff --git a/gtsam_unstable/slam/PoseBetweenFactor.h b/gtsam_unstable/slam/PoseBetweenFactor.h index bb5835f80..e20792e25 100644 --- a/gtsam_unstable/slam/PoseBetweenFactor.h +++ b/gtsam_unstable/slam/PoseBetweenFactor.h @@ -59,14 +59,14 @@ namespace gtsam { virtual ~PoseBetweenFactor() {} /// @return a deep copy of this factor - virtual gtsam::NonlinearFactor::shared_ptr clone() const { + gtsam::NonlinearFactor::shared_ptr clone() const override { return boost::static_pointer_cast( gtsam::NonlinearFactor::shared_ptr(new This(*this))); } /** implement functions needed for Testable */ /** print */ - virtual void print(const std::string& s, const KeyFormatter& keyFormatter = DefaultKeyFormatter) const { + void print(const std::string& s, const KeyFormatter& keyFormatter = DefaultKeyFormatter) const override { std::cout << s << "BetweenFactor(" << keyFormatter(this->key1()) << "," << keyFormatter(this->key2()) << ")\n"; @@ -77,7 +77,7 @@ namespace gtsam { } /** equals */ - virtual bool equals(const NonlinearFactor& expected, double tol=1e-9) const { + bool equals(const NonlinearFactor& expected, double tol=1e-9) const override { const This *e = dynamic_cast (&expected); return e != nullptr && Base::equals(*e, tol) @@ -90,7 +90,7 @@ namespace gtsam { /** vector of errors */ Vector evaluateError(const POSE& p1, const POSE& p2, boost::optional H1 = boost::none, - boost::optional H2 = boost::none) const { + boost::optional H2 = boost::none) const override { if(body_P_sensor_) { POSE hx; if(H1 || H2) { diff --git a/gtsam_unstable/slam/PosePriorFactor.h b/gtsam_unstable/slam/PosePriorFactor.h index ce9861160..c9965f9bf 100644 --- a/gtsam_unstable/slam/PosePriorFactor.h +++ b/gtsam_unstable/slam/PosePriorFactor.h @@ -56,14 +56,14 @@ namespace gtsam { } /// @return a deep copy of this factor - virtual gtsam::NonlinearFactor::shared_ptr clone() const { + gtsam::NonlinearFactor::shared_ptr clone() const override { return boost::static_pointer_cast( gtsam::NonlinearFactor::shared_ptr(new This(*this))); } /** implement functions needed for Testable */ /** print */ - virtual void print(const std::string& s, const KeyFormatter& keyFormatter = DefaultKeyFormatter) const { + void print(const std::string& s, const KeyFormatter& keyFormatter = DefaultKeyFormatter) const override { std::cout << s << "PriorFactor on " << keyFormatter(this->key()) << "\n"; prior_.print(" prior mean: "); if(this->body_P_sensor_) @@ -72,7 +72,7 @@ namespace gtsam { } /** equals */ - virtual bool equals(const NonlinearFactor& expected, double tol=1e-9) const { + bool equals(const NonlinearFactor& expected, double tol=1e-9) const override { const This* e = dynamic_cast (&expected); return e != nullptr && Base::equals(*e, tol) @@ -83,7 +83,7 @@ namespace gtsam { /** implement functions needed to derive from Factor */ /** vector of errors */ - Vector evaluateError(const POSE& p, boost::optional H = boost::none) const { + Vector evaluateError(const POSE& p, boost::optional H = boost::none) const override { if(body_P_sensor_) { // manifold equivalent of h(x)-z -> log(z,h(x)) return prior_.localCoordinates(p.compose(*body_P_sensor_, H)); diff --git a/gtsam_unstable/slam/ProjectionFactorPPP.h b/gtsam_unstable/slam/ProjectionFactorPPP.h index 19b8d56e6..caa388e2f 100644 --- a/gtsam_unstable/slam/ProjectionFactorPPP.h +++ b/gtsam_unstable/slam/ProjectionFactorPPP.h @@ -96,7 +96,7 @@ namespace gtsam { virtual ~ProjectionFactorPPP() {} /// @return a deep copy of this factor - virtual NonlinearFactor::shared_ptr clone() const { + NonlinearFactor::shared_ptr clone() const override { return boost::static_pointer_cast( NonlinearFactor::shared_ptr(new This(*this))); } @@ -105,14 +105,14 @@ namespace gtsam { * @param s optional string naming the factor * @param keyFormatter optional formatter useful for printing Symbols */ - void print(const std::string& s = "", const KeyFormatter& keyFormatter = DefaultKeyFormatter) const { + void print(const std::string& s = "", const KeyFormatter& keyFormatter = DefaultKeyFormatter) const override { std::cout << s << "ProjectionFactorPPP, z = "; traits::Print(measured_); Base::print("", keyFormatter); } /// equals - virtual bool equals(const NonlinearFactor& p, double tol = 1e-9) const { + bool equals(const NonlinearFactor& p, double tol = 1e-9) const override { const This *e = dynamic_cast(&p); return e && Base::equals(p, tol) @@ -124,7 +124,7 @@ namespace gtsam { Vector evaluateError(const Pose3& pose, const Pose3& transform, const Point3& point, boost::optional H1 = boost::none, boost::optional H2 = boost::none, - boost::optional H3 = boost::none) const { + boost::optional H3 = boost::none) const override { try { if(H1 || H2 || H3) { Matrix H0, H02; diff --git a/gtsam_unstable/slam/ProjectionFactorPPPC.h b/gtsam_unstable/slam/ProjectionFactorPPPC.h index 369075abf..af3294bce 100644 --- a/gtsam_unstable/slam/ProjectionFactorPPPC.h +++ b/gtsam_unstable/slam/ProjectionFactorPPPC.h @@ -91,7 +91,7 @@ namespace gtsam { virtual ~ProjectionFactorPPPC() {} /// @return a deep copy of this factor - virtual NonlinearFactor::shared_ptr clone() const { + NonlinearFactor::shared_ptr clone() const override { return boost::static_pointer_cast( NonlinearFactor::shared_ptr(new This(*this))); } @@ -100,14 +100,14 @@ namespace gtsam { * @param s optional string naming the factor * @param keyFormatter optional formatter useful for printing Symbols */ - void print(const std::string& s = "", const KeyFormatter& keyFormatter = DefaultKeyFormatter) const { + void print(const std::string& s = "", const KeyFormatter& keyFormatter = DefaultKeyFormatter) const override { std::cout << s << "ProjectionFactorPPPC, z = "; traits::Print(measured_); Base::print("", keyFormatter); } /// equals - virtual bool equals(const NonlinearFactor& p, double tol = 1e-9) const { + bool equals(const NonlinearFactor& p, double tol = 1e-9) const override { const This *e = dynamic_cast(&p); return e && Base::equals(p, tol) @@ -119,7 +119,7 @@ namespace gtsam { boost::optional H1 = boost::none, boost::optional H2 = boost::none, boost::optional H3 = boost::none, - boost::optional H4 = boost::none) const { + boost::optional H4 = boost::none) const override { try { if(H1 || H2 || H3 || H4) { Matrix H0, H02; diff --git a/gtsam_unstable/slam/RelativeElevationFactor.h b/gtsam_unstable/slam/RelativeElevationFactor.h index 3507a4492..b713d45dc 100644 --- a/gtsam_unstable/slam/RelativeElevationFactor.h +++ b/gtsam_unstable/slam/RelativeElevationFactor.h @@ -43,22 +43,22 @@ public: virtual ~RelativeElevationFactor() {} /// @return a deep copy of this factor - virtual gtsam::NonlinearFactor::shared_ptr clone() const { + gtsam::NonlinearFactor::shared_ptr clone() const override { return boost::static_pointer_cast( gtsam::NonlinearFactor::shared_ptr(new This(*this))); } /** h(x)-z */ Vector evaluateError(const Pose3& pose, const Point3& point, - boost::optional H1 = boost::none, boost::optional H2 = boost::none) const; + boost::optional H1 = boost::none, boost::optional H2 = boost::none) const override; /** return the measured */ inline double measured() const { return measured_; } /** equals specialized to this factor */ - virtual bool equals(const NonlinearFactor& expected, double tol=1e-9) const; + bool equals(const NonlinearFactor& expected, double tol=1e-9) const override; /** print contents */ - void print(const std::string& s="", const KeyFormatter& keyFormatter = DefaultKeyFormatter) const; + void print(const std::string& s="", const KeyFormatter& keyFormatter = DefaultKeyFormatter) const override; private: diff --git a/gtsam_unstable/slam/SmartRangeFactor.h b/gtsam_unstable/slam/SmartRangeFactor.h index 5511a0209..6bab3f334 100644 --- a/gtsam_unstable/slam/SmartRangeFactor.h +++ b/gtsam_unstable/slam/SmartRangeFactor.h @@ -73,14 +73,14 @@ class SmartRangeFactor: public NoiseModelFactor { // Testable /** print */ - virtual void print(const std::string& s = "", - const KeyFormatter& keyFormatter = DefaultKeyFormatter) const { + void print(const std::string& s = "", + const KeyFormatter& keyFormatter = DefaultKeyFormatter) const override { std::cout << s << "SmartRangeFactor with " << size() << " measurements\n"; NoiseModelFactor::print(s); } /** Check if two factors are equal */ - virtual bool equals(const NonlinearFactor& f, double tol = 1e-9) const { + bool equals(const NonlinearFactor& f, double tol = 1e-9) const override { return false; } @@ -143,8 +143,8 @@ class SmartRangeFactor: public NoiseModelFactor { /** * Error function *without* the NoiseModel, \f$ z-h(x) \f$. */ - virtual Vector unwhitenedError(const Values& x, - boost::optional&> H = boost::none) const { + Vector unwhitenedError(const Values& x, + boost::optional&> H = boost::none) const override { size_t n = size(); if (n < 3) { if (H) { @@ -175,7 +175,7 @@ class SmartRangeFactor: public NoiseModelFactor { } /// @return a deep copy of this factor - virtual gtsam::NonlinearFactor::shared_ptr clone() const { + gtsam::NonlinearFactor::shared_ptr clone() const override { return boost::static_pointer_cast( gtsam::NonlinearFactor::shared_ptr(new This(*this))); } diff --git a/gtsam_unstable/slam/SmartStereoProjectionFactor.h b/gtsam_unstable/slam/SmartStereoProjectionFactor.h index db80956fa..ac063eff9 100644 --- a/gtsam_unstable/slam/SmartStereoProjectionFactor.h +++ b/gtsam_unstable/slam/SmartStereoProjectionFactor.h @@ -102,7 +102,7 @@ public: * @param keyFormatter optional formatter useful for printing Symbols */ void print(const std::string& s = "", const KeyFormatter& keyFormatter = - DefaultKeyFormatter) const { + DefaultKeyFormatter) const override { std::cout << s << "SmartStereoProjectionFactor\n"; std::cout << "linearizationMode:\n" << params_.linearizationMode << std::endl; std::cout << "triangulationParameters:\n" << params_.triangulation << std::endl; @@ -111,7 +111,7 @@ public: } /// equals - virtual bool equals(const NonlinearFactor& p, double tol = 1e-9) const { + bool equals(const NonlinearFactor& p, double tol = 1e-9) const override { const SmartStereoProjectionFactor *e = dynamic_cast(&p); return e && params_.linearizationMode == e->params_.linearizationMode @@ -327,8 +327,8 @@ public: } /// linearize - virtual boost::shared_ptr linearize( - const Values& values) const { + boost::shared_ptr linearize( + const Values& values) const override { return linearizeDamped(values); } @@ -438,7 +438,7 @@ public: } /// Calculate total reprojection error - virtual double error(const Values& values) const { + double error(const Values& values) const override { if (this->active(values)) { return totalReprojectionError(Base::cameras(values)); } else { // else of active flag @@ -449,9 +449,9 @@ public: /** * This corrects the Jacobians and error vector for the case in which the right pixel in the monocular camera is missing (nan) */ - virtual void correctForMissingMeasurements(const Cameras& cameras, Vector& ue, + void correctForMissingMeasurements(const Cameras& cameras, Vector& ue, boost::optional Fs = boost::none, - boost::optional E = boost::none) const + boost::optional E = boost::none) const override { // when using stereo cameras, some of the measurements might be missing: for(size_t i=0; i < cameras.size(); i++){ diff --git a/gtsam_unstable/slam/SmartStereoProjectionPoseFactor.h b/gtsam_unstable/slam/SmartStereoProjectionPoseFactor.h index 7ea5a4c2f..124e45005 100644 --- a/gtsam_unstable/slam/SmartStereoProjectionPoseFactor.h +++ b/gtsam_unstable/slam/SmartStereoProjectionPoseFactor.h @@ -120,7 +120,7 @@ public: * @param keyFormatter optional formatter useful for printing Symbols */ void print(const std::string& s = "", const KeyFormatter& keyFormatter = - DefaultKeyFormatter) const { + DefaultKeyFormatter) const override { std::cout << s << "SmartStereoProjectionPoseFactor, z = \n "; for(const boost::shared_ptr& K: K_all_) K->print("calibration = "); @@ -128,7 +128,7 @@ public: } /// equals - virtual bool equals(const NonlinearFactor& p, double tol = 1e-9) const { + bool equals(const NonlinearFactor& p, double tol = 1e-9) const override { const SmartStereoProjectionPoseFactor *e = dynamic_cast(&p); @@ -138,7 +138,7 @@ public: /** * error calculates the error of the factor. */ - virtual double error(const Values& values) const { + double error(const Values& values) const override { if (this->active(values)) { return this->totalReprojectionError(cameras(values)); } else { // else of active flag @@ -157,7 +157,7 @@ public: * to keys involved in this factor * @return vector of Values */ - Base::Cameras cameras(const Values& values) const { + Base::Cameras cameras(const Values& values) const override { Base::Cameras cameras; size_t i=0; for(const Key& k: this->keys_) { diff --git a/gtsam_unstable/slam/TSAMFactors.h b/gtsam_unstable/slam/TSAMFactors.h index 0a456e59c..6f98a2dbd 100644 --- a/gtsam_unstable/slam/TSAMFactors.h +++ b/gtsam_unstable/slam/TSAMFactors.h @@ -47,7 +47,7 @@ public: /// Evaluate measurement error h(x)-z Vector evaluateError(const Pose2& pose, const Point2& point, boost::optional H1 = boost::none, boost::optional H2 = - boost::none) const { + boost::none) const override { return pose.transformTo(point, H1, H2) - measured_; } }; @@ -79,7 +79,7 @@ public: boost::optional H1 = boost::none, // boost::optional H2 = boost::none, // boost::optional H3 = boost::none, // - boost::optional H4 = boost::none) const { + boost::optional H4 = boost::none) const override { if (H1 || H2 || H3 || H4) { // TODO use fixed-size matrices Matrix D_pose_g_base1, D_pose_g_pose; @@ -134,7 +134,7 @@ public: boost::optional H1 = boost::none, // boost::optional H2 = boost::none, // boost::optional H3 = boost::none, // - boost::optional H4 = boost::none) const { + boost::optional H4 = boost::none) const override { if (H1 || H2 || H3 || H4) { // TODO use fixed-size matrices Matrix D_pose1_g_base1, D_pose1_g_pose1; diff --git a/gtsam_unstable/slam/TransformBtwRobotsUnaryFactor.h b/gtsam_unstable/slam/TransformBtwRobotsUnaryFactor.h index c29e3e794..35080bd42 100644 --- a/gtsam_unstable/slam/TransformBtwRobotsUnaryFactor.h +++ b/gtsam_unstable/slam/TransformBtwRobotsUnaryFactor.h @@ -81,13 +81,13 @@ namespace gtsam { /** Clone */ - virtual gtsam::NonlinearFactor::shared_ptr clone() const { return boost::make_shared(*this); } + gtsam::NonlinearFactor::shared_ptr clone() const override { return boost::make_shared(*this); } /** implement functions needed for Testable */ /** print */ - virtual void print(const std::string& s, const KeyFormatter& keyFormatter = DefaultKeyFormatter) const { + void print(const std::string& s, const KeyFormatter& keyFormatter = DefaultKeyFormatter) const override { std::cout << s << "TransformBtwRobotsUnaryFactor(" << keyFormatter(key_) << ")\n"; std::cout << "MR between factor keys: " @@ -99,7 +99,7 @@ namespace gtsam { } /** equals */ - virtual bool equals(const NonlinearFactor& f, double tol=1e-9) const { + bool equals(const NonlinearFactor& f, double tol=1e-9) const override { const This *t = dynamic_cast (&f); if(t && Base::equals(f)) @@ -128,7 +128,7 @@ namespace gtsam { } /* ************************************************************************* */ - virtual double error(const gtsam::Values& x) const { + double error(const gtsam::Values& x) const override { return whitenedError(x).squaredNorm(); } @@ -139,7 +139,7 @@ namespace gtsam { * Hence \f$ b = z - h(x) = - \mathtt{error\_vector}(x) \f$ */ /* This version of linearize recalculates the noise model each time */ - virtual boost::shared_ptr linearize(const gtsam::Values& x) const { + boost::shared_ptr linearize(const gtsam::Values& x) const override { // Only linearize if the factor is active if (!this->active(x)) return boost::shared_ptr(); @@ -208,7 +208,7 @@ namespace gtsam { return 1; } - virtual size_t dim() const { + size_t dim() const override { return model_->R().rows() + model_->R().cols(); } diff --git a/gtsam_unstable/slam/TransformBtwRobotsUnaryFactorEM.h b/gtsam_unstable/slam/TransformBtwRobotsUnaryFactorEM.h index 48aaa8ed7..2db2844ae 100644 --- a/gtsam_unstable/slam/TransformBtwRobotsUnaryFactorEM.h +++ b/gtsam_unstable/slam/TransformBtwRobotsUnaryFactorEM.h @@ -97,13 +97,13 @@ namespace gtsam { /** Clone */ - virtual NonlinearFactor::shared_ptr clone() const { return boost::make_shared(*this); } + NonlinearFactor::shared_ptr clone() const override { return boost::make_shared(*this); } /** implement functions needed for Testable */ /** print */ - virtual void print(const std::string& s, const KeyFormatter& keyFormatter = DefaultKeyFormatter) const { + void print(const std::string& s, const KeyFormatter& keyFormatter = DefaultKeyFormatter) const override { std::cout << s << "TransformBtwRobotsUnaryFactorEM(" << keyFormatter(key_) << ")\n"; std::cout << "MR between factor keys: " @@ -119,7 +119,7 @@ namespace gtsam { } /** equals */ - virtual bool equals(const NonlinearFactor& f, double tol=1e-9) const { + bool equals(const NonlinearFactor& f, double tol=1e-9) const override { const This *t = dynamic_cast (&f); if(t && Base::equals(f)) @@ -151,7 +151,7 @@ namespace gtsam { } /* ************************************************************************* */ - virtual double error(const Values& x) const { + double error(const Values& x) const override { return whitenedError(x).squaredNorm(); } @@ -162,7 +162,7 @@ namespace gtsam { * Hence \f$ b = z - h(x) = - \mathtt{error\_vector}(x) \f$ */ /* This version of linearize recalculates the noise model each time */ - virtual boost::shared_ptr linearize(const Values& x) const { + boost::shared_ptr linearize(const Values& x) const override { // Only linearize if the factor is active if (!this->active(x)) return boost::shared_ptr(); @@ -406,7 +406,7 @@ namespace gtsam { return 1; } - virtual size_t dim() const { + size_t dim() const override { return model_inlier_->R().rows() + model_inlier_->R().cols(); } diff --git a/tests/simulated2D.h b/tests/simulated2D.h index c4930a55b..ed412bba8 100644 --- a/tests/simulated2D.h +++ b/tests/simulated2D.h @@ -139,14 +139,14 @@ namespace simulated2D { } /// Return error and optional derivative - Vector evaluateError(const Pose& x, boost::optional H = boost::none) const { + Vector evaluateError(const Pose& x, boost::optional H = boost::none) const override { return (prior(x, H) - measured_); } virtual ~GenericPrior() {} /// @return a deep copy of this factor - virtual gtsam::NonlinearFactor::shared_ptr clone() const { + gtsam::NonlinearFactor::shared_ptr clone() const override { return boost::static_pointer_cast( gtsam::NonlinearFactor::shared_ptr(new This(*this))); } @@ -185,14 +185,14 @@ namespace simulated2D { /// Evaluate error and optionally return derivatives Vector evaluateError(const Pose& x1, const Pose& x2, boost::optional H1 = boost::none, - boost::optional H2 = boost::none) const { + boost::optional H2 = boost::none) const override { return (odo(x1, x2, H1, H2) - measured_); } virtual ~GenericOdometry() {} /// @return a deep copy of this factor - virtual gtsam::NonlinearFactor::shared_ptr clone() const { + gtsam::NonlinearFactor::shared_ptr clone() const override { return boost::static_pointer_cast( gtsam::NonlinearFactor::shared_ptr(new This(*this))); } @@ -232,14 +232,14 @@ namespace simulated2D { /// Evaluate error and optionally return derivatives Vector evaluateError(const Pose& x1, const Landmark& x2, boost::optional H1 = boost::none, - boost::optional H2 = boost::none) const { + boost::optional H2 = boost::none) const override { return (mea(x1, x2, H1, H2) - measured_); } virtual ~GenericMeasurement() {} /// @return a deep copy of this factor - virtual gtsam::NonlinearFactor::shared_ptr clone() const { + gtsam::NonlinearFactor::shared_ptr clone() const override { return boost::static_pointer_cast( gtsam::NonlinearFactor::shared_ptr(new This(*this))); } diff --git a/tests/simulated2DConstraints.h b/tests/simulated2DConstraints.h index deb9292f7..cb8c09fc8 100644 --- a/tests/simulated2DConstraints.h +++ b/tests/simulated2DConstraints.h @@ -60,7 +60,7 @@ namespace simulated2D { virtual ~ScalarCoordConstraint1() {} /// @return a deep copy of this factor - virtual gtsam::NonlinearFactor::shared_ptr clone() const { + gtsam::NonlinearFactor::shared_ptr clone() const override { return boost::static_pointer_cast( gtsam::NonlinearFactor::shared_ptr(new This(*this))); } @@ -87,8 +87,8 @@ namespace simulated2D { * @param x is the estimate of the constrained variable being evaluated * @param H is an optional Jacobian, linearized at x */ - virtual double value(const Point& x, boost::optional H = - boost::none) const { + double value(const Point& x, boost::optional H = + boost::none) const override { if (H) { Matrix D = Matrix::Zero(1, traits::GetDimension(x)); D(0, IDX) = 1.0; @@ -128,7 +128,7 @@ namespace simulated2D { virtual ~MaxDistanceConstraint() {} /// @return a deep copy of this factor - virtual gtsam::NonlinearFactor::shared_ptr clone() const { + gtsam::NonlinearFactor::shared_ptr clone() const override { return boost::static_pointer_cast( gtsam::NonlinearFactor::shared_ptr(new This(*this))); } @@ -150,9 +150,9 @@ namespace simulated2D { * @param H2 is an optional Jacobian in x2 * @return the distance between the variables */ - virtual double value(const Point& x1, const Point& x2, + double value(const Point& x1, const Point& x2, boost::optional H1 = boost::none, - boost::optional H2 = boost::none) const { + boost::optional H2 = boost::none) const override { if (H1) *H1 = numericalDerivative21(range_trait, x1, x2, 1e-5); if (H1) *H2 = numericalDerivative22(range_trait, x1, x2, 1e-5); return range_trait(x1, x2); @@ -177,7 +177,7 @@ namespace simulated2D { virtual ~MinDistanceConstraint() {} /// @return a deep copy of this factor - virtual gtsam::NonlinearFactor::shared_ptr clone() const { + gtsam::NonlinearFactor::shared_ptr clone() const override { return boost::static_pointer_cast( gtsam::NonlinearFactor::shared_ptr(new This(*this))); } @@ -200,9 +200,9 @@ namespace simulated2D { * @param H2 is an optional Jacobian in x2 * @return the distance between the variables */ - virtual double value(const Pose& x1, const Point& x2, + double value(const Pose& x1, const Point& x2, boost::optional H1 = boost::none, - boost::optional H2 = boost::none) const { + boost::optional H2 = boost::none) const override { if (H1) *H1 = numericalDerivative21(range_trait, x1, x2, 1e-5); if (H1) *H2 = numericalDerivative22(range_trait, x1, x2, 1e-5); return range_trait(x1, x2); diff --git a/tests/simulated2DOriented.h b/tests/simulated2DOriented.h index 948a87ce5..27932415b 100644 --- a/tests/simulated2DOriented.h +++ b/tests/simulated2DOriented.h @@ -119,12 +119,12 @@ namespace simulated2DOriented { /// Evaluate error and optionally derivative Vector evaluateError(const VALUE& x1, const VALUE& x2, boost::optional H1 = boost::none, - boost::optional H2 = boost::none) const { + boost::optional H2 = boost::none) const override { return measured_.localCoordinates(odo(x1, x2, H1, H2)); } /// @return a deep copy of this factor - virtual gtsam::NonlinearFactor::shared_ptr clone() const { + gtsam::NonlinearFactor::shared_ptr clone() const override { return boost::static_pointer_cast( gtsam::NonlinearFactor::shared_ptr(new This(*this))); } diff --git a/tests/simulated3D.h b/tests/simulated3D.h index 3c92e733e..3b4afb106 100644 --- a/tests/simulated3D.h +++ b/tests/simulated3D.h @@ -90,7 +90,7 @@ struct PointPrior3D: public NoiseModelFactor1 { * @return Vector error between prior value and x (Dimension: 3) */ Vector evaluateError(const Point3& x, boost::optional H = - boost::none) const { + boost::none) const override { return prior(x, H) - measured_; } }; @@ -121,7 +121,7 @@ struct Simulated3DMeasurement: public NoiseModelFactor2 { * @return vector error between measurement and prediction (Dimension: 3) */ Vector evaluateError(const Point3& x1, const Point3& x2, - boost::optional H1 = boost::none, boost::optional H2 = boost::none) const { + boost::optional H1 = boost::none, boost::optional H2 = boost::none) const override { return mea(x1, x2, H1, H2) - measured_; } }; diff --git a/tests/smallExample.h b/tests/smallExample.h index 2b29a6d10..0c933d106 100644 --- a/tests/smallExample.h +++ b/tests/smallExample.h @@ -337,7 +337,7 @@ struct UnaryFactor: public gtsam::NoiseModelFactor1 { gtsam::NoiseModelFactor1(model, key), z_(z) { } - Vector evaluateError(const Point2& x, boost::optional A = boost::none) const { + Vector evaluateError(const Point2& x, boost::optional A = boost::none) const override { if (A) *A = H(x); return (h(x) - z_); } diff --git a/tests/testExtendedKalmanFilter.cpp b/tests/testExtendedKalmanFilter.cpp index d759e83e1..0ea507a36 100644 --- a/tests/testExtendedKalmanFilter.cpp +++ b/tests/testExtendedKalmanFilter.cpp @@ -153,14 +153,14 @@ public: } /* print */ - virtual void print(const std::string& s = "", const KeyFormatter& keyFormatter = DefaultKeyFormatter) const { + void print(const std::string& s = "", const KeyFormatter& keyFormatter = DefaultKeyFormatter) const override { std::cout << s << ": NonlinearMotionModel\n"; std::cout << " TestKey1: " << keyFormatter(key1()) << std::endl; std::cout << " TestKey2: " << keyFormatter(key2()) << std::endl; } /** Check if two factors are equal. Note type is IndexFactor and needs cast. */ - virtual bool equals(const NonlinearFactor& f, double tol = 1e-9) const { + bool equals(const NonlinearFactor& f, double tol = 1e-9) const override { const This *e = dynamic_cast (&f); return (e != nullptr) && (key1() == e->key1()) && (key2() == e->key2()); } @@ -169,13 +169,13 @@ public: * calculate the error of the factor * Override for systems with unusual noise models */ - virtual double error(const Values& c) const { + double error(const Values& c) const override { Vector w = whitenedError(c); return 0.5 * w.dot(w); } /** get the dimension of the factor (number of rows on linearization) */ - size_t dim() const { + size_t dim() const override { return 2; } @@ -189,7 +189,7 @@ public: * Ax-b \approx h(x1+dx1,x2+dx2)-z = h(x1,x2) + A2*dx1 + A2*dx2 - z * Hence b = z - h(x1,x2) = - error_vector(x) */ - boost::shared_ptr linearize(const Values& c) const { + boost::shared_ptr linearize(const Values& c) const override { const X1& x1 = c.at(key1()); const X2& x2 = c.at(key2()); Matrix A1, A2; @@ -212,7 +212,7 @@ public: /** vector of errors */ Vector evaluateError(const Point2& p1, const Point2& p2, boost::optional H1 = boost::none, boost::optional H2 = - boost::none) const { + boost::none) const override { // error = p2 - f(p1) // H1 = d error / d p1 = -d f/ d p1 = -F @@ -284,13 +284,13 @@ public: } /* print */ - virtual void print(const std::string& s = "", const KeyFormatter& keyFormatter = DefaultKeyFormatter) const { + void print(const std::string& s = "", const KeyFormatter& keyFormatter = DefaultKeyFormatter) const override { std::cout << s << ": NonlinearMeasurementModel\n"; std::cout << " TestKey: " << keyFormatter(key()) << std::endl; } /** Check if two factors are equal. Note type is IndexFactor and needs cast. */ - virtual bool equals(const NonlinearFactor& f, double tol = 1e-9) const { + bool equals(const NonlinearFactor& f, double tol = 1e-9) const override { const This *e = dynamic_cast (&f); return (e != nullptr) && Base::equals(f); } @@ -299,13 +299,13 @@ public: * calculate the error of the factor * Override for systems with unusual noise models */ - virtual double error(const Values& c) const { + double error(const Values& c) const override { Vector w = whitenedError(c); return 0.5 * w.dot(w); } /** get the dimension of the factor (number of rows on linearization) */ - size_t dim() const { + size_t dim() const override { return 1; } @@ -319,7 +319,7 @@ public: * Ax-b \approx h(x1+dx1)-z = h(x1) + A1*dx1 - z * Hence b = z - h(x1) = - error_vector(x) */ - boost::shared_ptr linearize(const Values& c) const { + boost::shared_ptr linearize(const Values& c) const override { const X& x1 = c.at(key()); Matrix A1; Vector b = -evaluateError(x1, A1); @@ -336,7 +336,7 @@ public: } /** vector of errors */ - Vector evaluateError(const Point2& p, boost::optional H1 = boost::none) const { + Vector evaluateError(const Point2& p, boost::optional H1 = boost::none) const override { // error = z - h(p) // H = d error / d p = -d h/ d p = -H Vector z_hat = h(p); diff --git a/tests/testNonlinearFactor.cpp b/tests/testNonlinearFactor.cpp index e1156ceba..662b071df 100644 --- a/tests/testNonlinearFactor.cpp +++ b/tests/testNonlinearFactor.cpp @@ -239,12 +239,12 @@ public: typedef NoiseModelFactor4 Base; TestFactor4() : Base(noiseModel::Diagonal::Sigmas((Vector(1) << 2.0).finished()), X(1), X(2), X(3), X(4)) {} - virtual Vector + Vector evaluateError(const double& x1, const double& x2, const double& x3, const double& x4, boost::optional H1 = boost::none, boost::optional H2 = boost::none, boost::optional H3 = boost::none, - boost::optional H4 = boost::none) const { + boost::optional H4 = boost::none) const override { if(H1) { *H1 = (Matrix(1, 1) << 1.0).finished(); *H2 = (Matrix(1, 1) << 2.0).finished(); @@ -254,7 +254,7 @@ public: return (Vector(1) << x1 + x2 + x3 + x4).finished(); } - virtual gtsam::NonlinearFactor::shared_ptr clone() const { + gtsam::NonlinearFactor::shared_ptr clone() const override { return boost::static_pointer_cast( gtsam::NonlinearFactor::shared_ptr(new TestFactor4(*this))); } }; @@ -287,13 +287,13 @@ public: typedef NoiseModelFactor5 Base; TestFactor5() : Base(noiseModel::Diagonal::Sigmas((Vector(1) << 2.0).finished()), X(1), X(2), X(3), X(4), X(5)) {} - virtual Vector + Vector evaluateError(const X1& x1, const X2& x2, const X3& x3, const X4& x4, const X5& x5, boost::optional H1 = boost::none, boost::optional H2 = boost::none, boost::optional H3 = boost::none, boost::optional H4 = boost::none, - boost::optional H5 = boost::none) const { + boost::optional H5 = boost::none) const override { if(H1) { *H1 = (Matrix(1, 1) << 1.0).finished(); *H2 = (Matrix(1, 1) << 2.0).finished(); @@ -336,14 +336,14 @@ public: typedef NoiseModelFactor6 Base; TestFactor6() : Base(noiseModel::Diagonal::Sigmas((Vector(1) << 2.0).finished()), X(1), X(2), X(3), X(4), X(5), X(6)) {} - virtual Vector + Vector evaluateError(const X1& x1, const X2& x2, const X3& x3, const X4& x4, const X5& x5, const X6& x6, boost::optional H1 = boost::none, boost::optional H2 = boost::none, boost::optional H3 = boost::none, boost::optional H4 = boost::none, boost::optional H5 = boost::none, - boost::optional H6 = boost::none) const { + boost::optional H6 = boost::none) const override { if(H1) { *H1 = (Matrix(1, 1) << 1.0).finished(); *H2 = (Matrix(1, 1) << 2.0).finished(); diff --git a/tests/testNonlinearOptimizer.cpp b/tests/testNonlinearOptimizer.cpp index a549dc726..2616ab103 100644 --- a/tests/testNonlinearOptimizer.cpp +++ b/tests/testNonlinearOptimizer.cpp @@ -510,8 +510,8 @@ class IterativeLM : public LevenbergMarquardtOptimizer { initial_(initialValues) {} /// Solve that uses conjugate gradient - virtual VectorValues solve(const GaussianFactorGraph& gfg, - const NonlinearOptimizerParams& params) const { + VectorValues solve(const GaussianFactorGraph& gfg, + const NonlinearOptimizerParams& params) const override { VectorValues zeros = initial_.zeroVectors(); return conjugateGradientDescent(gfg, zeros, cgParams_); } diff --git a/wrap/Method.h b/wrap/Method.h index 88a73cd80..4d3c8d909 100644 --- a/wrap/Method.h +++ b/wrap/Method.h @@ -37,7 +37,7 @@ public: boost::optional instName = boost::none, bool verbose = false); - virtual bool isStatic() const { + bool isStatic() const override { return false; } @@ -64,10 +64,10 @@ public: private: // Emit method header - void proxy_header(FileWriter& proxyFile) const; + void proxy_header(FileWriter& proxyFile) const override; - virtual std::string wrapper_call(FileWriter& wrapperFile, Str cppClassName, - Str matlabUniqueName, const ArgumentList& args) const; + std::string wrapper_call(FileWriter& wrapperFile, Str cppClassName, + Str matlabUniqueName, const ArgumentList& args) const override; }; } // \namespace wrap diff --git a/wrap/ReturnType.h b/wrap/ReturnType.h index ba5086507..8d78bb48f 100644 --- a/wrap/ReturnType.h +++ b/wrap/ReturnType.h @@ -30,7 +30,7 @@ struct ReturnType : public Qualified { ReturnType(const std::string& name, Category c = CLASS, bool ptr = false) : Qualified(name, c), isPtr(ptr) {} - virtual void clear() { + void clear() override { Qualified::clear(); isPtr = false; } diff --git a/wrap/StaticMethod.h b/wrap/StaticMethod.h index 8392a1cc5..dbb918596 100644 --- a/wrap/StaticMethod.h +++ b/wrap/StaticMethod.h @@ -41,10 +41,10 @@ struct StaticMethod: public MethodBase { protected: - virtual void proxy_header(FileWriter& proxyFile) const; + void proxy_header(FileWriter& proxyFile) const override; - virtual std::string wrapper_call(FileWriter& wrapperFile, Str cppClassName, - Str matlabUniqueName, const ArgumentList& args) const; + std::string wrapper_call(FileWriter& wrapperFile, Str cppClassName, + Str matlabUniqueName, const ArgumentList& args) const override; }; } // \namespace wrap diff --git a/wrap/utilities.h b/wrap/utilities.h index 17c5cba12..8c6f9a0b2 100644 --- a/wrap/utilities.h +++ b/wrap/utilities.h @@ -40,7 +40,7 @@ class CantOpenFile : public std::exception { public: CantOpenFile(const std::string& filename) : what_("Can't open file " + filename) {} ~CantOpenFile() throw() {} - virtual const char* what() const throw() { return what_.c_str(); } + const char* what() const noexcept override { return what_.c_str(); } }; class OutputError : public std::exception { @@ -49,7 +49,7 @@ private: public: OutputError(const std::string& what) : what_(what) {} ~OutputError() throw() {} - virtual const char* what() const throw() { return what_.c_str(); } + const char* what() const noexcept override { return what_.c_str(); } }; class ParseFailed : public std::exception { @@ -58,7 +58,7 @@ class ParseFailed : public std::exception { public: ParseFailed(int length) : what_((boost::format("Parse failed at character [%d]")%(length-1)).str()) {} ~ParseFailed() throw() {} - virtual const char* what() const throw() { return what_.c_str(); } + const char* what() const noexcept override { return what_.c_str(); } }; class DependencyMissing : public std::exception { @@ -68,7 +68,7 @@ public: DependencyMissing(const std::string& dep, const std::string& loc) : what_("Missing dependency '" + dep + "' in " + loc) {} ~DependencyMissing() throw() {} - virtual const char* what() const throw() { return what_.c_str(); } + const char* what() const noexcept override { return what_.c_str(); } }; class DuplicateDefinition : public std::exception { @@ -78,7 +78,7 @@ public: DuplicateDefinition(const std::string& name) : what_("Duplicate definition of " + name) {} ~DuplicateDefinition() throw() {} - virtual const char* what() const throw() { return what_.c_str(); } + const char* what() const noexcept override { return what_.c_str(); } }; class AttributeError : public std::exception { @@ -88,7 +88,7 @@ public: AttributeError(const std::string& name, const std::string& problem) : what_("Class " + name + ": " + problem) {} ~AttributeError() throw() {} - virtual const char* what() const throw() { return what_.c_str(); } + const char* what() const noexcept override { return what_.c_str(); } }; // "Unique" key to signal calling the matlab object constructor with a raw pointer From 64fb7b9503fec55935bccd3cb4f1f8f12561baf8 Mon Sep 17 00:00:00 2001 From: Jose Luis Blanco Claraco Date: Sun, 26 Jul 2020 23:35:11 +0200 Subject: [PATCH 260/869] Avoid -Woverride in clang <12.0.0 --- cmake/GtsamBuildTypes.cmake | 13 +++++++++++-- 1 file changed, 11 insertions(+), 2 deletions(-) diff --git a/cmake/GtsamBuildTypes.cmake b/cmake/GtsamBuildTypes.cmake index bffe97904..7ba38e80b 100644 --- a/cmake/GtsamBuildTypes.cmake +++ b/cmake/GtsamBuildTypes.cmake @@ -104,7 +104,16 @@ if(MSVC) set(GTSAM_COMPILE_OPTIONS_PRIVATE_TIMING /MD /O2 CACHE STRING "(User editable) Private compiler flags for Timing configuration.") else() # Common to all configurations, next for each configuration: - + + message (STATUS "CMAKE_CXX_COMPILER_VERSION: ${CMAKE_CXX_COMPILER_VERSION}") + + if ( + ((CMAKE_CXX_COMPILER_ID MATCHES "Clang") AND (NOT CMAKE_CXX_COMPILER_VERSION VERSION_LESS 12.0.0)) OR + (CMAKE_CXX_COMPILER_ID MATCHES "GNU") + ) + set(flag_override_ -Wsuggest-override -Werror=suggest-override) + endif() + set(GTSAM_COMPILE_OPTIONS_PRIVATE_COMMON -Wall # Enable common warnings -fPIC # ensure proper code generation for shared libraries @@ -112,7 +121,7 @@ else() $<$:-Wreturn-stack-address -Werror=return-stack-address> # Error: return local address -Wreturn-type -Werror=return-type # Error on missing return() -Wformat -Werror=format-security # Error on wrong printf() arguments - $<$:-Wsuggest-override -Werror=suggest-override> # Enforce the use of the override keyword + $<$:${flag_override_}> # Enforce the use of the override keyword # CACHE STRING "(User editable) Private compiler flags for all configurations.") set(GTSAM_COMPILE_OPTIONS_PRIVATE_DEBUG -g -fno-inline CACHE STRING "(User editable) Private compiler flags for Debug configuration.") From 99256c6d286bf3b5f269d013eed9b37c58d41ffd Mon Sep 17 00:00:00 2001 From: Jose Luis Blanco Claraco Date: Sun, 26 Jul 2020 23:35:49 +0200 Subject: [PATCH 261/869] relax override -Werror for now --- cmake/GtsamBuildTypes.cmake | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/cmake/GtsamBuildTypes.cmake b/cmake/GtsamBuildTypes.cmake index 7ba38e80b..53b21647d 100644 --- a/cmake/GtsamBuildTypes.cmake +++ b/cmake/GtsamBuildTypes.cmake @@ -111,7 +111,7 @@ else() ((CMAKE_CXX_COMPILER_ID MATCHES "Clang") AND (NOT CMAKE_CXX_COMPILER_VERSION VERSION_LESS 12.0.0)) OR (CMAKE_CXX_COMPILER_ID MATCHES "GNU") ) - set(flag_override_ -Wsuggest-override -Werror=suggest-override) + set(flag_override_ -Wsuggest-override) # -Werror=suggest-override: Add again someday endif() set(GTSAM_COMPILE_OPTIONS_PRIVATE_COMMON From 406060b457d59c2dda74f0045a5227af18496698 Mon Sep 17 00:00:00 2001 From: Jose Luis Blanco Claraco Date: Mon, 27 Jul 2020 00:04:57 +0200 Subject: [PATCH 262/869] Fix missing virtual dtors --- gtsam/discrete/DiscreteBayesTree.h | 1 + gtsam/linear/GaussianBayesTree.h | 1 + gtsam/nonlinear/ISAM2Clique.h | 1 + gtsam/symbolic/SymbolicBayesTree.h | 1 + 4 files changed, 4 insertions(+) diff --git a/gtsam/discrete/DiscreteBayesTree.h b/gtsam/discrete/DiscreteBayesTree.h index 3d6e016fd..29da5817e 100644 --- a/gtsam/discrete/DiscreteBayesTree.h +++ b/gtsam/discrete/DiscreteBayesTree.h @@ -45,6 +45,7 @@ class GTSAM_EXPORT DiscreteBayesTreeClique typedef boost::shared_ptr shared_ptr; typedef boost::weak_ptr weak_ptr; DiscreteBayesTreeClique() {} + virtual ~DiscreteBayesTreeClique() {} DiscreteBayesTreeClique( const boost::shared_ptr& conditional) : Base(conditional) {} diff --git a/gtsam/linear/GaussianBayesTree.h b/gtsam/linear/GaussianBayesTree.h index b6f5acd52..e2d8ae87a 100644 --- a/gtsam/linear/GaussianBayesTree.h +++ b/gtsam/linear/GaussianBayesTree.h @@ -41,6 +41,7 @@ namespace gtsam { typedef boost::shared_ptr shared_ptr; typedef boost::weak_ptr weak_ptr; GaussianBayesTreeClique() {} + virtual ~GaussianBayesTreeClique() {} GaussianBayesTreeClique(const boost::shared_ptr& conditional) : Base(conditional) {} }; diff --git a/gtsam/nonlinear/ISAM2Clique.h b/gtsam/nonlinear/ISAM2Clique.h index 467741d66..9b40c02c6 100644 --- a/gtsam/nonlinear/ISAM2Clique.h +++ b/gtsam/nonlinear/ISAM2Clique.h @@ -51,6 +51,7 @@ class GTSAM_EXPORT ISAM2Clique /// Default constructor ISAM2Clique() : Base() {} + virtual ~ISAM2Clique() = default; /// Copy constructor, does *not* copy solution pointers as these are invalid /// in different trees. diff --git a/gtsam/symbolic/SymbolicBayesTree.h b/gtsam/symbolic/SymbolicBayesTree.h index e28f28764..3fdf1011b 100644 --- a/gtsam/symbolic/SymbolicBayesTree.h +++ b/gtsam/symbolic/SymbolicBayesTree.h @@ -39,6 +39,7 @@ namespace gtsam { typedef boost::shared_ptr shared_ptr; typedef boost::weak_ptr weak_ptr; SymbolicBayesTreeClique() {} + virtual ~SymbolicBayesTreeClique() {} SymbolicBayesTreeClique(const boost::shared_ptr& conditional) : Base(conditional) {} }; From 816529170478bb732c5269835a269d8a9fd6b056 Mon Sep 17 00:00:00 2001 From: Jose Luis Blanco Claraco Date: Mon, 27 Jul 2020 00:11:51 +0200 Subject: [PATCH 263/869] Fix warnings on incorrect for range reference bindings --- gtsam/base/timing.cpp | 2 +- gtsam/discrete/DecisionTreeFactor.cpp | 2 +- gtsam/discrete/Potentials.cpp | 2 +- gtsam/linear/Preconditioner.cpp | 2 +- gtsam/linear/VectorValues.cpp | 2 +- gtsam/slam/dataset.cpp | 4 ++-- wrap/Module.cpp | 2 +- 7 files changed, 8 insertions(+), 8 deletions(-) diff --git a/gtsam/base/timing.cpp b/gtsam/base/timing.cpp index b33f06045..4b41ea937 100644 --- a/gtsam/base/timing.cpp +++ b/gtsam/base/timing.cpp @@ -89,7 +89,7 @@ void TimingOutline::print(const std::string& outline) const { childOrder[child.second->myOrder_] = child.second; } // Print children - for(const ChildOrder::value_type order_child: childOrder) { + for(const ChildOrder::value_type& order_child: childOrder) { std::string childOutline(outline); childOutline += "| "; order_child.second->print(childOutline); diff --git a/gtsam/discrete/DecisionTreeFactor.cpp b/gtsam/discrete/DecisionTreeFactor.cpp index f83349436..b7b9d7034 100644 --- a/gtsam/discrete/DecisionTreeFactor.cpp +++ b/gtsam/discrete/DecisionTreeFactor.cpp @@ -69,7 +69,7 @@ namespace gtsam { for(Key j: f.keys()) cs[j] = f.cardinality(j); // Convert map into keys DiscreteKeys keys; - for(const DiscreteKey& key: cs) + for(const std::pair& key: cs) keys.push_back(key); // apply operand ADT result = ADT::apply(f, op); diff --git a/gtsam/discrete/Potentials.cpp b/gtsam/discrete/Potentials.cpp index fe99ea975..331a76c13 100644 --- a/gtsam/discrete/Potentials.cpp +++ b/gtsam/discrete/Potentials.cpp @@ -56,7 +56,7 @@ bool Potentials::equals(const Potentials& other, double tol) const { /* ************************************************************************* */ void Potentials::print(const string& s, const KeyFormatter& formatter) const { cout << s << "\n Cardinalities: {"; - for (const DiscreteKey& key : cardinalities_) + for (const std::pair& key : cardinalities_) cout << formatter(key.first) << ":" << key.second << ", "; cout << "}" << endl; ADT::print(" "); diff --git a/gtsam/linear/Preconditioner.cpp b/gtsam/linear/Preconditioner.cpp index 1c602a963..24a42afb8 100644 --- a/gtsam/linear/Preconditioner.cpp +++ b/gtsam/linear/Preconditioner.cpp @@ -145,7 +145,7 @@ void BlockJacobiPreconditioner::build( /* getting the block diagonals over the factors */ std::map hessianMap =gfg.hessianBlockDiagonal(); - for ( const Matrix hessian: hessianMap | boost::adaptors::map_values) + for (const Matrix& hessian: hessianMap | boost::adaptors::map_values) blocks.push_back(hessian); /* if necessary, allocating the memory for cacheing the factorization results */ diff --git a/gtsam/linear/VectorValues.cpp b/gtsam/linear/VectorValues.cpp index 0a25617e4..9b5868744 100644 --- a/gtsam/linear/VectorValues.cpp +++ b/gtsam/linear/VectorValues.cpp @@ -45,7 +45,7 @@ namespace gtsam { /* ************************************************************************* */ VectorValues::VectorValues(const Vector& x, const Dims& dims) { - typedef pair Pair; + using Pair = pair; size_t j = 0; for (const Pair& v : dims) { Key key; diff --git a/gtsam/slam/dataset.cpp b/gtsam/slam/dataset.cpp index 4a95b4297..3a2d04127 100644 --- a/gtsam/slam/dataset.cpp +++ b/gtsam/slam/dataset.cpp @@ -73,8 +73,8 @@ string findExampleDataFile(const string& name) { namesToSearch.push_back(name + ".xml"); // Find first name that exists - for(const fs::path& root: rootsToSearch) { - for(const fs::path& name: namesToSearch) { + for(const fs::path root: rootsToSearch) { + for(const fs::path name: namesToSearch) { if (fs::is_regular_file(root / name)) return (root / name).string(); } diff --git a/wrap/Module.cpp b/wrap/Module.cpp index ec02dc412..780c6f8da 100644 --- a/wrap/Module.cpp +++ b/wrap/Module.cpp @@ -248,7 +248,7 @@ void Module::parseMarkup(const std::string& data) { // Create type attributes table and check validity typeAttributes.addClasses(expandedClasses); typeAttributes.addForwardDeclarations(forward_declarations); - for (const TypedefPair p: typedefs) + for (const TypedefPair& p: typedefs) typeAttributes.addType(p.newType); // add Eigen types as template arguments are also checked ? vector eigen; From 8a9780113a855f4734365fce2a6b0ae969ff6fc4 Mon Sep 17 00:00:00 2001 From: Jose Luis Blanco Claraco Date: Mon, 27 Jul 2020 00:16:28 +0200 Subject: [PATCH 264/869] remove leftover cmake debug trace --- cmake/GtsamBuildTypes.cmake | 2 -- 1 file changed, 2 deletions(-) diff --git a/cmake/GtsamBuildTypes.cmake b/cmake/GtsamBuildTypes.cmake index 53b21647d..53dacd3f5 100644 --- a/cmake/GtsamBuildTypes.cmake +++ b/cmake/GtsamBuildTypes.cmake @@ -105,8 +105,6 @@ if(MSVC) else() # Common to all configurations, next for each configuration: - message (STATUS "CMAKE_CXX_COMPILER_VERSION: ${CMAKE_CXX_COMPILER_VERSION}") - if ( ((CMAKE_CXX_COMPILER_ID MATCHES "Clang") AND (NOT CMAKE_CXX_COMPILER_VERSION VERSION_LESS 12.0.0)) OR (CMAKE_CXX_COMPILER_ID MATCHES "GNU") From ccbdb40c936cb3f7f12e5d14cd0fa328c09e9a0c Mon Sep 17 00:00:00 2001 From: acxz <17132214+acxz@users.noreply.github.com> Date: Sun, 26 Jul 2020 20:08:55 -0400 Subject: [PATCH 265/869] fix warnings on incorrect for range reference bindings --- gtsam/linear/tests/testGaussianBayesNet.cpp | 8 ++++---- gtsam_unstable/geometry/tests/testSimilarity3.cpp | 2 +- 2 files changed, 5 insertions(+), 5 deletions(-) diff --git a/gtsam/linear/tests/testGaussianBayesNet.cpp b/gtsam/linear/tests/testGaussianBayesNet.cpp index 488368c72..eafefb3cb 100644 --- a/gtsam/linear/tests/testGaussianBayesNet.cpp +++ b/gtsam/linear/tests/testGaussianBayesNet.cpp @@ -137,7 +137,7 @@ TEST( GaussianBayesNet, optimize3 ) } /* ************************************************************************* */ -TEST(GaussianBayesNet, ordering) +TEST(GaussianBayesNet, ordering) { Ordering expected; expected += _x_, _y_; @@ -155,7 +155,7 @@ TEST( GaussianBayesNet, MatrixStress ) bn.emplace_shared(_z_, Vector2(5, 6), 6 * I_2x2); const VectorValues expected = bn.optimize(); - for (const auto keys : + for (const auto& keys : {KeyVector({_x_, _y_, _z_}), KeyVector({_x_, _z_, _y_}), KeyVector({_y_, _x_, _z_}), KeyVector({_y_, _z_, _x_}), KeyVector({_z_, _x_, _y_}), KeyVector({_z_, _y_, _x_})}) { @@ -183,7 +183,7 @@ TEST( GaussianBayesNet, backSubstituteTranspose ) VectorValues actual = smallBayesNet.backSubstituteTranspose(x); EXPECT(assert_equal(expected, actual)); - + const auto ordering = noisyBayesNet.ordering(); const Matrix R = smallBayesNet.matrix(ordering).first; const Vector expected_vector = R.transpose().inverse() * x.vector(ordering); @@ -206,7 +206,7 @@ TEST( GaussianBayesNet, backSubstituteTransposeNoisy ) VectorValues actual = noisyBayesNet.backSubstituteTranspose(x); EXPECT(assert_equal(expected, actual)); - + const auto ordering = noisyBayesNet.ordering(); const Matrix R = noisyBayesNet.matrix(ordering).first; const Vector expected_vector = R.transpose().inverse() * x.vector(ordering); diff --git a/gtsam_unstable/geometry/tests/testSimilarity3.cpp b/gtsam_unstable/geometry/tests/testSimilarity3.cpp index b07b5acd6..d23346896 100644 --- a/gtsam_unstable/geometry/tests/testSimilarity3.cpp +++ b/gtsam_unstable/geometry/tests/testSimilarity3.cpp @@ -244,7 +244,7 @@ TEST(Similarity3, GroupAction) { &Similarity3::transformFrom, _1, _2, boost::none, boost::none); Point3 q(1, 2, 3); - for (const auto T : { T1, T2, T3, T4, T5, T6 }) { + for (const auto& T : { T1, T2, T3, T4, T5, T6 }) { Point3 q(1, 0, 0); Matrix H1 = numericalDerivative21(f, T, q); Matrix H2 = numericalDerivative22(f, T, q); From ced6eac7e2c2792b02c3ef55533b3210dfd2571b Mon Sep 17 00:00:00 2001 From: acxz <17132214+acxz@users.noreply.github.com> Date: Sun, 26 Jul 2020 20:13:10 -0400 Subject: [PATCH 266/869] remove useless Planning test --- .../discrete/tests/testPlanning.cpp | 37 ------------------- 1 file changed, 37 deletions(-) delete mode 100644 gtsam_unstable/discrete/tests/testPlanning.cpp diff --git a/gtsam_unstable/discrete/tests/testPlanning.cpp b/gtsam_unstable/discrete/tests/testPlanning.cpp deleted file mode 100644 index 431d7a4ef..000000000 --- a/gtsam_unstable/discrete/tests/testPlanning.cpp +++ /dev/null @@ -1,37 +0,0 @@ -/* - * testPlanning.cpp - * @brief develop code for planning example - * @date Feb 13, 2012 - * @author Frank Dellaert - */ - -//#include -#include -#include -#include -#include - -using namespace std; -using namespace gtsam; - -/* ************************************************************************* */ -TEST_UNSAFE(Planner, allInOne) -{ - // A small planning problem - // First variable is location - DiscreteKey location(0,3), - haveRock(1,2), haveSoil(2,2), haveImage(3,2), - commRock(4,2), commSoil(5,2), commImage(6,2); - - // There are 3 actions: - // Drive, communicate, sample -} - - -/* ************************************************************************* */ -int main() { - TestResult tr; - return TestRegistry::runAllTests(tr); -} -/* ************************************************************************* */ - From 1b775798100c55969bebac4f0d2fd99cf1e22da3 Mon Sep 17 00:00:00 2001 From: acxz <17132214+acxz@users.noreply.github.com> Date: Sun, 26 Jul 2020 20:16:32 -0400 Subject: [PATCH 267/869] fix return copy --- gtsam_unstable/discrete/tests/testScheduler.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/gtsam_unstable/discrete/tests/testScheduler.cpp b/gtsam_unstable/discrete/tests/testScheduler.cpp index 0be4e4b1f..3f6c6a1e0 100644 --- a/gtsam_unstable/discrete/tests/testScheduler.cpp +++ b/gtsam_unstable/discrete/tests/testScheduler.cpp @@ -75,7 +75,7 @@ DiscreteFactorGraph createExpected() { // Mutual exclusion for students expected.addAllDiff(A, J); - return expected; + return std::move(expected); } /* ************************************************************************* */ From c0c2564ac629e6d6919d2759421fd5682a74c62e Mon Sep 17 00:00:00 2001 From: Fan Jiang Date: Mon, 27 Jul 2020 09:29:28 -0400 Subject: [PATCH 268/869] Copy cython files --- python/gtsam_py/python/__init__.py | 26 ++ .../python/examples/DogLegOptimizerExample.py | 118 ++++++ .../python/examples/GPSFactorExample.py | 56 +++ .../python/examples/ImuFactorExample.py | 153 ++++++++ .../python/examples/ImuFactorExample2.py | 172 ++++++++ .../python/examples/OdometryExample.py | 69 ++++ .../examples/PlanarManipulatorExample.py | 334 ++++++++++++++++ .../python/examples/PlanarSLAMExample.py | 81 ++++ .../python/examples/Pose2SLAMExample.py | 97 +++++ .../python/examples/Pose2SLAMExample_g2o.py | 88 +++++ .../python/examples/Pose3SLAMExample_g2o.py | 71 ++++ ...Pose3SLAMExample_initializePose3Chordal.py | 35 ++ .../python/examples/PreintegrationExample.py | 140 +++++++ python/gtsam_py/python/examples/README.md | 57 +++ python/gtsam_py/python/examples/SFMExample.py | 121 ++++++ python/gtsam_py/python/examples/SFMdata.py | 39 ++ .../python/examples/SimpleRotation.py | 85 ++++ .../python/examples/VisualISAM2Example.py | 154 ++++++++ .../python/examples/VisualISAMExample.py | 103 +++++ python/gtsam_py/python/examples/__init__.py | 0 python/gtsam_py/python/tests/__init__.py | 0 .../python/tests/testScenarioRunner.py | 47 +++ .../gtsam_py/python/tests/test_Cal3Unified.py | 38 ++ .../python/tests/test_FrobeniusFactor.py | 56 +++ .../python/tests/test_GaussianFactorGraph.py | 92 +++++ .../python/tests/test_JacobianFactor.py | 92 +++++ .../python/tests/test_KalmanFilter.py | 83 ++++ .../python/tests/test_KarcherMeanFactor.py | 80 ++++ .../python/tests/test_LocalizationExample.py | 64 +++ .../python/tests/test_NonlinearOptimizer.py | 83 ++++ .../python/tests/test_OdometryExample.py | 59 +++ .../python/tests/test_PlanarSLAMExample.py | 78 ++++ python/gtsam_py/python/tests/test_Pose2.py | 32 ++ .../python/tests/test_Pose2SLAMExample.py | 76 ++++ python/gtsam_py/python/tests/test_Pose3.py | 70 ++++ .../python/tests/test_Pose3SLAMExample.py | 60 +++ .../gtsam_py/python/tests/test_PriorFactor.py | 61 +++ .../gtsam_py/python/tests/test_SFMExample.py | 82 ++++ python/gtsam_py/python/tests/test_SO4.py | 59 +++ python/gtsam_py/python/tests/test_SOn.py | 59 +++ python/gtsam_py/python/tests/test_Scenario.py | 53 +++ .../python/tests/test_SimpleCamera.py | 45 +++ .../python/tests/test_StereoVOExample.py | 82 ++++ python/gtsam_py/python/tests/test_Values.py | 86 ++++ .../python/tests/test_VisualISAMExample.py | 57 +++ python/gtsam_py/python/tests/test_dataset.py | 45 +++ python/gtsam_py/python/tests/test_dsf_map.py | 40 ++ .../python/tests/test_initialize_pose3.py | 89 +++++ .../python/tests/test_logging_optimizer.py | 108 +++++ python/gtsam_py/python/utils/__init__.py | 0 python/gtsam_py/python/utils/circlePose3.py | 38 ++ .../python/utils/logging_optimizer.py | 52 +++ python/gtsam_py/python/utils/plot.py | 369 ++++++++++++++++++ python/gtsam_py/python/utils/test_case.py | 27 ++ .../python/utils/visual_data_generator.py | 118 ++++++ python/gtsam_py/python/utils/visual_isam.py | 131 +++++++ 56 files changed, 4610 insertions(+) create mode 100644 python/gtsam_py/python/__init__.py create mode 100644 python/gtsam_py/python/examples/DogLegOptimizerExample.py create mode 100644 python/gtsam_py/python/examples/GPSFactorExample.py create mode 100644 python/gtsam_py/python/examples/ImuFactorExample.py create mode 100644 python/gtsam_py/python/examples/ImuFactorExample2.py create mode 100644 python/gtsam_py/python/examples/OdometryExample.py create mode 100644 python/gtsam_py/python/examples/PlanarManipulatorExample.py create mode 100644 python/gtsam_py/python/examples/PlanarSLAMExample.py create mode 100644 python/gtsam_py/python/examples/Pose2SLAMExample.py create mode 100644 python/gtsam_py/python/examples/Pose2SLAMExample_g2o.py create mode 100644 python/gtsam_py/python/examples/Pose3SLAMExample_g2o.py create mode 100644 python/gtsam_py/python/examples/Pose3SLAMExample_initializePose3Chordal.py create mode 100644 python/gtsam_py/python/examples/PreintegrationExample.py create mode 100644 python/gtsam_py/python/examples/README.md create mode 100644 python/gtsam_py/python/examples/SFMExample.py create mode 100644 python/gtsam_py/python/examples/SFMdata.py create mode 100644 python/gtsam_py/python/examples/SimpleRotation.py create mode 100644 python/gtsam_py/python/examples/VisualISAM2Example.py create mode 100644 python/gtsam_py/python/examples/VisualISAMExample.py create mode 100644 python/gtsam_py/python/examples/__init__.py create mode 100644 python/gtsam_py/python/tests/__init__.py create mode 100644 python/gtsam_py/python/tests/testScenarioRunner.py create mode 100644 python/gtsam_py/python/tests/test_Cal3Unified.py create mode 100644 python/gtsam_py/python/tests/test_FrobeniusFactor.py create mode 100644 python/gtsam_py/python/tests/test_GaussianFactorGraph.py create mode 100644 python/gtsam_py/python/tests/test_JacobianFactor.py create mode 100644 python/gtsam_py/python/tests/test_KalmanFilter.py create mode 100644 python/gtsam_py/python/tests/test_KarcherMeanFactor.py create mode 100644 python/gtsam_py/python/tests/test_LocalizationExample.py create mode 100644 python/gtsam_py/python/tests/test_NonlinearOptimizer.py create mode 100644 python/gtsam_py/python/tests/test_OdometryExample.py create mode 100644 python/gtsam_py/python/tests/test_PlanarSLAMExample.py create mode 100644 python/gtsam_py/python/tests/test_Pose2.py create mode 100644 python/gtsam_py/python/tests/test_Pose2SLAMExample.py create mode 100644 python/gtsam_py/python/tests/test_Pose3.py create mode 100644 python/gtsam_py/python/tests/test_Pose3SLAMExample.py create mode 100644 python/gtsam_py/python/tests/test_PriorFactor.py create mode 100644 python/gtsam_py/python/tests/test_SFMExample.py create mode 100644 python/gtsam_py/python/tests/test_SO4.py create mode 100644 python/gtsam_py/python/tests/test_SOn.py create mode 100644 python/gtsam_py/python/tests/test_Scenario.py create mode 100644 python/gtsam_py/python/tests/test_SimpleCamera.py create mode 100644 python/gtsam_py/python/tests/test_StereoVOExample.py create mode 100644 python/gtsam_py/python/tests/test_Values.py create mode 100644 python/gtsam_py/python/tests/test_VisualISAMExample.py create mode 100644 python/gtsam_py/python/tests/test_dataset.py create mode 100644 python/gtsam_py/python/tests/test_dsf_map.py create mode 100644 python/gtsam_py/python/tests/test_initialize_pose3.py create mode 100644 python/gtsam_py/python/tests/test_logging_optimizer.py create mode 100644 python/gtsam_py/python/utils/__init__.py create mode 100644 python/gtsam_py/python/utils/circlePose3.py create mode 100644 python/gtsam_py/python/utils/logging_optimizer.py create mode 100644 python/gtsam_py/python/utils/plot.py create mode 100644 python/gtsam_py/python/utils/test_case.py create mode 100644 python/gtsam_py/python/utils/visual_data_generator.py create mode 100644 python/gtsam_py/python/utils/visual_isam.py diff --git a/python/gtsam_py/python/__init__.py b/python/gtsam_py/python/__init__.py new file mode 100644 index 000000000..d40ee4502 --- /dev/null +++ b/python/gtsam_py/python/__init__.py @@ -0,0 +1,26 @@ +from .gtsam import * + +try: + import gtsam_unstable + + + def _deprecated_wrapper(item, name): + def wrapper(*args, **kwargs): + from warnings import warn + message = ('importing the unstable item "{}" directly from gtsam is deprecated. '.format(name) + + 'Please import it from gtsam_unstable.') + warn(message) + return item(*args, **kwargs) + return wrapper + + + for name in dir(gtsam_unstable): + if not name.startswith('__'): + item = getattr(gtsam_unstable, name) + if callable(item): + item = _deprecated_wrapper(item, name) + globals()[name] = item + +except ImportError: + pass + diff --git a/python/gtsam_py/python/examples/DogLegOptimizerExample.py b/python/gtsam_py/python/examples/DogLegOptimizerExample.py new file mode 100644 index 000000000..776ceedc4 --- /dev/null +++ b/python/gtsam_py/python/examples/DogLegOptimizerExample.py @@ -0,0 +1,118 @@ +""" +GTSAM Copyright 2010-2019, Georgia Tech Research Corporation, +Atlanta, Georgia 30332-0415 +All Rights Reserved + +See LICENSE for the license information + +Example comparing DoglegOptimizer with Levenberg-Marquardt. +Author: Frank Dellaert +""" +# pylint: disable=no-member, invalid-name + +import math +import argparse + +import gtsam +import matplotlib.pyplot as plt +import numpy as np + + +def run(args): + """Test Dogleg vs LM, inspired by issue #452.""" + + # print parameters + print("num samples = {}, deltaInitial = {}".format( + args.num_samples, args.delta)) + + # Ground truth solution + T11 = gtsam.Pose2(0, 0, 0) + T12 = gtsam.Pose2(1, 0, 0) + T21 = gtsam.Pose2(0, 1, 0) + T22 = gtsam.Pose2(1, 1, 0) + + # Factor graph + graph = gtsam.NonlinearFactorGraph() + + # Priors + prior = gtsam.noiseModel_Isotropic.Sigma(3, 1) + graph.add(gtsam.PriorFactorPose2(11, T11, prior)) + graph.add(gtsam.PriorFactorPose2(21, T21, prior)) + + # Odometry + model = gtsam.noiseModel_Diagonal.Sigmas(np.array([0.01, 0.01, 0.3])) + graph.add(gtsam.BetweenFactorPose2(11, 12, T11.between(T12), model)) + graph.add(gtsam.BetweenFactorPose2(21, 22, T21.between(T22), model)) + + # Range + model_rho = gtsam.noiseModel_Isotropic.Sigma(1, 0.01) + graph.add(gtsam.RangeFactorPose2(12, 22, 1.0, model_rho)) + + params = gtsam.DoglegParams() + params.setDeltaInitial(args.delta) # default is 10 + + # Add progressively more noise to ground truth + sigmas = [0.01, 0.1, 0.2, 0.5, 1, 2, 5, 10, 20] + n = len(sigmas) + p_dl, s_dl, p_lm, s_lm = [0]*n, [0]*n, [0]*n, [0]*n + for i, sigma in enumerate(sigmas): + dl_fails, lm_fails = 0, 0 + # Attempt num_samples optimizations for both DL and LM + for _attempt in range(args.num_samples): + initial = gtsam.Values() + initial.insert(11, T11.retract(np.random.normal(0, sigma, 3))) + initial.insert(12, T12.retract(np.random.normal(0, sigma, 3))) + initial.insert(21, T21.retract(np.random.normal(0, sigma, 3))) + initial.insert(22, T22.retract(np.random.normal(0, sigma, 3))) + + # Run dogleg optimizer + dl = gtsam.DoglegOptimizer(graph, initial, params) + result = dl.optimize() + dl_fails += graph.error(result) > 1e-9 + + # Run + lm = gtsam.LevenbergMarquardtOptimizer(graph, initial) + result = lm.optimize() + lm_fails += graph.error(result) > 1e-9 + + # Calculate Bayes estimate of success probability + # using a beta prior of alpha=0.5, beta=0.5 + alpha, beta = 0.5, 0.5 + v = args.num_samples+alpha+beta + p_dl[i] = (args.num_samples-dl_fails+alpha)/v + p_lm[i] = (args.num_samples-lm_fails+alpha)/v + + def stddev(p): + """Calculate standard deviation.""" + return math.sqrt(p*(1-p)/(1+v)) + + s_dl[i] = stddev(p_dl[i]) + s_lm[i] = stddev(p_lm[i]) + + fmt = "sigma= {}:\tDL success {:.2f}% +/- {:.2f}%, LM success {:.2f}% +/- {:.2f}%" + print(fmt.format(sigma, + 100*p_dl[i], 100*s_dl[i], + 100*p_lm[i], 100*s_lm[i])) + + if args.plot: + fig, ax = plt.subplots() + dl_plot = plt.errorbar(sigmas, p_dl, yerr=s_dl, label="Dogleg") + lm_plot = plt.errorbar(sigmas, p_lm, yerr=s_lm, label="LM") + plt.title("Dogleg emprical success vs. LM") + plt.legend(handles=[dl_plot, lm_plot]) + ax.set_xlim(0, sigmas[-1]+1) + ax.set_ylim(0, 1) + plt.show() + + +if __name__ == "__main__": + parser = argparse.ArgumentParser( + description="Compare Dogleg and LM success rates") + parser.add_argument("-n", "--num_samples", type=int, default=1000, + help="Number of samples for each sigma") + parser.add_argument("-d", "--delta", type=float, default=10.0, + help="Initial delta for dogleg") + parser.add_argument("-p", "--plot", action="store_true", + help="Flag to plot results") + args = parser.parse_args() + run(args) diff --git a/python/gtsam_py/python/examples/GPSFactorExample.py b/python/gtsam_py/python/examples/GPSFactorExample.py new file mode 100644 index 000000000..493a07725 --- /dev/null +++ b/python/gtsam_py/python/examples/GPSFactorExample.py @@ -0,0 +1,56 @@ +""" +GTSAM Copyright 2010-2018, Georgia Tech Research Corporation, +Atlanta, Georgia 30332-0415 +All Rights Reserved +Authors: Frank Dellaert, et al. (see THANKS for the full author list) + +See LICENSE for the license information + +Simple robot motion example, with prior and one GPS measurements +Author: Mandy Xie +""" +# pylint: disable=invalid-name, E1101 + +from __future__ import print_function + +import numpy as np + +import gtsam + +import matplotlib.pyplot as plt +import gtsam.utils.plot as gtsam_plot + +# ENU Origin is where the plane was in hold next to runway +lat0 = 33.86998 +lon0 = -84.30626 +h0 = 274 + +# Create noise models +GPS_NOISE = gtsam.noiseModel_Isotropic.Sigma(3, 0.1) +PRIOR_NOISE = gtsam.noiseModel_Isotropic.Sigma(6, 0.25) + +# Create an empty nonlinear factor graph +graph = gtsam.NonlinearFactorGraph() + +# Add a prior on the first point, setting it to the origin +# A prior factor consists of a mean and a noise model (covariance matrix) +priorMean = gtsam.Pose3() # prior at origin +graph.add(gtsam.PriorFactorPose3(1, priorMean, PRIOR_NOISE)) + +# Add GPS factors +gps = gtsam.Point3(lat0, lon0, h0) +graph.add(gtsam.GPSFactor(1, gps, GPS_NOISE)) +print("\nFactor Graph:\n{}".format(graph)) + +# Create the data structure to hold the initialEstimate estimate to the solution +# For illustrative purposes, these have been deliberately set to incorrect values +initial = gtsam.Values() +initial.insert(1, gtsam.Pose3()) +print("\nInitial Estimate:\n{}".format(initial)) + +# optimize using Levenberg-Marquardt optimization +params = gtsam.LevenbergMarquardtParams() +optimizer = gtsam.LevenbergMarquardtOptimizer(graph, initial, params) +result = optimizer.optimize() +print("\nFinal Result:\n{}".format(result)) + diff --git a/python/gtsam_py/python/examples/ImuFactorExample.py b/python/gtsam_py/python/examples/ImuFactorExample.py new file mode 100644 index 000000000..0e01766e7 --- /dev/null +++ b/python/gtsam_py/python/examples/ImuFactorExample.py @@ -0,0 +1,153 @@ +""" +GTSAM Copyright 2010-2019, Georgia Tech Research Corporation, +Atlanta, Georgia 30332-0415 +All Rights Reserved + +See LICENSE for the license information + +A script validating and demonstrating the ImuFactor inference. + +Author: Frank Dellaert, Varun Agrawal +""" + +from __future__ import print_function + +import math + +import gtsam +import matplotlib.pyplot as plt +import numpy as np +from gtsam import symbol_shorthand_B as B +from gtsam import symbol_shorthand_V as V +from gtsam import symbol_shorthand_X as X +from gtsam.utils.plot import plot_pose3 +from mpl_toolkits.mplot3d import Axes3D + +from PreintegrationExample import POSES_FIG, PreintegrationExample + +BIAS_KEY = B(0) + + +np.set_printoptions(precision=3, suppress=True) + + +class ImuFactorExample(PreintegrationExample): + + def __init__(self): + self.velocity = np.array([2, 0, 0]) + self.priorNoise = gtsam.noiseModel_Isotropic.Sigma(6, 0.1) + self.velNoise = gtsam.noiseModel_Isotropic.Sigma(3, 0.1) + + # Choose one of these twists to change scenario: + zero_twist = (np.zeros(3), np.zeros(3)) + forward_twist = (np.zeros(3), self.velocity) + loop_twist = (np.array([0, -math.radians(30), 0]), self.velocity) + sick_twist = ( + np.array([math.radians(30), -math.radians(30), 0]), self.velocity) + + accBias = np.array([-0.3, 0.1, 0.2]) + gyroBias = np.array([0.1, 0.3, -0.1]) + bias = gtsam.imuBias_ConstantBias(accBias, gyroBias) + + dt = 1e-2 + super(ImuFactorExample, self).__init__(sick_twist, bias, dt) + + def addPrior(self, i, graph): + state = self.scenario.navState(i) + graph.push_back(gtsam.PriorFactorPose3( + X(i), state.pose(), self.priorNoise)) + graph.push_back(gtsam.PriorFactorVector( + V(i), state.velocity(), self.velNoise)) + + def run(self): + graph = gtsam.NonlinearFactorGraph() + + # initialize data structure for pre-integrated IMU measurements + pim = gtsam.PreintegratedImuMeasurements(self.params, self.actualBias) + + T = 12 + num_poses = T + 1 # assumes 1 factor per second + initial = gtsam.Values() + initial.insert(BIAS_KEY, self.actualBias) + for i in range(num_poses): + state_i = self.scenario.navState(float(i)) + + poseNoise = gtsam.Pose3.Expmap(np.random.randn(3)*0.1) + pose = state_i.pose().compose(poseNoise) + + velocity = state_i.velocity() + np.random.randn(3)*0.1 + + initial.insert(X(i), pose) + initial.insert(V(i), velocity) + + # simulate the loop + i = 0 # state index + actual_state_i = self.scenario.navState(0) + for k, t in enumerate(np.arange(0, T, self.dt)): + # get measurements and add them to PIM + measuredOmega = self.runner.measuredAngularVelocity(t) + measuredAcc = self.runner.measuredSpecificForce(t) + pim.integrateMeasurement(measuredAcc, measuredOmega, self.dt) + + poseNoise = gtsam.Pose3.Expmap(np.random.randn(3)*0.1) + + actual_state_i = gtsam.NavState( + actual_state_i.pose().compose(poseNoise), + actual_state_i.velocity() + np.random.randn(3)*0.1) + + # Plot IMU many times + if k % 10 == 0: + self.plotImu(t, measuredOmega, measuredAcc) + + # Plot every second + if k % int(1 / self.dt) == 0: + self.plotGroundTruthPose(t) + + # create IMU factor every second + if (k + 1) % int(1 / self.dt) == 0: + factor = gtsam.ImuFactor(X(i), V(i), X( + i + 1), V(i + 1), BIAS_KEY, pim) + graph.push_back(factor) + if True: + print(factor) + print(pim.predict(actual_state_i, self.actualBias)) + pim.resetIntegration() + actual_state_i = self.scenario.navState(t + self.dt) + i += 1 + + # add priors on beginning and end + self.addPrior(0, graph) + self.addPrior(num_poses - 1, graph) + + # optimize using Levenberg-Marquardt optimization + params = gtsam.LevenbergMarquardtParams() + params.setVerbosityLM("SUMMARY") + optimizer = gtsam.LevenbergMarquardtOptimizer(graph, initial, params) + result = optimizer.optimize() + + # Calculate and print marginal covariances + marginals = gtsam.Marginals(graph, result) + print("Covariance on bias:\n", marginals.marginalCovariance(BIAS_KEY)) + for i in range(num_poses): + print("Covariance on pose {}:\n{}\n".format( + i, marginals.marginalCovariance(X(i)))) + print("Covariance on vel {}:\n{}\n".format( + i, marginals.marginalCovariance(V(i)))) + + # Plot resulting poses + i = 0 + while result.exists(X(i)): + pose_i = result.atPose3(X(i)) + plot_pose3(POSES_FIG, pose_i, 0.1) + i += 1 + + gtsam.utils.plot.set_axes_equal(POSES_FIG) + + print(result.atimuBias_ConstantBias(BIAS_KEY)) + + plt.ioff() + plt.show() + + +if __name__ == '__main__': + ImuFactorExample().run() diff --git a/python/gtsam_py/python/examples/ImuFactorExample2.py b/python/gtsam_py/python/examples/ImuFactorExample2.py new file mode 100644 index 000000000..0d98f08fe --- /dev/null +++ b/python/gtsam_py/python/examples/ImuFactorExample2.py @@ -0,0 +1,172 @@ +""" +iSAM2 example with ImuFactor. +Author: Robert Truax (C++), Frank Dellaert (Python) +""" +# pylint: disable=invalid-name, E1101 + +from __future__ import print_function + +import math + +import gtsam +import gtsam.utils.plot as gtsam_plot +import matplotlib.pyplot as plt +import numpy as np +from gtsam import (ISAM2, BetweenFactorConstantBias, Cal3_S2, + ConstantTwistScenario, ImuFactor, NonlinearFactorGraph, + PinholeCameraCal3_S2, Point3, Pose3, + PriorFactorConstantBias, PriorFactorPose3, + PriorFactorVector, Rot3, Values) +from gtsam import symbol_shorthand_B as B +from gtsam import symbol_shorthand_V as V +from gtsam import symbol_shorthand_X as X +from mpl_toolkits.mplot3d import Axes3D # pylint: disable=W0611 + + +def vector3(x, y, z): + """Create 3d double numpy array.""" + return np.array([x, y, z], dtype=np.float) + + +def ISAM2_plot(values, fignum=0): + """Plot poses.""" + fig = plt.figure(fignum) + axes = fig.gca(projection='3d') + plt.cla() + + i = 0 + min_bounds = 0, 0, 0 + max_bounds = 0, 0, 0 + while values.exists(X(i)): + pose_i = values.atPose3(X(i)) + gtsam_plot.plot_pose3(fignum, pose_i, 10) + position = pose_i.translation().vector() + min_bounds = [min(v1, v2) for (v1, v2) in zip(position, min_bounds)] + max_bounds = [max(v1, v2) for (v1, v2) in zip(position, max_bounds)] + # max_bounds = min(pose_i.x(), max_bounds[0]), 0, 0 + i += 1 + + # draw + axes.set_xlim3d(min_bounds[0]-1, max_bounds[0]+1) + axes.set_ylim3d(min_bounds[1]-1, max_bounds[1]+1) + axes.set_zlim3d(min_bounds[2]-1, max_bounds[2]+1) + plt.pause(1) + + +# IMU preintegration parameters +# Default Params for a Z-up navigation frame, such as ENU: gravity points along negative Z-axis +g = 9.81 +n_gravity = vector3(0, 0, -g) +PARAMS = gtsam.PreintegrationParams.MakeSharedU(g) +I = np.eye(3) +PARAMS.setAccelerometerCovariance(I * 0.1) +PARAMS.setGyroscopeCovariance(I * 0.1) +PARAMS.setIntegrationCovariance(I * 0.1) +PARAMS.setUse2ndOrderCoriolis(False) +PARAMS.setOmegaCoriolis(vector3(0, 0, 0)) + +BIAS_COVARIANCE = gtsam.noiseModel_Isotropic.Variance(6, 0.1) +DELTA = Pose3(Rot3.Rodrigues(0, 0, 0), + Point3(0.05, -0.10, 0.20)) + + +def IMU_example(): + """Run iSAM 2 example with IMU factor.""" + + # Start with a camera on x-axis looking at origin + radius = 30 + up = Point3(0, 0, 1) + target = Point3(0, 0, 0) + position = Point3(radius, 0, 0) + camera = PinholeCameraCal3_S2.Lookat(position, target, up, Cal3_S2()) + pose_0 = camera.pose() + + # Create the set of ground-truth landmarks and poses + angular_velocity = math.radians(180) # rad/sec + delta_t = 1.0/18 # makes for 10 degrees per step + + angular_velocity_vector = vector3(0, -angular_velocity, 0) + linear_velocity_vector = vector3(radius * angular_velocity, 0, 0) + scenario = ConstantTwistScenario( + angular_velocity_vector, linear_velocity_vector, pose_0) + + # Create a factor graph + newgraph = NonlinearFactorGraph() + + # Create (incremental) ISAM2 solver + isam = ISAM2() + + # Create the initial estimate to the solution + # Intentionally initialize the variables off from the ground truth + initialEstimate = Values() + + # Add a prior on pose x0. This indirectly specifies where the origin is. + # 30cm std on x,y,z 0.1 rad on roll,pitch,yaw + noise = gtsam.noiseModel_Diagonal.Sigmas( + np.array([0.1, 0.1, 0.1, 0.3, 0.3, 0.3])) + newgraph.push_back(PriorFactorPose3(X(0), pose_0, noise)) + + # Add imu priors + biasKey = B(0) + biasnoise = gtsam.noiseModel_Isotropic.Sigma(6, 0.1) + biasprior = PriorFactorConstantBias(biasKey, gtsam.imuBias_ConstantBias(), + biasnoise) + newgraph.push_back(biasprior) + initialEstimate.insert(biasKey, gtsam.imuBias_ConstantBias()) + velnoise = gtsam.noiseModel_Isotropic.Sigma(3, 0.1) + + # Calculate with correct initial velocity + n_velocity = vector3(0, angular_velocity * radius, 0) + velprior = PriorFactorVector(V(0), n_velocity, velnoise) + newgraph.push_back(velprior) + initialEstimate.insert(V(0), n_velocity) + + accum = gtsam.PreintegratedImuMeasurements(PARAMS) + + # Simulate poses and imu measurements, adding them to the factor graph + for i in range(80): + t = i * delta_t # simulation time + if i == 0: # First time add two poses + pose_1 = scenario.pose(delta_t) + initialEstimate.insert(X(0), pose_0.compose(DELTA)) + initialEstimate.insert(X(1), pose_1.compose(DELTA)) + elif i >= 2: # Add more poses as necessary + pose_i = scenario.pose(t) + initialEstimate.insert(X(i), pose_i.compose(DELTA)) + + if i > 0: + # Add Bias variables periodically + if i % 5 == 0: + biasKey += 1 + factor = BetweenFactorConstantBias( + biasKey - 1, biasKey, gtsam.imuBias_ConstantBias(), BIAS_COVARIANCE) + newgraph.add(factor) + initialEstimate.insert(biasKey, gtsam.imuBias_ConstantBias()) + + # Predict acceleration and gyro measurements in (actual) body frame + nRb = scenario.rotation(t).matrix() + bRn = np.transpose(nRb) + measuredAcc = scenario.acceleration_b(t) - np.dot(bRn, n_gravity) + measuredOmega = scenario.omega_b(t) + accum.integrateMeasurement(measuredAcc, measuredOmega, delta_t) + + # Add Imu Factor + imufac = ImuFactor(X(i - 1), V(i - 1), X(i), V(i), biasKey, accum) + newgraph.add(imufac) + + # insert new velocity, which is wrong + initialEstimate.insert(V(i), n_velocity) + accum.resetIntegration() + + # Incremental solution + isam.update(newgraph, initialEstimate) + result = isam.calculateEstimate() + ISAM2_plot(result) + + # reset + newgraph = NonlinearFactorGraph() + initialEstimate.clear() + + +if __name__ == '__main__': + IMU_example() diff --git a/python/gtsam_py/python/examples/OdometryExample.py b/python/gtsam_py/python/examples/OdometryExample.py new file mode 100644 index 000000000..e778e3f85 --- /dev/null +++ b/python/gtsam_py/python/examples/OdometryExample.py @@ -0,0 +1,69 @@ +""" +GTSAM Copyright 2010-2018, Georgia Tech Research Corporation, +Atlanta, Georgia 30332-0415 +All Rights Reserved +Authors: Frank Dellaert, et al. (see THANKS for the full author list) + +See LICENSE for the license information + +Simple robot motion example, with prior and two odometry measurements +Author: Frank Dellaert +""" +# pylint: disable=invalid-name, E1101 + +from __future__ import print_function + +import numpy as np + +import gtsam + +import matplotlib.pyplot as plt +import gtsam.utils.plot as gtsam_plot + +# Create noise models +ODOMETRY_NOISE = gtsam.noiseModel_Diagonal.Sigmas(np.array([0.2, 0.2, 0.1])) +PRIOR_NOISE = gtsam.noiseModel_Diagonal.Sigmas(np.array([0.3, 0.3, 0.1])) + +# Create an empty nonlinear factor graph +graph = gtsam.NonlinearFactorGraph() + +# Add a prior on the first pose, setting it to the origin +# A prior factor consists of a mean and a noise model (covariance matrix) +priorMean = gtsam.Pose2(0.0, 0.0, 0.0) # prior at origin +graph.add(gtsam.PriorFactorPose2(1, priorMean, PRIOR_NOISE)) + +# Add odometry factors +odometry = gtsam.Pose2(2.0, 0.0, 0.0) +# For simplicity, we will use the same noise model for each odometry factor +# Create odometry (Between) factors between consecutive poses +graph.add(gtsam.BetweenFactorPose2(1, 2, odometry, ODOMETRY_NOISE)) +graph.add(gtsam.BetweenFactorPose2(2, 3, odometry, ODOMETRY_NOISE)) +print("\nFactor Graph:\n{}".format(graph)) + +# Create the data structure to hold the initialEstimate estimate to the solution +# For illustrative purposes, these have been deliberately set to incorrect values +initial = gtsam.Values() +initial.insert(1, gtsam.Pose2(0.5, 0.0, 0.2)) +initial.insert(2, gtsam.Pose2(2.3, 0.1, -0.2)) +initial.insert(3, gtsam.Pose2(4.1, 0.1, 0.1)) +print("\nInitial Estimate:\n{}".format(initial)) + +# optimize using Levenberg-Marquardt optimization +params = gtsam.LevenbergMarquardtParams() +optimizer = gtsam.LevenbergMarquardtOptimizer(graph, initial, params) +result = optimizer.optimize() +print("\nFinal Result:\n{}".format(result)) + +# 5. Calculate and print marginal covariances for all variables +marginals = gtsam.Marginals(graph, result) +for i in range(1, 4): + print("X{} covariance:\n{}\n".format(i, marginals.marginalCovariance(i))) + +fig = plt.figure(0) +for i in range(1, 4): + gtsam_plot.plot_pose2(0, result.atPose2(i), 0.5, marginals.marginalCovariance(i)) +plt.axis('equal') +plt.show() + + + diff --git a/python/gtsam_py/python/examples/PlanarManipulatorExample.py b/python/gtsam_py/python/examples/PlanarManipulatorExample.py new file mode 100644 index 000000000..e42ae09d7 --- /dev/null +++ b/python/gtsam_py/python/examples/PlanarManipulatorExample.py @@ -0,0 +1,334 @@ +""" +GTSAM Copyright 2010-2018, Georgia Tech Research Corporation, +Atlanta, Georgia 30332-0415 +All Rights Reserved +Authors: Frank Dellaert, et al. (see THANKS for the full author list) + +See LICENSE for the license information + +Kinematics of three-link manipulator with GTSAM poses and product of exponential maps. +Author: Frank Dellaert +""" +# pylint: disable=invalid-name, E1101 + +from __future__ import print_function + +import math +import unittest +from functools import reduce + +import matplotlib.pyplot as plt +import numpy as np +from mpl_toolkits.mplot3d import Axes3D # pylint: disable=W0611 + +import gtsam +import gtsam.utils.plot as gtsam_plot +from gtsam import Pose2 +from gtsam.utils.test_case import GtsamTestCase + + +def vector3(x, y, z): + """Create 3D double numpy array.""" + return np.array([x, y, z], dtype=np.float) + + +def compose(*poses): + """Compose all Pose2 transforms given as arguments from left to right.""" + return reduce((lambda x, y: x.compose(y)), poses) + + +def vee(M): + """Pose2 vee operator.""" + return vector3(M[0, 2], M[1, 2], M[1, 0]) + + +def delta(g0, g1): + """Difference between x,y,,theta components of SE(2) poses.""" + return vector3(g1.x() - g0.x(), g1.y() - g0.y(), g1.theta() - g0.theta()) + + +def trajectory(g0, g1, N=20): + """ Create an interpolated trajectory in SE(2), treating x,y, and theta separately. + g0 and g1 are the initial and final pose, respectively. + N is the number of *intervals* + Returns N+1 poses + """ + e = delta(g0, g1) + return [Pose2(g0.x()+e[0]*t, g0.y()+e[1]*t, g0.theta()+e[2]*t) for t in np.linspace(0, 1, N)] + + +class ThreeLinkArm(object): + """Three-link arm class.""" + + def __init__(self): + self.L1 = 3.5 + self.L2 = 3.5 + self.L3 = 2.5 + self.xi1 = vector3(0, 0, 1) + self.xi2 = vector3(self.L1, 0, 1) + self.xi3 = vector3(self.L1+self.L2, 0, 1) + self.sXt0 = Pose2(0, self.L1+self.L2 + self.L3, math.radians(90)) + + def fk(self, q): + """ Forward kinematics. + Takes numpy array of joint angles, in radians. + """ + sXl1 = Pose2(0, 0, math.radians(90)) + l1Zl1 = Pose2(0, 0, q[0]) + l1Xl2 = Pose2(self.L1, 0, 0) + l2Zl2 = Pose2(0, 0, q[1]) + l2Xl3 = Pose2(self.L2, 0, 0) + l3Zl3 = Pose2(0, 0, q[2]) + l3Xt = Pose2(self.L3, 0, 0) + return compose(sXl1, l1Zl1, l1Xl2, l2Zl2, l2Xl3, l3Zl3, l3Xt) + + def jacobian(self, q): + """ Calculate manipulator Jacobian. + Takes numpy array of joint angles, in radians. + """ + a = q[0]+q[1] + b = a+q[2] + return np.array([[-self.L1*math.cos(q[0]) - self.L2*math.cos(a)-self.L3*math.cos(b), + -self.L1*math.cos(a)-self.L3*math.cos(b), + - self.L3*math.cos(b)], + [-self.L1*math.sin(q[0]) - self.L2*math.sin(a)-self.L3*math.sin(b), + -self.L1*math.sin(a)-self.L3*math.sin(b), + - self.L3*math.sin(b)], + [1, 1, 1]], np.float) + + def poe(self, q): + """ Forward kinematics. + Takes numpy array of joint angles, in radians. + """ + l1Zl1 = Pose2.Expmap(self.xi1 * q[0]) + l2Zl2 = Pose2.Expmap(self.xi2 * q[1]) + l3Zl3 = Pose2.Expmap(self.xi3 * q[2]) + return compose(l1Zl1, l2Zl2, l3Zl3, self.sXt0) + + def con(self, q): + """ Forward kinematics, conjugation form. + Takes numpy array of joint angles, in radians. + """ + def expmap(x, y, theta): + """Implement exponential map via conjugation with axis (x,y).""" + return compose(Pose2(x, y, 0), Pose2(0, 0, theta), Pose2(-x, -y, 0)) + + l1Zl1 = expmap(0.0, 0.0, q[0]) + l2Zl2 = expmap(0.0, self.L1, q[1]) + l3Zl3 = expmap(0.0, self.L1+self.L2, q[2]) + return compose(l1Zl1, l2Zl2, l3Zl3, self.sXt0) + + def ik(self, sTt_desired, e=1e-9): + """ Inverse kinematics. + Takes desired Pose2 of tool T with respect to base S. + Optional: mu, gradient descent rate; e: error norm threshold + """ + q = np.radians(vector3(30, -30, 45)) # well within workspace + error = vector3(100, 100, 100) + + while np.linalg.norm(error) > e: + error = delta(sTt_desired, self.fk(q)) + J = self.jacobian(q) + q -= np.dot(np.linalg.pinv(J), error) + + # return result in interval [-pi,pi) + return np.remainder(q+math.pi, 2*math.pi)-math.pi + + def manipulator_jacobian(self, q): + """ Calculate manipulator Jacobian. + Takes numpy array of joint angles, in radians. + Returns the manipulator Jacobian of differential twists. When multiplied with + a vector of joint velocities, will yield a single differential twist which is + the spatial velocity d(sTt)/dt * inv(sTt) of the end-effector pose. + Just like always, differential twists can be hatted and multiplied with spatial + coordinates of a point to give the spatial velocity of the point. + """ + l1Zl1 = Pose2.Expmap(self.xi1 * q[0]) + l2Zl2 = Pose2.Expmap(self.xi2 * q[1]) + # l3Zl3 = Pose2.Expmap(self.xi3 * q[2]) + + p1 = self.xi1 + # p1 = Pose2().Adjoint(self.xi1) + + sTl1 = l1Zl1 + p2 = sTl1.Adjoint(self.xi2) + + sTl2 = compose(l1Zl1, l2Zl2) + p3 = sTl2.Adjoint(self.xi3) + + differential_twists = [p1, p2, p3] + return np.stack(differential_twists, axis=1) + + def plot(self, fignum, q): + """ Plot arm. + Takes figure number, and numpy array of joint angles, in radians. + """ + fig = plt.figure(fignum) + axes = fig.gca() + + sXl1 = Pose2(0, 0, math.radians(90)) + t = sXl1.translation() + p1 = np.array([t.x(), t.y()]) + gtsam_plot.plot_pose2_on_axes(axes, sXl1) + + def plot_line(p, g, color): + t = g.translation() + q = np.array([t.x(), t.y()]) + line = np.append(p[np.newaxis], q[np.newaxis], axis=0) + axes.plot(line[:, 0], line[:, 1], color) + return q + + l1Zl1 = Pose2(0, 0, q[0]) + l1Xl2 = Pose2(self.L1, 0, 0) + sTl2 = compose(sXl1, l1Zl1, l1Xl2) + p2 = plot_line(p1, sTl2, 'r-') + gtsam_plot.plot_pose2_on_axes(axes, sTl2) + + l2Zl2 = Pose2(0, 0, q[1]) + l2Xl3 = Pose2(self.L2, 0, 0) + sTl3 = compose(sTl2, l2Zl2, l2Xl3) + p3 = plot_line(p2, sTl3, 'g-') + gtsam_plot.plot_pose2_on_axes(axes, sTl3) + + l3Zl3 = Pose2(0, 0, q[2]) + l3Xt = Pose2(self.L3, 0, 0) + sTt = compose(sTl3, l3Zl3, l3Xt) + plot_line(p3, sTt, 'b-') + gtsam_plot.plot_pose2_on_axes(axes, sTt) + + +# Create common example configurations. +Q0 = vector3(0, 0, 0) +Q1 = np.radians(vector3(-30, -45, -90)) +Q2 = np.radians(vector3(-90, 90, 0)) + + +class TestPose2SLAMExample(GtsamTestCase): + """Unit tests for functions used below.""" + + def setUp(self): + self.arm = ThreeLinkArm() + + def assertPose2Equals(self, actual, expected, tol=1e-2): + """Helper function that prints out actual and expected if not equal.""" + equal = actual.equals(expected, tol) + if not equal: + raise self.failureException( + "Poses are not equal:\n{}!={}".format(actual, expected)) + + def test_fk_arm(self): + """Make sure forward kinematics is correct for some known test configurations.""" + # at rest + expected = Pose2(0, 2*3.5 + 2.5, math.radians(90)) + sTt = self.arm.fk(Q0) + self.assertIsInstance(sTt, Pose2) + self.assertPose2Equals(sTt, expected) + + # -30, -45, -90 + expected = Pose2(5.78, 1.52, math.radians(-75)) + sTt = self.arm.fk(Q1) + self.assertPose2Equals(sTt, expected) + + def test_jacobian(self): + """Test Jacobian calculation.""" + # at rest + expected = np.array([[-9.5, -6, -2.5], [0, 0, 0], [1, 1, 1]], np.float) + J = self.arm.jacobian(Q0) + np.testing.assert_array_almost_equal(J, expected) + + # at -90, 90, 0 + expected = np.array([[-6, -6, -2.5], [3.5, 0, 0], [1, 1, 1]], np.float) + J = self.arm.jacobian(Q2) + np.testing.assert_array_almost_equal(J, expected) + + def test_con_arm(self): + """Make sure POE is correct for some known test configurations.""" + # at rest + expected = Pose2(0, 2*3.5 + 2.5, math.radians(90)) + sTt = self.arm.con(Q0) + self.assertIsInstance(sTt, Pose2) + self.assertPose2Equals(sTt, expected) + + # -30, -45, -90 + expected = Pose2(5.78, 1.52, math.radians(-75)) + sTt = self.arm.con(Q1) + self.assertPose2Equals(sTt, expected) + + def test_poe_arm(self): + """Make sure POE is correct for some known test configurations.""" + # at rest + expected = Pose2(0, 2*3.5 + 2.5, math.radians(90)) + sTt = self.arm.poe(Q0) + self.assertIsInstance(sTt, Pose2) + self.assertPose2Equals(sTt, expected) + + # -30, -45, -90 + expected = Pose2(5.78, 1.52, math.radians(-75)) + sTt = self.arm.poe(Q1) + self.assertPose2Equals(sTt, expected) + + def test_ik(self): + """Check iterative inverse kinematics function.""" + # at rest + actual = self.arm.ik(Pose2(0, 2*3.5 + 2.5, math.radians(90))) + np.testing.assert_array_almost_equal(actual, Q0, decimal=2) + + # -30, -45, -90 + sTt_desired = Pose2(5.78, 1.52, math.radians(-75)) + actual = self.arm.ik(sTt_desired) + self.assertPose2Equals(self.arm.fk(actual), sTt_desired) + np.testing.assert_array_almost_equal(actual, Q1, decimal=2) + + def test_manipulator_jacobian(self): + """Test Jacobian calculation.""" + # at rest + expected = np.array([[0, 3.5, 7], [0, 0, 0], [1, 1, 1]], np.float) + J = self.arm.manipulator_jacobian(Q0) + np.testing.assert_array_almost_equal(J, expected) + + # at -90, 90, 0 + expected = np.array( + [[0, 0, 3.5], [0, -3.5, -3.5], [1, 1, 1]], np.float) + J = self.arm.manipulator_jacobian(Q2) + np.testing.assert_array_almost_equal(J, expected) + + +def run_example(): + """ Use trajectory interpolation and then trajectory tracking a la Murray + to move a 3-link arm on a straight line. + """ + # Create arm + arm = ThreeLinkArm() + + # Get initial pose using forward kinematics + q = np.radians(vector3(30, -30, 45)) + sTt_initial = arm.fk(q) + + # Create interpolated trajectory in task space to desired goal pose + sTt_goal = Pose2(2.4, 4.3, math.radians(0)) + poses = trajectory(sTt_initial, sTt_goal, 50) + + # Setup figure and plot initial pose + fignum = 0 + fig = plt.figure(fignum) + axes = fig.gca() + axes.set_xlim(-5, 5) + axes.set_ylim(0, 10) + gtsam_plot.plot_pose2(fignum, arm.fk(q)) + + # For all poses in interpolated trajectory, calculate dq to move to next pose. + # We do this by calculating the local Jacobian J and doing dq = inv(J)*delta(sTt, pose). + for pose in poses: + sTt = arm.fk(q) + error = delta(sTt, pose) + J = arm.jacobian(q) + q += np.dot(np.linalg.inv(J), error) + arm.plot(fignum, q) + plt.pause(0.01) + + plt.pause(10) + + +if __name__ == "__main__": + run_example() + unittest.main() diff --git a/python/gtsam_py/python/examples/PlanarSLAMExample.py b/python/gtsam_py/python/examples/PlanarSLAMExample.py new file mode 100644 index 000000000..c84f0f834 --- /dev/null +++ b/python/gtsam_py/python/examples/PlanarSLAMExample.py @@ -0,0 +1,81 @@ +""" +GTSAM Copyright 2010-2018, Georgia Tech Research Corporation, +Atlanta, Georgia 30332-0415 +All Rights Reserved +Authors: Frank Dellaert, et al. (see THANKS for the full author list) + +See LICENSE for the license information + +Simple robotics example using odometry measurements and bearing-range (laser) measurements +Author: Alex Cunningham (C++), Kevin Deng & Frank Dellaert (Python) +""" +# pylint: disable=invalid-name, E1101 + +from __future__ import print_function + +import gtsam +import numpy as np +from gtsam import symbol_shorthand_L as L +from gtsam import symbol_shorthand_X as X + +# Create noise models +PRIOR_NOISE = gtsam.noiseModel_Diagonal.Sigmas(np.array([0.3, 0.3, 0.1])) +ODOMETRY_NOISE = gtsam.noiseModel_Diagonal.Sigmas(np.array([0.2, 0.2, 0.1])) +MEASUREMENT_NOISE = gtsam.noiseModel_Diagonal.Sigmas(np.array([0.1, 0.2])) + +# Create an empty nonlinear factor graph +graph = gtsam.NonlinearFactorGraph() + +# Create the keys corresponding to unknown variables in the factor graph +X1 = X(1) +X2 = X(2) +X3 = X(3) +L1 = L(4) +L2 = L(5) + +# Add a prior on pose X1 at the origin. A prior factor consists of a mean and a noise model +graph.add(gtsam.PriorFactorPose2(X1, gtsam.Pose2(0.0, 0.0, 0.0), PRIOR_NOISE)) + +# Add odometry factors between X1,X2 and X2,X3, respectively +graph.add(gtsam.BetweenFactorPose2( + X1, X2, gtsam.Pose2(2.0, 0.0, 0.0), ODOMETRY_NOISE)) +graph.add(gtsam.BetweenFactorPose2( + X2, X3, gtsam.Pose2(2.0, 0.0, 0.0), ODOMETRY_NOISE)) + +# Add Range-Bearing measurements to two different landmarks L1 and L2 +graph.add(gtsam.BearingRangeFactor2D( + X1, L1, gtsam.Rot2.fromDegrees(45), np.sqrt(4.0+4.0), MEASUREMENT_NOISE)) +graph.add(gtsam.BearingRangeFactor2D( + X2, L1, gtsam.Rot2.fromDegrees(90), 2.0, MEASUREMENT_NOISE)) +graph.add(gtsam.BearingRangeFactor2D( + X3, L2, gtsam.Rot2.fromDegrees(90), 2.0, MEASUREMENT_NOISE)) + +# Print graph +print("Factor Graph:\n{}".format(graph)) + +# Create (deliberately inaccurate) initial estimate +initial_estimate = gtsam.Values() +initial_estimate.insert(X1, gtsam.Pose2(-0.25, 0.20, 0.15)) +initial_estimate.insert(X2, gtsam.Pose2(2.30, 0.10, -0.20)) +initial_estimate.insert(X3, gtsam.Pose2(4.10, 0.10, 0.10)) +initial_estimate.insert(L1, gtsam.Point2(1.80, 2.10)) +initial_estimate.insert(L2, gtsam.Point2(4.10, 1.80)) + +# Print +print("Initial Estimate:\n{}".format(initial_estimate)) + +# Optimize using Levenberg-Marquardt optimization. The optimizer +# accepts an optional set of configuration parameters, controlling +# things like convergence criteria, the type of linear system solver +# to use, and the amount of information displayed during optimization. +# Here we will use the default set of parameters. See the +# documentation for the full set of parameters. +params = gtsam.LevenbergMarquardtParams() +optimizer = gtsam.LevenbergMarquardtOptimizer(graph, initial_estimate, params) +result = optimizer.optimize() +print("\nFinal Result:\n{}".format(result)) + +# Calculate and print marginal covariances for all variables +marginals = gtsam.Marginals(graph, result) +for (key, str) in [(X1, "X1"), (X2, "X2"), (X3, "X3"), (L1, "L1"), (L2, "L2")]: + print("{} covariance:\n{}\n".format(str, marginals.marginalCovariance(key))) diff --git a/python/gtsam_py/python/examples/Pose2SLAMExample.py b/python/gtsam_py/python/examples/Pose2SLAMExample.py new file mode 100644 index 000000000..680f2209f --- /dev/null +++ b/python/gtsam_py/python/examples/Pose2SLAMExample.py @@ -0,0 +1,97 @@ +""" +GTSAM Copyright 2010-2018, Georgia Tech Research Corporation, +Atlanta, Georgia 30332-0415 +All Rights Reserved +Authors: Frank Dellaert, et al. (see THANKS for the full author list) + +See LICENSE for the license information + +Simple robotics example using odometry measurements and bearing-range (laser) measurements +Author: Alex Cunningham (C++), Kevin Deng & Frank Dellaert (Python) +""" +# pylint: disable=invalid-name, E1101 + +from __future__ import print_function + +import math + +import numpy as np + +import gtsam + +import matplotlib.pyplot as plt +import gtsam.utils.plot as gtsam_plot + + +def vector3(x, y, z): + """Create 3d double numpy array.""" + return np.array([x, y, z], dtype=np.float) + + +# Create noise models +PRIOR_NOISE = gtsam.noiseModel_Diagonal.Sigmas(vector3(0.3, 0.3, 0.1)) +ODOMETRY_NOISE = gtsam.noiseModel_Diagonal.Sigmas(vector3(0.2, 0.2, 0.1)) + +# 1. Create a factor graph container and add factors to it +graph = gtsam.NonlinearFactorGraph() + +# 2a. Add a prior on the first pose, setting it to the origin +# A prior factor consists of a mean and a noise ODOMETRY_NOISE (covariance matrix) +graph.add(gtsam.PriorFactorPose2(1, gtsam.Pose2(0, 0, 0), PRIOR_NOISE)) + +# 2b. Add odometry factors +# Create odometry (Between) factors between consecutive poses +graph.add(gtsam.BetweenFactorPose2(1, 2, gtsam.Pose2(2, 0, 0), ODOMETRY_NOISE)) +graph.add(gtsam.BetweenFactorPose2( + 2, 3, gtsam.Pose2(2, 0, math.pi / 2), ODOMETRY_NOISE)) +graph.add(gtsam.BetweenFactorPose2( + 3, 4, gtsam.Pose2(2, 0, math.pi / 2), ODOMETRY_NOISE)) +graph.add(gtsam.BetweenFactorPose2( + 4, 5, gtsam.Pose2(2, 0, math.pi / 2), ODOMETRY_NOISE)) + +# 2c. Add the loop closure constraint +# This factor encodes the fact that we have returned to the same pose. In real +# systems, these constraints may be identified in many ways, such as appearance-based +# techniques with camera images. We will use another Between Factor to enforce this constraint: +graph.add(gtsam.BetweenFactorPose2( + 5, 2, gtsam.Pose2(2, 0, math.pi / 2), ODOMETRY_NOISE)) +print("\nFactor Graph:\n{}".format(graph)) # print + +# 3. Create the data structure to hold the initial_estimate estimate to the +# solution. For illustrative purposes, these have been deliberately set to incorrect values +initial_estimate = gtsam.Values() +initial_estimate.insert(1, gtsam.Pose2(0.5, 0.0, 0.2)) +initial_estimate.insert(2, gtsam.Pose2(2.3, 0.1, -0.2)) +initial_estimate.insert(3, gtsam.Pose2(4.1, 0.1, math.pi / 2)) +initial_estimate.insert(4, gtsam.Pose2(4.0, 2.0, math.pi)) +initial_estimate.insert(5, gtsam.Pose2(2.1, 2.1, -math.pi / 2)) +print("\nInitial Estimate:\n{}".format(initial_estimate)) # print + +# 4. Optimize the initial values using a Gauss-Newton nonlinear optimizer +# The optimizer accepts an optional set of configuration parameters, +# controlling things like convergence criteria, the type of linear +# system solver to use, and the amount of information displayed during +# optimization. We will set a few parameters as a demonstration. +parameters = gtsam.GaussNewtonParams() + +# Stop iterating once the change in error between steps is less than this value +parameters.setRelativeErrorTol(1e-5) +# Do not perform more than N iteration steps +parameters.setMaxIterations(100) +# Create the optimizer ... +optimizer = gtsam.GaussNewtonOptimizer(graph, initial_estimate, parameters) +# ... and optimize +result = optimizer.optimize() +print("Final Result:\n{}".format(result)) + +# 5. Calculate and print marginal covariances for all variables +marginals = gtsam.Marginals(graph, result) +for i in range(1, 6): + print("X{} covariance:\n{}\n".format(i, marginals.marginalCovariance(i))) + +fig = plt.figure(0) +for i in range(1, 6): + gtsam_plot.plot_pose2(0, result.atPose2(i), 0.5, marginals.marginalCovariance(i)) + +plt.axis('equal') +plt.show() diff --git a/python/gtsam_py/python/examples/Pose2SLAMExample_g2o.py b/python/gtsam_py/python/examples/Pose2SLAMExample_g2o.py new file mode 100644 index 000000000..09114370d --- /dev/null +++ b/python/gtsam_py/python/examples/Pose2SLAMExample_g2o.py @@ -0,0 +1,88 @@ +""" +GTSAM Copyright 2010-2018, Georgia Tech Research Corporation, +Atlanta, Georgia 30332-0415 +All Rights Reserved +Authors: Frank Dellaert, et al. (see THANKS for the full author list) + +See LICENSE for the license information + +A 2D Pose SLAM example that reads input from g2o, converts it to a factor graph +and does the optimization. Output is written on a file, in g2o format +""" +# pylint: disable=invalid-name, E1101 + +from __future__ import print_function +import argparse +import math +import numpy as np +import matplotlib.pyplot as plt + +import gtsam +from gtsam.utils import plot + + +def vector3(x, y, z): + """Create 3d double numpy array.""" + return np.array([x, y, z], dtype=np.float) + + +parser = argparse.ArgumentParser( + description="A 2D Pose SLAM example that reads input from g2o, " + "converts it to a factor graph and does the optimization. " + "Output is written on a file, in g2o format") +parser.add_argument('-i', '--input', help='input file g2o format') +parser.add_argument('-o', '--output', + help="the path to the output file with optimized graph") +parser.add_argument('-m', '--maxiter', type=int, + help="maximum number of iterations for optimizer") +parser.add_argument('-k', '--kernel', choices=['none', 'huber', 'tukey'], + default="none", help="Type of kernel used") +parser.add_argument("-p", "--plot", action="store_true", + help="Flag to plot results") +args = parser.parse_args() + +g2oFile = gtsam.findExampleDataFile("noisyToyGraph.txt") if args.input is None\ + else args.input + +maxIterations = 100 if args.maxiter is None else args.maxiter + +is3D = False + +graph, initial = gtsam.readG2o(g2oFile, is3D) + +assert args.kernel == "none", "Supplied kernel type is not yet implemented" + +# Add prior on the pose having index (key) = 0 +priorModel = gtsam.noiseModel_Diagonal.Variances(vector3(1e-6, 1e-6, 1e-8)) +graph.add(gtsam.PriorFactorPose2(0, gtsam.Pose2(), priorModel)) + +params = gtsam.GaussNewtonParams() +params.setVerbosity("Termination") +params.setMaxIterations(maxIterations) +# parameters.setRelativeErrorTol(1e-5) +# Create the optimizer ... +optimizer = gtsam.GaussNewtonOptimizer(graph, initial, params) +# ... and optimize +result = optimizer.optimize() + +print("Optimization complete") +print("initial error = ", graph.error(initial)) +print("final error = ", graph.error(result)) + + +if args.output is None: + print("\nFactor Graph:\n{}".format(graph)) + print("\nInitial Estimate:\n{}".format(initial)) + print("Final Result:\n{}".format(result)) +else: + outputFile = args.output + print("Writing results to file: ", outputFile) + graphNoKernel, _ = gtsam.readG2o(g2oFile, is3D) + gtsam.writeG2o(graphNoKernel, result, outputFile) + print ("Done!") + +if args.plot: + resultPoses = gtsam.utilities_extractPose2(result) + for i in range(resultPoses.shape[0]): + plot.plot_pose2(1, gtsam.Pose2(resultPoses[i, :])) + plt.show() diff --git a/python/gtsam_py/python/examples/Pose3SLAMExample_g2o.py b/python/gtsam_py/python/examples/Pose3SLAMExample_g2o.py new file mode 100644 index 000000000..3c1a54f7b --- /dev/null +++ b/python/gtsam_py/python/examples/Pose3SLAMExample_g2o.py @@ -0,0 +1,71 @@ +""" + * @file Pose3SLAMExample_initializePose3.cpp + * @brief A 3D Pose SLAM example that reads input from g2o, and initializes the + * Pose3 using InitializePose3 + * @date Jan 17, 2019 + * @author Vikrant Shah based on CPP example by Luca Carlone +""" +# pylint: disable=invalid-name, E1101 + +from __future__ import print_function +import argparse +import numpy as np +import matplotlib.pyplot as plt +from mpl_toolkits.mplot3d import Axes3D + +import gtsam +from gtsam.utils import plot + + +def vector6(x, y, z, a, b, c): + """Create 6d double numpy array.""" + return np.array([x, y, z, a, b, c], dtype=np.float) + + +parser = argparse.ArgumentParser( + description="A 3D Pose SLAM example that reads input from g2o, and " + "initializes Pose3") +parser.add_argument('-i', '--input', help='input file g2o format') +parser.add_argument('-o', '--output', + help="the path to the output file with optimized graph") +parser.add_argument("-p", "--plot", action="store_true", + help="Flag to plot results") +args = parser.parse_args() + +g2oFile = gtsam.findExampleDataFile("pose3example.txt") if args.input is None \ + else args.input + +is3D = True +graph, initial = gtsam.readG2o(g2oFile, is3D) + +# Add Prior on the first key +priorModel = gtsam.noiseModel_Diagonal.Variances(vector6(1e-6, 1e-6, 1e-6, + 1e-4, 1e-4, 1e-4)) + +print("Adding prior to g2o file ") +firstKey = initial.keys().at(0) +graph.add(gtsam.PriorFactorPose3(firstKey, gtsam.Pose3(), priorModel)) + +params = gtsam.GaussNewtonParams() +params.setVerbosity("Termination") # this will show info about stopping conds +optimizer = gtsam.GaussNewtonOptimizer(graph, initial, params) +result = optimizer.optimize() +print("Optimization complete") + +print("initial error = ", graph.error(initial)) +print("final error = ", graph.error(result)) + +if args.output is None: + print("Final Result:\n{}".format(result)) +else: + outputFile = args.output + print("Writing results to file: ", outputFile) + graphNoKernel, _ = gtsam.readG2o(g2oFile, is3D) + gtsam.writeG2o(graphNoKernel, result, outputFile) + print ("Done!") + +if args.plot: + resultPoses = gtsam.utilities_allPose3s(result) + for i in range(resultPoses.size()): + plot.plot_pose3(1, resultPoses.atPose3(i)) + plt.show() diff --git a/python/gtsam_py/python/examples/Pose3SLAMExample_initializePose3Chordal.py b/python/gtsam_py/python/examples/Pose3SLAMExample_initializePose3Chordal.py new file mode 100644 index 000000000..02c696905 --- /dev/null +++ b/python/gtsam_py/python/examples/Pose3SLAMExample_initializePose3Chordal.py @@ -0,0 +1,35 @@ +""" +GTSAM Copyright 2010-2018, Georgia Tech Research Corporation, +Atlanta, Georgia 30332-0415 +All Rights Reserved +Authors: Frank Dellaert, et al. (see THANKS for the full author list) + +See LICENSE for the license information + +Initialize PoseSLAM with Chordal init +Author: Luca Carlone, Frank Dellaert (python port) +""" +# pylint: disable=invalid-name, E1101 + +from __future__ import print_function + +import numpy as np + +import gtsam + +# Read graph from file +g2oFile = gtsam.findExampleDataFile("pose3example.txt") + +is3D = True +graph, initial = gtsam.readG2o(g2oFile, is3D) + +# Add prior on the first key. TODO: assumes first key ios z +priorModel = gtsam.noiseModel_Diagonal.Variances( + np.array([1e-6, 1e-6, 1e-6, 1e-4, 1e-4, 1e-4])) +firstKey = initial.keys().at(0) +graph.add(gtsam.PriorFactorPose3(0, gtsam.Pose3(), priorModel)) + +# Initializing Pose3 - chordal relaxation" +initialization = gtsam.InitializePose3.initialize(graph) + +print(initialization) diff --git a/python/gtsam_py/python/examples/PreintegrationExample.py b/python/gtsam_py/python/examples/PreintegrationExample.py new file mode 100644 index 000000000..76520b355 --- /dev/null +++ b/python/gtsam_py/python/examples/PreintegrationExample.py @@ -0,0 +1,140 @@ +""" +GTSAM Copyright 2010-2019, Georgia Tech Research Corporation, +Atlanta, Georgia 30332-0415 +All Rights Reserved + +See LICENSE for the license information + +A script validating the Preintegration of IMU measurements +""" + +import math + +import matplotlib.pyplot as plt +import numpy as np +from mpl_toolkits.mplot3d import Axes3D + +import gtsam +from gtsam.utils.plot import plot_pose3 + +IMU_FIG = 1 +POSES_FIG = 2 + + +class PreintegrationExample(object): + + @staticmethod + def defaultParams(g): + """Create default parameters with Z *up* and realistic noise parameters""" + params = gtsam.PreintegrationParams.MakeSharedU(g) + kGyroSigma = math.radians(0.5) / 60 # 0.5 degree ARW + kAccelSigma = 0.1 / 60 # 10 cm VRW + params.setGyroscopeCovariance( + kGyroSigma ** 2 * np.identity(3, np.float)) + params.setAccelerometerCovariance( + kAccelSigma ** 2 * np.identity(3, np.float)) + params.setIntegrationCovariance( + 0.0000001 ** 2 * np.identity(3, np.float)) + return params + + def __init__(self, twist=None, bias=None, dt=1e-2): + """Initialize with given twist, a pair(angularVelocityVector, velocityVector).""" + + # setup interactive plotting + plt.ion() + + # Setup loop as default scenario + if twist is not None: + (W, V) = twist + else: + # default = loop with forward velocity 2m/s, while pitching up + # with angular velocity 30 degree/sec (negative in FLU) + W = np.array([0, -math.radians(30), 0]) + V = np.array([2, 0, 0]) + + self.scenario = gtsam.ConstantTwistScenario(W, V) + self.dt = dt + + self.maxDim = 5 + self.labels = list('xyz') + self.colors = list('rgb') + + # Create runner + self.g = 10 # simple gravity constant + self.params = self.defaultParams(self.g) + + if bias is not None: + self.actualBias = bias + else: + accBias = np.array([0, 0.1, 0]) + gyroBias = np.array([0, 0, 0]) + self.actualBias = gtsam.imuBias_ConstantBias(accBias, gyroBias) + + self.runner = gtsam.ScenarioRunner( + self.scenario, self.params, self.dt, self.actualBias) + + def plotImu(self, t, measuredOmega, measuredAcc): + plt.figure(IMU_FIG) + + # plot angular velocity + omega_b = self.scenario.omega_b(t) + for i, (label, color) in enumerate(zip(self.labels, self.colors)): + plt.subplot(4, 3, i + 1) + plt.scatter(t, omega_b[i], color='k', marker='.') + plt.scatter(t, measuredOmega[i], color=color, marker='.') + plt.xlabel('angular velocity ' + label) + + # plot acceleration in nav + acceleration_n = self.scenario.acceleration_n(t) + for i, (label, color) in enumerate(zip(self.labels, self.colors)): + plt.subplot(4, 3, i + 4) + plt.scatter(t, acceleration_n[i], color=color, marker='.') + plt.xlabel('acceleration in nav ' + label) + + # plot acceleration in body + acceleration_b = self.scenario.acceleration_b(t) + for i, (label, color) in enumerate(zip(self.labels, self.colors)): + plt.subplot(4, 3, i + 7) + plt.scatter(t, acceleration_b[i], color=color, marker='.') + plt.xlabel('acceleration in body ' + label) + + # plot actual specific force, as well as corrupted + actual = self.runner.actualSpecificForce(t) + for i, (label, color) in enumerate(zip(self.labels, self.colors)): + plt.subplot(4, 3, i + 10) + plt.scatter(t, actual[i], color='k', marker='.') + plt.scatter(t, measuredAcc[i], color=color, marker='.') + plt.xlabel('specific force ' + label) + + def plotGroundTruthPose(self, t): + # plot ground truth pose, as well as prediction from integrated IMU measurements + actualPose = self.scenario.pose(t) + plot_pose3(POSES_FIG, actualPose, 0.3) + t = actualPose.translation() + self.maxDim = max([abs(t.x()), abs(t.y()), abs(t.z()), self.maxDim]) + ax = plt.gca() + ax.set_xlim3d(-self.maxDim, self.maxDim) + ax.set_ylim3d(-self.maxDim, self.maxDim) + ax.set_zlim3d(-self.maxDim, self.maxDim) + + plt.pause(0.01) + + def run(self): + # simulate the loop + T = 12 + for i, t in enumerate(np.arange(0, T, self.dt)): + measuredOmega = self.runner.measuredAngularVelocity(t) + measuredAcc = self.runner.measuredSpecificForce(t) + if i % 25 == 0: + self.plotImu(t, measuredOmega, measuredAcc) + self.plotGroundTruthPose(t) + pim = self.runner.integrate(t, self.actualBias, True) + predictedNavState = self.runner.predict(pim, self.actualBias) + plot_pose3(POSES_FIG, predictedNavState.pose(), 0.1) + + plt.ioff() + plt.show() + + +if __name__ == '__main__': + PreintegrationExample().run() diff --git a/python/gtsam_py/python/examples/README.md b/python/gtsam_py/python/examples/README.md new file mode 100644 index 000000000..99bce00e2 --- /dev/null +++ b/python/gtsam_py/python/examples/README.md @@ -0,0 +1,57 @@ +These examples are almost identical to the old handwritten python wrapper +examples. However, there are just some slight name changes, for example +`noiseModel.Diagonal` becomes `noiseModel_Diagonal` etc... +Also, instead of `gtsam.Symbol('b', 0)` we can simply say `gtsam.symbol_shorthand_B(0)` or `B(0)` if we use python aliasing. + +# Porting Progress + +| C++ Example Name | Ported | +|-------------------------------------------------------|--------| +| CameraResectioning | | +| CreateSFMExampleData | | +| DiscreteBayesNet_FG | none of the required discrete functionality is exposed through cython | +| easyPoint2KalmanFilter | ExtendedKalmanFilter not exposed through cython | +| elaboratePoint2KalmanFilter | GaussianSequentialSolver not exposed through cython | +| ImuFactorExample2 | X | +| ImuFactorsExample | | +| ISAM2Example_SmartFactor | | +| ISAM2_SmartFactorStereo_IMU | | +| LocalizationExample | impossible? | +| METISOrderingExample | | +| OdometryExample | X | +| PlanarSLAMExample | X | +| Pose2SLAMExample | X | +| Pose2SLAMExampleExpressions | | +| Pose2SLAMExample_g2o | X | +| Pose2SLAMExample_graph | | +| Pose2SLAMExample_graphviz | | +| Pose2SLAMExample_lago | lago not exposed through cython | +| Pose2SLAMStressTest | | +| Pose2SLAMwSPCG | | +| Pose3SLAMExample_changeKeys | | +| Pose3SLAMExampleExpressions_BearingRangeWithTransform | | +| Pose3SLAMExample_g2o | X | +| Pose3SLAMExample_initializePose3Chordal | | +| Pose3SLAMExample_initializePose3Gradient | | +| RangeISAMExample_plaza2 | | +| SelfCalibrationExample | | +| SFMExample_bal_COLAMD_METIS | | +| SFMExample_bal | | +| SFMExample | X | +| SFMExampleExpressions_bal | | +| SFMExampleExpressions | | +| SFMExample_SmartFactor | | +| SFMExample_SmartFactorPCG | | +| SimpleRotation | X | +| SolverComparer | | +| StereoVOExample | | +| StereoVOExample_large | | +| TimeTBB | | +| UGM_chain | discrete functionality not exposed | +| UGM_small | discrete functionality not exposed | +| VisualISAM2Example | X | +| VisualISAMExample | X | + +Extra Examples (with no C++ equivalent) +- PlanarManipulatorExample +- SFMData diff --git a/python/gtsam_py/python/examples/SFMExample.py b/python/gtsam_py/python/examples/SFMExample.py new file mode 100644 index 000000000..e02def2f9 --- /dev/null +++ b/python/gtsam_py/python/examples/SFMExample.py @@ -0,0 +1,121 @@ +""" +GTSAM Copyright 2010, Georgia Tech Research Corporation, +Atlanta, Georgia 30332-0415 +All Rights Reserved +Authors: Frank Dellaert, et al. (see THANKS for the full author list) + +See LICENSE for the license information + +A structure-from-motion problem on a simulated dataset +""" +from __future__ import print_function + +import gtsam +import matplotlib.pyplot as plt +import numpy as np +from gtsam import symbol_shorthand_L as L +from gtsam import symbol_shorthand_X as X +from gtsam.examples import SFMdata +from gtsam.gtsam import (Cal3_S2, DoglegOptimizer, + GenericProjectionFactorCal3_S2, Marginals, + NonlinearFactorGraph, PinholeCameraCal3_S2, Point3, + Pose3, PriorFactorPoint3, PriorFactorPose3, Rot3, + SimpleCamera, Values) +from gtsam.utils import plot + + +def main(): + """ + Camera observations of landmarks (i.e. pixel coordinates) will be stored as Point2 (x, y). + + Each variable in the system (poses and landmarks) must be identified with a unique key. + We can either use simple integer keys (1, 2, 3, ...) or symbols (X1, X2, L1). + Here we will use Symbols + + In GTSAM, measurement functions are represented as 'factors'. Several common factors + have been provided with the library for solving robotics/SLAM/Bundle Adjustment problems. + Here we will use Projection factors to model the camera's landmark observations. + Also, we will initialize the robot at some location using a Prior factor. + + When the factors are created, we will add them to a Factor Graph. As the factors we are using + are nonlinear factors, we will need a Nonlinear Factor Graph. + + Finally, once all of the factors have been added to our factor graph, we will want to + solve/optimize to graph to find the best (Maximum A Posteriori) set of variable values. + GTSAM includes several nonlinear optimizers to perform this step. Here we will use a + trust-region method known as Powell's Degleg + + The nonlinear solvers within GTSAM are iterative solvers, meaning they linearize the + nonlinear functions around an initial linearization point, then solve the linear system + to update the linearization point. This happens repeatedly until the solver converges + to a consistent set of variable values. This requires us to specify an initial guess + for each variable, held in a Values container. + """ + + # Define the camera calibration parameters + K = Cal3_S2(50.0, 50.0, 0.0, 50.0, 50.0) + + # Define the camera observation noise model + measurement_noise = gtsam.noiseModel_Isotropic.Sigma(2, 1.0) # one pixel in u and v + + # Create the set of ground-truth landmarks + points = SFMdata.createPoints() + + # Create the set of ground-truth poses + poses = SFMdata.createPoses(K) + + # Create a factor graph + graph = NonlinearFactorGraph() + + # Add a prior on pose x1. This indirectly specifies where the origin is. + # 0.3 rad std on roll,pitch,yaw and 0.1m on x,y,z + pose_noise = gtsam.noiseModel_Diagonal.Sigmas(np.array([0.3, 0.3, 0.3, 0.1, 0.1, 0.1])) + factor = PriorFactorPose3(X(0), poses[0], pose_noise) + graph.push_back(factor) + + # Simulated measurements from each camera pose, adding them to the factor graph + for i, pose in enumerate(poses): + camera = PinholeCameraCal3_S2(pose, K) + for j, point in enumerate(points): + measurement = camera.project(point) + factor = GenericProjectionFactorCal3_S2( + measurement, measurement_noise, X(i), L(j), K) + graph.push_back(factor) + + # Because the structure-from-motion problem has a scale ambiguity, the problem is still under-constrained + # Here we add a prior on the position of the first landmark. This fixes the scale by indicating the distance + # between the first camera and the first landmark. All other landmark positions are interpreted using this scale. + point_noise = gtsam.noiseModel_Isotropic.Sigma(3, 0.1) + factor = PriorFactorPoint3(L(0), points[0], point_noise) + graph.push_back(factor) + graph.print_('Factor Graph:\n') + + # Create the data structure to hold the initial estimate to the solution + # Intentionally initialize the variables off from the ground truth + initial_estimate = Values() + for i, pose in enumerate(poses): + transformed_pose = pose.retract(0.1*np.random.randn(6,1)) + initial_estimate.insert(X(i), transformed_pose) + for j, point in enumerate(points): + transformed_point = Point3(point.vector() + 0.1*np.random.randn(3)) + initial_estimate.insert(L(j), transformed_point) + initial_estimate.print_('Initial Estimates:\n') + + # Optimize the graph and print results + params = gtsam.DoglegParams() + params.setVerbosity('TERMINATION') + optimizer = DoglegOptimizer(graph, initial_estimate, params) + print('Optimizing:') + result = optimizer.optimize() + result.print_('Final results:\n') + print('initial error = {}'.format(graph.error(initial_estimate))) + print('final error = {}'.format(graph.error(result))) + + marginals = Marginals(graph, result) + plot.plot_3d_points(1, result, marginals=marginals) + plot.plot_trajectory(1, result, marginals=marginals, scale=8) + plot.set_axes_equal(1) + plt.show() + +if __name__ == '__main__': + main() diff --git a/python/gtsam_py/python/examples/SFMdata.py b/python/gtsam_py/python/examples/SFMdata.py new file mode 100644 index 000000000..c586f7e52 --- /dev/null +++ b/python/gtsam_py/python/examples/SFMdata.py @@ -0,0 +1,39 @@ +""" +A structure-from-motion example with landmarks + - The landmarks form a 10 meter cube + - The robot rotates around the landmarks, always facing towards the cube +""" +# pylint: disable=invalid-name, E1101 + +import numpy as np + +import gtsam + + +def createPoints(): + # Create the set of ground-truth landmarks + points = [gtsam.Point3(10.0, 10.0, 10.0), + gtsam.Point3(-10.0, 10.0, 10.0), + gtsam.Point3(-10.0, -10.0, 10.0), + gtsam.Point3(10.0, -10.0, 10.0), + gtsam.Point3(10.0, 10.0, -10.0), + gtsam.Point3(-10.0, 10.0, -10.0), + gtsam.Point3(-10.0, -10.0, -10.0), + gtsam.Point3(10.0, -10.0, -10.0)] + return points + + +def createPoses(K): + # Create the set of ground-truth poses + radius = 40.0 + height = 10.0 + angles = np.linspace(0, 2*np.pi, 8, endpoint=False) + up = gtsam.Point3(0, 0, 1) + target = gtsam.Point3(0, 0, 0) + poses = [] + for theta in angles: + position = gtsam.Point3(radius*np.cos(theta), + radius*np.sin(theta), height) + camera = gtsam.PinholeCameraCal3_S2.Lookat(position, target, up, K) + poses.append(camera.pose()) + return poses diff --git a/python/gtsam_py/python/examples/SimpleRotation.py b/python/gtsam_py/python/examples/SimpleRotation.py new file mode 100644 index 000000000..4e82d3778 --- /dev/null +++ b/python/gtsam_py/python/examples/SimpleRotation.py @@ -0,0 +1,85 @@ +""" +GTSAM Copyright 2010, Georgia Tech Research Corporation, +Atlanta, Georgia 30332-0415 +All Rights Reserved +Authors: Frank Dellaert, et al. (see THANKS for the full author list) + +See LICENSE for the license information + +This example will perform a relatively trivial optimization on +a single variable with a single factor. +""" + +import gtsam +import numpy as np +from gtsam import symbol_shorthand_X as X + + +def main(): + """ + Step 1: Create a factor to express a unary constraint + + The "prior" in this case is the measurement from a sensor, + with a model of the noise on the measurement. + + The "Key" created here is a label used to associate parts of the + state (stored in "RotValues") with particular factors. They require + an index to allow for lookup, and should be unique. + + In general, creating a factor requires: + - A key or set of keys labeling the variables that are acted upon + - A measurement value + - A measurement model with the correct dimensionality for the factor + """ + prior = gtsam.Rot2.fromAngle(np.deg2rad(30)) + prior.print_('goal angle') + model = gtsam.noiseModel_Isotropic.Sigma(dim=1, sigma=np.deg2rad(1)) + key = X(1) + factor = gtsam.PriorFactorRot2(key, prior, model) + + """ + Step 2: Create a graph container and add the factor to it + + Before optimizing, all factors need to be added to a Graph container, + which provides the necessary top-level functionality for defining a + system of constraints. + + In this case, there is only one factor, but in a practical scenario, + many more factors would be added. + """ + graph = gtsam.NonlinearFactorGraph() + graph.push_back(factor) + graph.print_('full graph') + + """ + Step 3: Create an initial estimate + + An initial estimate of the solution for the system is necessary to + start optimization. This system state is the "Values" instance, + which is similar in structure to a dictionary, in that it maps + keys (the label created in step 1) to specific values. + + The initial estimate provided to optimization will be used as + a linearization point for optimization, so it is important that + all of the variables in the graph have a corresponding value in + this structure. + """ + initial = gtsam.Values() + initial.insert(key, gtsam.Rot2.fromAngle(np.deg2rad(20))) + initial.print_('initial estimate') + + """ + Step 4: Optimize + + After formulating the problem with a graph of constraints + and an initial estimate, executing optimization is as simple + as calling a general optimization function with the graph and + initial estimate. This will yield a new RotValues structure + with the final state of the optimization. + """ + result = gtsam.LevenbergMarquardtOptimizer(graph, initial).optimize() + result.print_('final result') + + +if __name__ == '__main__': + main() diff --git a/python/gtsam_py/python/examples/VisualISAM2Example.py b/python/gtsam_py/python/examples/VisualISAM2Example.py new file mode 100644 index 000000000..49e6ca95c --- /dev/null +++ b/python/gtsam_py/python/examples/VisualISAM2Example.py @@ -0,0 +1,154 @@ +""" +GTSAM Copyright 2010-2018, Georgia Tech Research Corporation, +Atlanta, Georgia 30332-0415 +All Rights Reserved +Authors: Frank Dellaert, et al. (see THANKS for the full author list) + +See LICENSE for the license information + +An example of running visual SLAM using iSAM2. +Author: Duy-Nguyen Ta (C++), Frank Dellaert (Python) +""" +# pylint: disable=invalid-name, E1101 + +from __future__ import print_function + +import gtsam +import gtsam.utils.plot as gtsam_plot +import matplotlib.pyplot as plt +import numpy as np +from gtsam import symbol_shorthand_L as L +from gtsam import symbol_shorthand_X as X +from gtsam.examples import SFMdata +from mpl_toolkits.mplot3d import Axes3D # pylint: disable=W0611 + + +def visual_ISAM2_plot(result): + """ + VisualISAMPlot plots current state of ISAM2 object + Author: Ellon Paiva + Based on MATLAB version by: Duy Nguyen Ta and Frank Dellaert + """ + + # Declare an id for the figure + fignum = 0 + + fig = plt.figure(fignum) + axes = fig.gca(projection='3d') + plt.cla() + + # Plot points + # Can't use data because current frame might not see all points + # marginals = Marginals(isam.getFactorsUnsafe(), isam.calculateEstimate()) + # gtsam.plot_3d_points(result, [], marginals) + gtsam_plot.plot_3d_points(fignum, result, 'rx') + + # Plot cameras + i = 0 + while result.exists(X(i)): + pose_i = result.atPose3(X(i)) + gtsam_plot.plot_pose3(fignum, pose_i, 10) + i += 1 + + # draw + axes.set_xlim3d(-40, 40) + axes.set_ylim3d(-40, 40) + axes.set_zlim3d(-40, 40) + plt.pause(1) + + +def visual_ISAM2_example(): + plt.ion() + + # Define the camera calibration parameters + K = gtsam.Cal3_S2(50.0, 50.0, 0.0, 50.0, 50.0) + + # Define the camera observation noise model + measurement_noise = gtsam.noiseModel_Isotropic.Sigma( + 2, 1.0) # one pixel in u and v + + # Create the set of ground-truth landmarks + points = SFMdata.createPoints() + + # Create the set of ground-truth poses + poses = SFMdata.createPoses(K) + + # Create an iSAM2 object. Unlike iSAM1, which performs periodic batch steps + # to maintain proper linearization and efficient variable ordering, iSAM2 + # performs partial relinearization/reordering at each step. A parameter + # structure is available that allows the user to set various properties, such + # as the relinearization threshold and type of linear solver. For this + # example, we we set the relinearization threshold small so the iSAM2 result + # will approach the batch result. + parameters = gtsam.ISAM2Params() + parameters.setRelinearizeThreshold(0.01) + parameters.setRelinearizeSkip(1) + isam = gtsam.ISAM2(parameters) + + # Create a Factor Graph and Values to hold the new data + graph = gtsam.NonlinearFactorGraph() + initial_estimate = gtsam.Values() + + # Loop over the different poses, adding the observations to iSAM incrementally + for i, pose in enumerate(poses): + + # Add factors for each landmark observation + for j, point in enumerate(points): + camera = gtsam.PinholeCameraCal3_S2(pose, K) + measurement = camera.project(point) + graph.push_back(gtsam.GenericProjectionFactorCal3_S2( + measurement, measurement_noise, X(i), L(j), K)) + + # Add an initial guess for the current pose + # Intentionally initialize the variables off from the ground truth + initial_estimate.insert(X(i), pose.compose(gtsam.Pose3( + gtsam.Rot3.Rodrigues(-0.1, 0.2, 0.25), gtsam.Point3(0.05, -0.10, 0.20)))) + + # If this is the first iteration, add a prior on the first pose to set the + # coordinate frame and a prior on the first landmark to set the scale. + # Also, as iSAM solves incrementally, we must wait until each is observed + # at least twice before adding it to iSAM. + if i == 0: + # Add a prior on pose x0 + pose_noise = gtsam.noiseModel_Diagonal.Sigmas(np.array( + [0.1, 0.1, 0.1, 0.3, 0.3, 0.3])) # 30cm std on x,y,z 0.1 rad on roll,pitch,yaw + graph.push_back(gtsam.PriorFactorPose3(X(0), poses[0], pose_noise)) + + # Add a prior on landmark l0 + point_noise = gtsam.noiseModel_Isotropic.Sigma(3, 0.1) + graph.push_back(gtsam.PriorFactorPoint3( + L(0), points[0], point_noise)) # add directly to graph + + # Add initial guesses to all observed landmarks + # Intentionally initialize the variables off from the ground truth + for j, point in enumerate(points): + initial_estimate.insert(L(j), gtsam.Point3( + point.x()-0.25, point.y()+0.20, point.z()+0.15)) + else: + # Update iSAM with the new factors + isam.update(graph, initial_estimate) + # Each call to iSAM2 update(*) performs one iteration of the iterative nonlinear solver. + # If accuracy is desired at the expense of time, update(*) can be called additional + # times to perform multiple optimizer iterations every step. + isam.update() + current_estimate = isam.calculateEstimate() + print("****************************************************") + print("Frame", i, ":") + for j in range(i + 1): + print(X(j), ":", current_estimate.atPose3(X(j))) + + for j in range(len(points)): + print(L(j), ":", current_estimate.atPoint3(L(j))) + + visual_ISAM2_plot(current_estimate) + + # Clear the factor graph and values for the next iteration + graph.resize(0) + initial_estimate.clear() + + plt.ioff() + plt.show() + + +if __name__ == '__main__': + visual_ISAM2_example() diff --git a/python/gtsam_py/python/examples/VisualISAMExample.py b/python/gtsam_py/python/examples/VisualISAMExample.py new file mode 100644 index 000000000..5cc37867b --- /dev/null +++ b/python/gtsam_py/python/examples/VisualISAMExample.py @@ -0,0 +1,103 @@ +""" +GTSAM Copyright 2010, Georgia Tech Research Corporation, +Atlanta, Georgia 30332-0415 +All Rights Reserved +Authors: Frank Dellaert, et al. (see THANKS for the full author list) + +See LICENSE for the license information + +A visualSLAM example for the structure-from-motion problem on a simulated dataset +This version uses iSAM to solve the problem incrementally +""" + +from __future__ import print_function + +import numpy as np +import gtsam +from gtsam.examples import SFMdata +from gtsam.gtsam import (Cal3_S2, GenericProjectionFactorCal3_S2, + NonlinearFactorGraph, NonlinearISAM, Point3, Pose3, + PriorFactorPoint3, PriorFactorPose3, Rot3, + PinholeCameraCal3_S2, Values) +from gtsam import symbol_shorthand_L as L +from gtsam import symbol_shorthand_X as X + + +def main(): + """ + A structure-from-motion example with landmarks + - The landmarks form a 10 meter cube + - The robot rotates around the landmarks, always facing towards the cube + """ + + # Define the camera calibration parameters + K = Cal3_S2(50.0, 50.0, 0.0, 50.0, 50.0) + + # Define the camera observation noise model + camera_noise = gtsam.noiseModel_Isotropic.Sigma(2, 1.0) # one pixel in u and v + + # Create the set of ground-truth landmarks + points = SFMdata.createPoints() + # Create the set of ground-truth poses + poses = SFMdata.createPoses(K) + + # Create a NonlinearISAM object which will relinearize and reorder the variables + # every "reorderInterval" updates + isam = NonlinearISAM(reorderInterval=3) + + # Create a Factor Graph and Values to hold the new data + graph = NonlinearFactorGraph() + initial_estimate = Values() + + # Loop over the different poses, adding the observations to iSAM incrementally + for i, pose in enumerate(poses): + camera = PinholeCameraCal3_S2(pose, K) + # Add factors for each landmark observation + for j, point in enumerate(points): + measurement = camera.project(point) + factor = GenericProjectionFactorCal3_S2(measurement, camera_noise, X(i), L(j), K) + graph.push_back(factor) + + # Intentionally initialize the variables off from the ground truth + noise = Pose3(r=Rot3.Rodrigues(-0.1, 0.2, 0.25), t=Point3(0.05, -0.10, 0.20)) + initial_xi = pose.compose(noise) + + # Add an initial guess for the current pose + initial_estimate.insert(X(i), initial_xi) + + # If this is the first iteration, add a prior on the first pose to set the coordinate frame + # and a prior on the first landmark to set the scale + # Also, as iSAM solves incrementally, we must wait until each is observed at least twice before + # adding it to iSAM. + if i == 0: + # Add a prior on pose x0, with 0.3 rad std on roll,pitch,yaw and 0.1m x,y,z + pose_noise = gtsam.noiseModel_Diagonal.Sigmas(np.array([0.3, 0.3, 0.3, 0.1, 0.1, 0.1])) + factor = PriorFactorPose3(X(0), poses[0], pose_noise) + graph.push_back(factor) + + # Add a prior on landmark l0 + point_noise = gtsam.noiseModel_Isotropic.Sigma(3, 0.1) + factor = PriorFactorPoint3(L(0), points[0], point_noise) + graph.push_back(factor) + + # Add initial guesses to all observed landmarks + noise = np.array([-0.25, 0.20, 0.15]) + for j, point in enumerate(points): + # Intentionally initialize the variables off from the ground truth + initial_lj = points[j].vector() + noise + initial_estimate.insert(L(j), Point3(initial_lj)) + else: + # Update iSAM with the new factors + isam.update(graph, initial_estimate) + current_estimate = isam.estimate() + print('*' * 50) + print('Frame {}:'.format(i)) + current_estimate.print_('Current estimate: ') + + # Clear the factor graph and values for the next iteration + graph.resize(0) + initial_estimate.clear() + + +if __name__ == '__main__': + main() diff --git a/python/gtsam_py/python/examples/__init__.py b/python/gtsam_py/python/examples/__init__.py new file mode 100644 index 000000000..e69de29bb diff --git a/python/gtsam_py/python/tests/__init__.py b/python/gtsam_py/python/tests/__init__.py new file mode 100644 index 000000000..e69de29bb diff --git a/python/gtsam_py/python/tests/testScenarioRunner.py b/python/gtsam_py/python/tests/testScenarioRunner.py new file mode 100644 index 000000000..97a97b0ec --- /dev/null +++ b/python/gtsam_py/python/tests/testScenarioRunner.py @@ -0,0 +1,47 @@ +""" +GTSAM Copyright 2010-2019, Georgia Tech Research Corporation, +Atlanta, Georgia 30332-0415 +All Rights Reserved + +See LICENSE for the license information + +ScenarioRunner unit tests. +Author: Frank Dellaert & Duy Nguyen Ta (Python) +""" +import math +import unittest + +import numpy as np + +import gtsam +from gtsam.utils.test_case import GtsamTestCase + + +class TestScenarioRunner(GtsamTestCase): + def setUp(self): + self.g = 10 # simple gravity constant + + def test_loop_runner(self): + # Forward velocity 2m/s + # Pitch up with angular velocity 6 degree/sec (negative in FLU) + v = 2 + w = math.radians(6) + W = np.array([0, -w, 0]) + V = np.array([v, 0, 0]) + scenario = gtsam.ConstantTwistScenario(W, V) + + dt = 0.1 + params = gtsam.PreintegrationParams.MakeSharedU(self.g) + bias = gtsam.imuBias_ConstantBias() + runner = gtsam.ScenarioRunner( + scenario, params, dt, bias) + + # Test specific force at time 0: a is pointing up + t = 0.0 + a = w * v + np.testing.assert_almost_equal( + np.array([0, 0, a + self.g]), runner.actualSpecificForce(t)) + + +if __name__ == '__main__': + unittest.main() diff --git a/python/gtsam_py/python/tests/test_Cal3Unified.py b/python/gtsam_py/python/tests/test_Cal3Unified.py new file mode 100644 index 000000000..fbf5f3565 --- /dev/null +++ b/python/gtsam_py/python/tests/test_Cal3Unified.py @@ -0,0 +1,38 @@ +""" +GTSAM Copyright 2010-2019, Georgia Tech Research Corporation, +Atlanta, Georgia 30332-0415 +All Rights Reserved + +See LICENSE for the license information + +Cal3Unified unit tests. +Author: Frank Dellaert & Duy Nguyen Ta (Python) +""" +import unittest + +import numpy as np + +import gtsam +from gtsam.utils.test_case import GtsamTestCase + + +class TestCal3Unified(GtsamTestCase): + + def test_Cal3Unified(self): + K = gtsam.Cal3Unified() + self.assertEqual(K.fx(), 1.) + self.assertEqual(K.fx(), 1.) + + def test_retract(self): + expected = gtsam.Cal3Unified(100 + 2, 105 + 3, 0.0 + 4, 320 + 5, 240 + 6, + 1e-3 + 7, 2.0*1e-3 + 8, 3.0*1e-3 + 9, 4.0*1e-3 + 10, 0.1 + 1) + K = gtsam.Cal3Unified(100, 105, 0.0, 320, 240, + 1e-3, 2.0*1e-3, 3.0*1e-3, 4.0*1e-3, 0.1) + d = np.array([2, 3, 4, 5, 6, 7, 8, 9, 10, 1], order='F') + actual = K.retract(d) + self.gtsamAssertEquals(actual, expected) + np.testing.assert_allclose(d, K.localCoordinates(actual)) + + +if __name__ == "__main__": + unittest.main() diff --git a/python/gtsam_py/python/tests/test_FrobeniusFactor.py b/python/gtsam_py/python/tests/test_FrobeniusFactor.py new file mode 100644 index 000000000..f3f5354bb --- /dev/null +++ b/python/gtsam_py/python/tests/test_FrobeniusFactor.py @@ -0,0 +1,56 @@ +""" +GTSAM Copyright 2010-2019, Georgia Tech Research Corporation, +Atlanta, Georgia 30332-0415 +All Rights Reserved + +See LICENSE for the license information + +FrobeniusFactor unit tests. +Author: Frank Dellaert +""" +# pylint: disable=no-name-in-module, import-error, invalid-name +import unittest + +import numpy as np +from gtsam import (Rot3, SO3, SO4, FrobeniusBetweenFactorSO4, FrobeniusFactorSO4, + FrobeniusWormholeFactor, SOn) + +id = SO4() +v1 = np.array([0, 0, 0, 0.1, 0, 0]) +Q1 = SO4.Expmap(v1) +v2 = np.array([0, 0, 0, 0.01, 0.02, 0.03]) +Q2 = SO4.Expmap(v2) + + +class TestFrobeniusFactorSO4(unittest.TestCase): + """Test FrobeniusFactor factors.""" + + def test_frobenius_factor(self): + """Test creation of a factor that calculates the Frobenius norm.""" + factor = FrobeniusFactorSO4(1, 2) + actual = factor.evaluateError(Q1, Q2) + expected = (Q2.matrix()-Q1.matrix()).transpose().reshape((16,)) + np.testing.assert_array_equal(actual, expected) + + def test_frobenius_between_factor(self): + """Test creation of a Frobenius BetweenFactor.""" + factor = FrobeniusBetweenFactorSO4(1, 2, Q1.between(Q2)) + actual = factor.evaluateError(Q1, Q2) + expected = np.zeros((16,)) + np.testing.assert_array_almost_equal(actual, expected) + + def test_frobenius_wormhole_factor(self): + """Test creation of a factor that calculates Shonan error.""" + R1 = SO3.Expmap(v1[3:]) + R2 = SO3.Expmap(v2[3:]) + factor = FrobeniusWormholeFactor(1, 2, Rot3(R1.between(R2).matrix()), p=4) + I4 = SOn(4) + Q1 = I4.retract(v1) + Q2 = I4.retract(v2) + actual = factor.evaluateError(Q1, Q2) + expected = np.zeros((12,)) + np.testing.assert_array_almost_equal(actual, expected, decimal=4) + + +if __name__ == "__main__": + unittest.main() diff --git a/python/gtsam_py/python/tests/test_GaussianFactorGraph.py b/python/gtsam_py/python/tests/test_GaussianFactorGraph.py new file mode 100644 index 000000000..983825d8b --- /dev/null +++ b/python/gtsam_py/python/tests/test_GaussianFactorGraph.py @@ -0,0 +1,92 @@ +""" +GTSAM Copyright 2010-2019, Georgia Tech Research Corporation, +Atlanta, Georgia 30332-0415 +All Rights Reserved + +See LICENSE for the license information + +Unit tests for Linear Factor Graphs. +Author: Frank Dellaert & Gerry Chen +""" +# pylint: disable=invalid-name, no-name-in-module, no-member + +from __future__ import print_function + +import unittest + +import gtsam +import numpy as np +from gtsam import symbol_shorthand_X as X +from gtsam.utils.test_case import GtsamTestCase + + +def create_graph(): + """Create a basic linear factor graph for testing""" + graph = gtsam.GaussianFactorGraph() + + x0 = X(0) + x1 = X(1) + x2 = X(2) + + BETWEEN_NOISE = gtsam.noiseModel_Diagonal.Sigmas(np.ones(1)) + PRIOR_NOISE = gtsam.noiseModel_Diagonal.Sigmas(np.ones(1)) + + graph.add(x1, np.eye(1), x0, -np.eye(1), np.ones(1), BETWEEN_NOISE) + graph.add(x2, np.eye(1), x1, -np.eye(1), 2*np.ones(1), BETWEEN_NOISE) + graph.add(x0, np.eye(1), np.zeros(1), PRIOR_NOISE) + + return graph, (x0, x1, x2) + +class TestGaussianFactorGraph(GtsamTestCase): + """Tests for Gaussian Factor Graphs.""" + + def test_fg(self): + """Test solving a linear factor graph""" + graph, X = create_graph() + result = graph.optimize() + + EXPECTEDX = [0, 1, 3] + + # check solutions + self.assertAlmostEqual(EXPECTEDX[0], result.at(X[0]), delta=1e-8) + self.assertAlmostEqual(EXPECTEDX[1], result.at(X[1]), delta=1e-8) + self.assertAlmostEqual(EXPECTEDX[2], result.at(X[2]), delta=1e-8) + + def test_convertNonlinear(self): + """Test converting a linear factor graph to a nonlinear one""" + graph, X = create_graph() + + EXPECTEDM = [1, 2, 3] + + # create nonlinear factor graph for marginalization + nfg = gtsam.LinearContainerFactor.ConvertLinearGraph(graph) + optimizer = gtsam.LevenbergMarquardtOptimizer(nfg, gtsam.Values()) + nlresult = optimizer.optimizeSafely() + + # marginalize + marginals = gtsam.Marginals(nfg, nlresult) + m = [marginals.marginalCovariance(x) for x in X] + + # check linear marginalizations + self.assertAlmostEqual(EXPECTEDM[0], m[0], delta=1e-8) + self.assertAlmostEqual(EXPECTEDM[1], m[1], delta=1e-8) + self.assertAlmostEqual(EXPECTEDM[2], m[2], delta=1e-8) + + def test_linearMarginalization(self): + """Marginalize a linear factor graph""" + graph, X = create_graph() + result = graph.optimize() + + EXPECTEDM = [1, 2, 3] + + # linear factor graph marginalize + marginals = gtsam.Marginals(graph, result) + m = [marginals.marginalCovariance(x) for x in X] + + # check linear marginalizations + self.assertAlmostEqual(EXPECTEDM[0], m[0], delta=1e-8) + self.assertAlmostEqual(EXPECTEDM[1], m[1], delta=1e-8) + self.assertAlmostEqual(EXPECTEDM[2], m[2], delta=1e-8) + +if __name__ == '__main__': + unittest.main() diff --git a/python/gtsam_py/python/tests/test_JacobianFactor.py b/python/gtsam_py/python/tests/test_JacobianFactor.py new file mode 100644 index 000000000..04433492b --- /dev/null +++ b/python/gtsam_py/python/tests/test_JacobianFactor.py @@ -0,0 +1,92 @@ +""" +GTSAM Copyright 2010-2019, Georgia Tech Research Corporation, +Atlanta, Georgia 30332-0415 +All Rights Reserved + +See LICENSE for the license information + +JacobianFactor unit tests. +Author: Frank Dellaert & Duy Nguyen Ta (Python) +""" +import unittest + +import numpy as np + +import gtsam +from gtsam.utils.test_case import GtsamTestCase + + +class TestJacobianFactor(GtsamTestCase): + + def test_eliminate(self): + # Recommended way to specify a matrix (see cython/README) + Ax2 = np.array( + [[-5., 0.], + [+0., -5.], + [10., 0.], + [+0., 10.]], order='F') + + # This is good too + Al1 = np.array( + [[5, 0], + [0, 5], + [0, 0], + [0, 0]], dtype=float, order = 'F') + + # Not recommended for performance reasons, but should still work + # as the wrapper should convert it to the correct type and storage order + Ax1 = np.array( + [[0, 0], # f4 + [0, 0], # f4 + [-10, 0], # f2 + [0, -10]]) # f2 + + x2 = 1 + l1 = 2 + x1 = 3 + + # the RHS + b2 = np.array([-1., 1.5, 2., -1.]) + sigmas = np.array([1., 1., 1., 1.]) + model4 = gtsam.noiseModel_Diagonal.Sigmas(sigmas) + combined = gtsam.JacobianFactor(x2, Ax2, l1, Al1, x1, Ax1, b2, model4) + + # eliminate the first variable (x2) in the combined factor, destructive + # ! + ord = gtsam.Ordering() + ord.push_back(x2) + actualCG, lf = combined.eliminate(ord) + + # create expected Conditional Gaussian + R11 = np.array([[11.1803, 0.00], + [0.00, 11.1803]]) + S12 = np.array([[-2.23607, 0.00], + [+0.00, -2.23607]]) + S13 = np.array([[-8.94427, 0.00], + [+0.00, -8.94427]]) + d = np.array([2.23607, -1.56525]) + expectedCG = gtsam.GaussianConditional( + x2, d, R11, l1, S12, x1, S13, gtsam.noiseModel_Unit.Create(2)) + # check if the result matches + self.gtsamAssertEquals(actualCG, expectedCG, 1e-4) + + # the expected linear factor + Bl1 = np.array([[4.47214, 0.00], + [0.00, 4.47214]]) + + Bx1 = np.array( + # x1 + [[-4.47214, 0.00], + [+0.00, -4.47214]]) + + # the RHS + b1 = np.array([0.0, 0.894427]) + + model2 = gtsam.noiseModel_Diagonal.Sigmas(np.array([1., 1.])) + expectedLF = gtsam.JacobianFactor(l1, Bl1, x1, Bx1, b1, model2) + + # check if the result matches the combined (reduced) factor + self.gtsamAssertEquals(lf, expectedLF, 1e-4) + +if __name__ == "__main__": + unittest.main() diff --git a/python/gtsam_py/python/tests/test_KalmanFilter.py b/python/gtsam_py/python/tests/test_KalmanFilter.py new file mode 100644 index 000000000..94c41df72 --- /dev/null +++ b/python/gtsam_py/python/tests/test_KalmanFilter.py @@ -0,0 +1,83 @@ +""" +GTSAM Copyright 2010-2019, Georgia Tech Research Corporation, +Atlanta, Georgia 30332-0415 +All Rights Reserved + +See LICENSE for the license information + +KalmanFilter unit tests. +Author: Frank Dellaert & Duy Nguyen Ta (Python) +""" +import unittest + +import numpy as np + +import gtsam +from gtsam.utils.test_case import GtsamTestCase + + +class TestKalmanFilter(GtsamTestCase): + + def test_KalmanFilter(self): + F = np.eye(2) + B = np.eye(2) + u = np.array([1.0, 0.0]) + modelQ = gtsam.noiseModel_Diagonal.Sigmas(np.array([0.1, 0.1])) + Q = 0.01 * np.eye(2) + H = np.eye(2) + z1 = np.array([1.0, 0.0]) + z2 = np.array([2.0, 0.0]) + z3 = np.array([3.0, 0.0]) + modelR = gtsam.noiseModel_Diagonal.Sigmas(np.array([0.1, 0.1])) + R = 0.01 * np.eye(2) + + # Create the set of expected output TestValues + expected0 = np.array([0.0, 0.0]) + P00 = 0.01 * np.eye(2) + + expected1 = np.array([1.0, 0.0]) + P01 = P00 + Q + I11 = np.linalg.inv(P01) + np.linalg.inv(R) + + expected2 = np.array([2.0, 0.0]) + P12 = np.linalg.inv(I11) + Q + I22 = np.linalg.inv(P12) + np.linalg.inv(R) + + expected3 = np.array([3.0, 0.0]) + P23 = np.linalg.inv(I22) + Q + I33 = np.linalg.inv(P23) + np.linalg.inv(R) + + # Create an KalmanFilter object + KF = gtsam.KalmanFilter(n=2) + + # Create the Kalman Filter initialization point + x_initial = np.array([0.0, 0.0]) + P_initial = 0.01 * np.eye(2) + + # Create an KF object + state = KF.init(x_initial, P_initial) + self.assertTrue(np.allclose(expected0, state.mean())) + self.assertTrue(np.allclose(P00, state.covariance())) + + # Run iteration 1 + state = KF.predict(state, F, B, u, modelQ) + self.assertTrue(np.allclose(expected1, state.mean())) + self.assertTrue(np.allclose(P01, state.covariance())) + state = KF.update(state, H, z1, modelR) + self.assertTrue(np.allclose(expected1, state.mean())) + self.assertTrue(np.allclose(I11, state.information())) + + # Run iteration 2 + state = KF.predict(state, F, B, u, modelQ) + self.assertTrue(np.allclose(expected2, state.mean())) + state = KF.update(state, H, z2, modelR) + self.assertTrue(np.allclose(expected2, state.mean())) + + # Run iteration 3 + state = KF.predict(state, F, B, u, modelQ) + self.assertTrue(np.allclose(expected3, state.mean())) + state = KF.update(state, H, z3, modelR) + self.assertTrue(np.allclose(expected3, state.mean())) + +if __name__ == "__main__": + unittest.main() diff --git a/python/gtsam_py/python/tests/test_KarcherMeanFactor.py b/python/gtsam_py/python/tests/test_KarcherMeanFactor.py new file mode 100644 index 000000000..6976decc1 --- /dev/null +++ b/python/gtsam_py/python/tests/test_KarcherMeanFactor.py @@ -0,0 +1,80 @@ +""" +GTSAM Copyright 2010-2019, Georgia Tech Research Corporation, +Atlanta, Georgia 30332-0415 +All Rights Reserved + +See LICENSE for the license information + +KarcherMeanFactor unit tests. +Author: Frank Dellaert +""" + +# pylint: disable=invalid-name, no-name-in-module, no-member + +import unittest + +import gtsam +import numpy as np +from gtsam.utils.test_case import GtsamTestCase + +KEY = 0 +MODEL = gtsam.noiseModel_Unit.Create(3) + + +def find_Karcher_mean_Rot3(rotations): + """Find the Karcher mean of given values.""" + # Cost function C(R) = \sum PriorFactor(R_i)::error(R) + # No closed form solution. + graph = gtsam.NonlinearFactorGraph() + for R in rotations: + graph.add(gtsam.PriorFactorRot3(KEY, R, MODEL)) + initial = gtsam.Values() + initial.insert(KEY, gtsam.Rot3()) + result = gtsam.GaussNewtonOptimizer(graph, initial).optimize() + return result.atRot3(KEY) + + +# Rot3 version +R = gtsam.Rot3.Expmap(np.array([0.1, 0, 0])) + + +class TestKarcherMean(GtsamTestCase): + + def test_find(self): + # Check that optimizing for Karcher mean (which minimizes Between distance) + # gets correct result. + rotations = {R, R.inverse()} + expected = gtsam.Rot3() + actual = find_Karcher_mean_Rot3(rotations) + self.gtsamAssertEquals(expected, actual) + + def test_factor(self): + """Check that the InnerConstraint factor leaves the mean unchanged.""" + # Make a graph with two variables, one between, and one InnerConstraint + # The optimal result should satisfy the between, while moving the other + # variable to make the mean the same as before. + # Mean of R and R' is identity. Let's make a BetweenFactor making R21 = + # R*R*R, i.e. geodesic length is 3 rather than 2. + graph = gtsam.NonlinearFactorGraph() + R12 = R.compose(R.compose(R)) + graph.add(gtsam.BetweenFactorRot3(1, 2, R12, MODEL)) + keys = gtsam.KeyVector() + keys.push_back(1) + keys.push_back(2) + graph.add(gtsam.KarcherMeanFactorRot3(keys)) + + initial = gtsam.Values() + initial.insert(1, R.inverse()) + initial.insert(2, R) + expected = find_Karcher_mean_Rot3([R, R.inverse()]) + + result = gtsam.GaussNewtonOptimizer(graph, initial).optimize() + actual = find_Karcher_mean_Rot3( + [result.atRot3(1), result.atRot3(2)]) + self.gtsamAssertEquals(expected, actual) + self.gtsamAssertEquals( + R12, result.atRot3(1).between(result.atRot3(2))) + + +if __name__ == "__main__": + unittest.main() diff --git a/python/gtsam_py/python/tests/test_LocalizationExample.py b/python/gtsam_py/python/tests/test_LocalizationExample.py new file mode 100644 index 000000000..6ce65f087 --- /dev/null +++ b/python/gtsam_py/python/tests/test_LocalizationExample.py @@ -0,0 +1,64 @@ +""" +GTSAM Copyright 2010-2019, Georgia Tech Research Corporation, +Atlanta, Georgia 30332-0415 +All Rights Reserved + +See LICENSE for the license information + +Localization unit tests. +Author: Frank Dellaert & Duy Nguyen Ta (Python) +""" +import unittest + +import numpy as np + +import gtsam +from gtsam.utils.test_case import GtsamTestCase + + +class TestLocalizationExample(GtsamTestCase): + + def test_LocalizationExample(self): + # Create the graph (defined in pose2SLAM.h, derived from + # NonlinearFactorGraph) + graph = gtsam.NonlinearFactorGraph() + + # Add two odometry factors + # create a measurement for both factors (the same in this case) + odometry = gtsam.Pose2(2.0, 0.0, 0.0) + odometryNoise = gtsam.noiseModel_Diagonal.Sigmas( + np.array([0.2, 0.2, 0.1])) # 20cm std on x,y, 0.1 rad on theta + graph.add(gtsam.BetweenFactorPose2(0, 1, odometry, odometryNoise)) + graph.add(gtsam.BetweenFactorPose2(1, 2, odometry, odometryNoise)) + + # Add three "GPS" measurements + # We use Pose2 Priors here with high variance on theta + groundTruth = gtsam.Values() + groundTruth.insert(0, gtsam.Pose2(0.0, 0.0, 0.0)) + groundTruth.insert(1, gtsam.Pose2(2.0, 0.0, 0.0)) + groundTruth.insert(2, gtsam.Pose2(4.0, 0.0, 0.0)) + model = gtsam.noiseModel_Diagonal.Sigmas(np.array([0.1, 0.1, 10.])) + for i in range(3): + graph.add(gtsam.PriorFactorPose2(i, groundTruth.atPose2(i), model)) + + # Initialize to noisy points + initialEstimate = gtsam.Values() + initialEstimate.insert(0, gtsam.Pose2(0.5, 0.0, 0.2)) + initialEstimate.insert(1, gtsam.Pose2(2.3, 0.1, -0.2)) + initialEstimate.insert(2, gtsam.Pose2(4.1, 0.1, 0.1)) + + # Optimize using Levenberg-Marquardt optimization with an ordering from + # colamd + optimizer = gtsam.LevenbergMarquardtOptimizer(graph, initialEstimate) + result = optimizer.optimizeSafely() + + # Plot Covariance Ellipses + marginals = gtsam.Marginals(graph, result) + P = [None] * result.size() + for i in range(0, result.size()): + pose_i = result.atPose2(i) + self.gtsamAssertEquals(pose_i, groundTruth.atPose2(i), 1e-4) + P[i] = marginals.marginalCovariance(i) + +if __name__ == "__main__": + unittest.main() diff --git a/python/gtsam_py/python/tests/test_NonlinearOptimizer.py b/python/gtsam_py/python/tests/test_NonlinearOptimizer.py new file mode 100644 index 000000000..985dc30a2 --- /dev/null +++ b/python/gtsam_py/python/tests/test_NonlinearOptimizer.py @@ -0,0 +1,83 @@ +""" +GTSAM Copyright 2010-2019, Georgia Tech Research Corporation, +Atlanta, Georgia 30332-0415 +All Rights Reserved + +See LICENSE for the license information + +Unit tests for IMU testing scenarios. +Author: Frank Dellaert & Duy Nguyen Ta (Python) +""" +# pylint: disable=invalid-name, no-name-in-module + +from __future__ import print_function + +import unittest + +import gtsam +from gtsam import (DoglegOptimizer, DoglegParams, GaussNewtonOptimizer, + GaussNewtonParams, LevenbergMarquardtOptimizer, + LevenbergMarquardtParams, PCGSolverParameters, + DummyPreconditionerParameters, NonlinearFactorGraph, Ordering, + Point2, PriorFactorPoint2, Values) +from gtsam.utils.test_case import GtsamTestCase + +KEY1 = 1 +KEY2 = 2 + + +class TestScenario(GtsamTestCase): + def test_optimize(self): + """Do trivial test with three optimizer variants.""" + fg = NonlinearFactorGraph() + model = gtsam.noiseModel_Unit.Create(2) + fg.add(PriorFactorPoint2(KEY1, Point2(0, 0), model)) + + # test error at minimum + xstar = Point2(0, 0) + optimal_values = Values() + optimal_values.insert(KEY1, xstar) + self.assertEqual(0.0, fg.error(optimal_values), 0.0) + + # test error at initial = [(1-cos(3))^2 + (sin(3))^2]*50 = + x0 = Point2(3, 3) + initial_values = Values() + initial_values.insert(KEY1, x0) + self.assertEqual(9.0, fg.error(initial_values), 1e-3) + + # optimize parameters + ordering = Ordering() + ordering.push_back(KEY1) + + # Gauss-Newton + gnParams = GaussNewtonParams() + gnParams.setOrdering(ordering) + actual1 = GaussNewtonOptimizer(fg, initial_values, gnParams).optimize() + self.assertAlmostEqual(0, fg.error(actual1)) + + # Levenberg-Marquardt + lmParams = LevenbergMarquardtParams.CeresDefaults() + lmParams.setOrdering(ordering) + actual2 = LevenbergMarquardtOptimizer( + fg, initial_values, lmParams).optimize() + self.assertAlmostEqual(0, fg.error(actual2)) + + # Levenberg-Marquardt + lmParams = LevenbergMarquardtParams.CeresDefaults() + lmParams.setLinearSolverType("ITERATIVE") + cgParams = PCGSolverParameters() + cgParams.setPreconditionerParams(DummyPreconditionerParameters()) + lmParams.setIterativeParams(cgParams) + actual2 = LevenbergMarquardtOptimizer( + fg, initial_values, lmParams).optimize() + self.assertAlmostEqual(0, fg.error(actual2)) + + # Dogleg + dlParams = DoglegParams() + dlParams.setOrdering(ordering) + actual3 = DoglegOptimizer(fg, initial_values, dlParams).optimize() + self.assertAlmostEqual(0, fg.error(actual3)) + + +if __name__ == "__main__": + unittest.main() diff --git a/python/gtsam_py/python/tests/test_OdometryExample.py b/python/gtsam_py/python/tests/test_OdometryExample.py new file mode 100644 index 000000000..c8ea95588 --- /dev/null +++ b/python/gtsam_py/python/tests/test_OdometryExample.py @@ -0,0 +1,59 @@ +""" +GTSAM Copyright 2010-2019, Georgia Tech Research Corporation, +Atlanta, Georgia 30332-0415 +All Rights Reserved + +See LICENSE for the license information + +Odometry unit tests. +Author: Frank Dellaert & Duy Nguyen Ta (Python) +""" +import unittest + +import numpy as np + +import gtsam +from gtsam.utils.test_case import GtsamTestCase + + +class TestOdometryExample(GtsamTestCase): + + def test_OdometryExample(self): + # Create the graph (defined in pose2SLAM.h, derived from + # NonlinearFactorGraph) + graph = gtsam.NonlinearFactorGraph() + + # Add a Gaussian prior on pose x_1 + priorMean = gtsam.Pose2(0.0, 0.0, 0.0) # prior mean is at origin + priorNoise = gtsam.noiseModel_Diagonal.Sigmas( + np.array([0.3, 0.3, 0.1])) # 30cm std on x,y, 0.1 rad on theta + # add directly to graph + graph.add(gtsam.PriorFactorPose2(1, priorMean, priorNoise)) + + # Add two odometry factors + # create a measurement for both factors (the same in this case) + odometry = gtsam.Pose2(2.0, 0.0, 0.0) + odometryNoise = gtsam.noiseModel_Diagonal.Sigmas( + np.array([0.2, 0.2, 0.1])) # 20cm std on x,y, 0.1 rad on theta + graph.add(gtsam.BetweenFactorPose2(1, 2, odometry, odometryNoise)) + graph.add(gtsam.BetweenFactorPose2(2, 3, odometry, odometryNoise)) + + # Initialize to noisy points + initialEstimate = gtsam.Values() + initialEstimate.insert(1, gtsam.Pose2(0.5, 0.0, 0.2)) + initialEstimate.insert(2, gtsam.Pose2(2.3, 0.1, -0.2)) + initialEstimate.insert(3, gtsam.Pose2(4.1, 0.1, 0.1)) + + # Optimize using Levenberg-Marquardt optimization with an ordering from + # colamd + optimizer = gtsam.LevenbergMarquardtOptimizer(graph, initialEstimate) + result = optimizer.optimizeSafely() + marginals = gtsam.Marginals(graph, result) + marginals.marginalCovariance(1) + + # Check first pose equality + pose_1 = result.atPose2(1) + self.gtsamAssertEquals(pose_1, gtsam.Pose2(), 1e-4) + +if __name__ == "__main__": + unittest.main() diff --git a/python/gtsam_py/python/tests/test_PlanarSLAMExample.py b/python/gtsam_py/python/tests/test_PlanarSLAMExample.py new file mode 100644 index 000000000..ae813d35c --- /dev/null +++ b/python/gtsam_py/python/tests/test_PlanarSLAMExample.py @@ -0,0 +1,78 @@ +""" +GTSAM Copyright 2010-2019, Georgia Tech Research Corporation, +Atlanta, Georgia 30332-0415 +All Rights Reserved + +See LICENSE for the license information + +PlanarSLAM unit tests. +Author: Frank Dellaert & Duy Nguyen Ta (Python) +""" +import unittest +from math import pi + +import numpy as np + +import gtsam +from gtsam.utils.test_case import GtsamTestCase + + +class TestPlanarSLAM(GtsamTestCase): + + def test_PlanarSLAM(self): + # Assumptions + # - All values are axis aligned + # - Robot poses are facing along the X axis (horizontal, to the right in images) + # - We have full odometry for measurements + # - The robot is on a grid, moving 2 meters each step + + # Create graph container and add factors to it + graph = gtsam.NonlinearFactorGraph() + + # Add prior + # gaussian for prior + priorMean = gtsam.Pose2(0.0, 0.0, 0.0) # prior at origin + priorNoise = gtsam.noiseModel_Diagonal.Sigmas(np.array([0.3, 0.3, 0.1])) + # add directly to graph + graph.add(gtsam.PriorFactorPose2(1, priorMean, priorNoise)) + + # Add odometry + # general noisemodel for odometry + odometryNoise = gtsam.noiseModel_Diagonal.Sigmas(np.array([0.2, 0.2, 0.1])) + graph.add(gtsam.BetweenFactorPose2( + 1, 2, gtsam.Pose2(2.0, 0.0, 0.0), odometryNoise)) + graph.add(gtsam.BetweenFactorPose2( + 2, 3, gtsam.Pose2(2.0, 0.0, pi / 2), odometryNoise)) + graph.add(gtsam.BetweenFactorPose2( + 3, 4, gtsam.Pose2(2.0, 0.0, pi / 2), odometryNoise)) + graph.add(gtsam.BetweenFactorPose2( + 4, 5, gtsam.Pose2(2.0, 0.0, pi / 2), odometryNoise)) + + # Add pose constraint + model = gtsam.noiseModel_Diagonal.Sigmas(np.array([0.2, 0.2, 0.1])) + graph.add(gtsam.BetweenFactorPose2(5, 2, gtsam.Pose2(2.0, 0.0, pi / 2), model)) + + # Initialize to noisy points + initialEstimate = gtsam.Values() + initialEstimate.insert(1, gtsam.Pose2(0.5, 0.0, 0.2)) + initialEstimate.insert(2, gtsam.Pose2(2.3, 0.1, -0.2)) + initialEstimate.insert(3, gtsam.Pose2(4.1, 0.1, pi / 2)) + initialEstimate.insert(4, gtsam.Pose2(4.0, 2.0, pi)) + initialEstimate.insert(5, gtsam.Pose2(2.1, 2.1, -pi / 2)) + + # Optimize using Levenberg-Marquardt optimization with an ordering from + # colamd + optimizer = gtsam.LevenbergMarquardtOptimizer(graph, initialEstimate) + result = optimizer.optimizeSafely() + + # Plot Covariance Ellipses + marginals = gtsam.Marginals(graph, result) + P = marginals.marginalCovariance(1) + + pose_1 = result.atPose2(1) + self.gtsamAssertEquals(pose_1, gtsam.Pose2(), 1e-4) + + + +if __name__ == "__main__": + unittest.main() diff --git a/python/gtsam_py/python/tests/test_Pose2.py b/python/gtsam_py/python/tests/test_Pose2.py new file mode 100644 index 000000000..9652b594a --- /dev/null +++ b/python/gtsam_py/python/tests/test_Pose2.py @@ -0,0 +1,32 @@ +""" +GTSAM Copyright 2010-2019, Georgia Tech Research Corporation, +Atlanta, Georgia 30332-0415 +All Rights Reserved + +See LICENSE for the license information + +Pose2 unit tests. +Author: Frank Dellaert & Duy Nguyen Ta (Python) +""" +import unittest + +import numpy as np + +import gtsam +from gtsam import Pose2 +from gtsam.utils.test_case import GtsamTestCase + + +class TestPose2(GtsamTestCase): + """Test selected Pose2 methods.""" + + def test_adjoint(self): + """Test adjoint method.""" + xi = np.array([1, 2, 3]) + expected = np.dot(Pose2.adjointMap_(xi), xi) + actual = Pose2.adjoint_(xi, xi) + np.testing.assert_array_equal(actual, expected) + + +if __name__ == "__main__": + unittest.main() diff --git a/python/gtsam_py/python/tests/test_Pose2SLAMExample.py b/python/gtsam_py/python/tests/test_Pose2SLAMExample.py new file mode 100644 index 000000000..a79b6b18c --- /dev/null +++ b/python/gtsam_py/python/tests/test_Pose2SLAMExample.py @@ -0,0 +1,76 @@ +""" +GTSAM Copyright 2010-2019, Georgia Tech Research Corporation, +Atlanta, Georgia 30332-0415 +All Rights Reserved + +See LICENSE for the license information + +Pose2SLAM unit tests. +Author: Frank Dellaert & Duy Nguyen Ta (Python) +""" +import unittest +from math import pi + +import numpy as np + +import gtsam +from gtsam.utils.test_case import GtsamTestCase + + +class TestPose2SLAMExample(GtsamTestCase): + + def test_Pose2SLAMExample(self): + # Assumptions + # - All values are axis aligned + # - Robot poses are facing along the X axis (horizontal, to the right in images) + # - We have full odometry for measurements + # - The robot is on a grid, moving 2 meters each step + + # Create graph container and add factors to it + graph = gtsam.NonlinearFactorGraph() + + # Add prior + # gaussian for prior + priorMean = gtsam.Pose2(0.0, 0.0, 0.0) # prior at origin + priorNoise = gtsam.noiseModel_Diagonal.Sigmas(np.array([0.3, 0.3, 0.1])) + # add directly to graph + graph.add(gtsam.PriorFactorPose2(1, priorMean, priorNoise)) + + # Add odometry + # general noisemodel for odometry + odometryNoise = gtsam.noiseModel_Diagonal.Sigmas(np.array([0.2, 0.2, 0.1])) + graph.add(gtsam.BetweenFactorPose2( + 1, 2, gtsam.Pose2(2.0, 0.0, 0.0), odometryNoise)) + graph.add(gtsam.BetweenFactorPose2( + 2, 3, gtsam.Pose2(2.0, 0.0, pi / 2), odometryNoise)) + graph.add(gtsam.BetweenFactorPose2( + 3, 4, gtsam.Pose2(2.0, 0.0, pi / 2), odometryNoise)) + graph.add(gtsam.BetweenFactorPose2( + 4, 5, gtsam.Pose2(2.0, 0.0, pi / 2), odometryNoise)) + + # Add pose constraint + model = gtsam.noiseModel_Diagonal.Sigmas(np.array([0.2, 0.2, 0.1])) + graph.add(gtsam.BetweenFactorPose2(5, 2, gtsam.Pose2(2.0, 0.0, pi / 2), model)) + + # Initialize to noisy points + initialEstimate = gtsam.Values() + initialEstimate.insert(1, gtsam.Pose2(0.5, 0.0, 0.2)) + initialEstimate.insert(2, gtsam.Pose2(2.3, 0.1, -0.2)) + initialEstimate.insert(3, gtsam.Pose2(4.1, 0.1, pi / 2)) + initialEstimate.insert(4, gtsam.Pose2(4.0, 2.0, pi)) + initialEstimate.insert(5, gtsam.Pose2(2.1, 2.1, -pi / 2)) + + # Optimize using Levenberg-Marquardt optimization with an ordering from + # colamd + optimizer = gtsam.LevenbergMarquardtOptimizer(graph, initialEstimate) + result = optimizer.optimizeSafely() + + # Plot Covariance Ellipses + marginals = gtsam.Marginals(graph, result) + P = marginals.marginalCovariance(1) + + pose_1 = result.atPose2(1) + self.gtsamAssertEquals(pose_1, gtsam.Pose2(), 1e-4) + +if __name__ == "__main__": + unittest.main() diff --git a/python/gtsam_py/python/tests/test_Pose3.py b/python/gtsam_py/python/tests/test_Pose3.py new file mode 100644 index 000000000..138f1ff13 --- /dev/null +++ b/python/gtsam_py/python/tests/test_Pose3.py @@ -0,0 +1,70 @@ +""" +GTSAM Copyright 2010-2019, Georgia Tech Research Corporation, +Atlanta, Georgia 30332-0415 +All Rights Reserved + +See LICENSE for the license information + +Pose3 unit tests. +Author: Frank Dellaert, Duy Nguyen Ta +""" +# pylint: disable=no-name-in-module +import math +import unittest + +import numpy as np + +import gtsam +from gtsam import Point3, Pose3, Rot3 +from gtsam.utils.test_case import GtsamTestCase + + +class TestPose3(GtsamTestCase): + """Test selected Pose3 methods.""" + + def test_between(self): + """Test between method.""" + T2 = Pose3(Rot3.Rodrigues(0.3, 0.2, 0.1), Point3(3.5, -8.2, 4.2)) + T3 = Pose3(Rot3.Rodrigues(-90, 0, 0), Point3(1, 2, 3)) + expected = T2.inverse().compose(T3) + actual = T2.between(T3) + self.gtsamAssertEquals(actual, expected, 1e-6) + + def test_transform_to(self): + """Test transformTo method.""" + transform = Pose3(Rot3.Rodrigues(0, 0, -1.570796), Point3(2, 4, 0)) + actual = transform.transformTo(Point3(3, 2, 10)) + expected = Point3(2, 1, 10) + self.gtsamAssertEquals(actual, expected, 1e-6) + + def test_range(self): + """Test range method.""" + l1 = Point3(1, 0, 0) + l2 = Point3(1, 1, 0) + x1 = Pose3() + + xl1 = Pose3(Rot3.Ypr(0.0, 0.0, 0.0), Point3(1, 0, 0)) + xl2 = Pose3(Rot3.Ypr(0.0, 1.0, 0.0), Point3(1, 1, 0)) + + # establish range is indeed zero + self.assertEqual(1, x1.range(point=l1)) + + # establish range is indeed sqrt2 + self.assertEqual(math.sqrt(2.0), x1.range(point=l2)) + + # establish range is indeed zero + self.assertEqual(1, x1.range(pose=xl1)) + + # establish range is indeed sqrt2 + self.assertEqual(math.sqrt(2.0), x1.range(pose=xl2)) + + def test_adjoint(self): + """Test adjoint method.""" + xi = np.array([1, 2, 3, 4, 5, 6]) + expected = np.dot(Pose3.adjointMap_(xi), xi) + actual = Pose3.adjoint_(xi, xi) + np.testing.assert_array_equal(actual, expected) + + +if __name__ == "__main__": + unittest.main() diff --git a/python/gtsam_py/python/tests/test_Pose3SLAMExample.py b/python/gtsam_py/python/tests/test_Pose3SLAMExample.py new file mode 100644 index 000000000..1e9eaac67 --- /dev/null +++ b/python/gtsam_py/python/tests/test_Pose3SLAMExample.py @@ -0,0 +1,60 @@ +""" +GTSAM Copyright 2010-2019, Georgia Tech Research Corporation, +Atlanta, Georgia 30332-0415 +All Rights Reserved + +See LICENSE for the license information + +PoseSLAM unit tests. +Author: Frank Dellaert & Duy Nguyen Ta (Python) +""" +import unittest +from math import pi + +import numpy as np + +import gtsam +from gtsam.utils.test_case import GtsamTestCase +from gtsam.utils.circlePose3 import * + + +class TestPose3SLAMExample(GtsamTestCase): + + def test_Pose3SLAMExample(self): + # Create a hexagon of poses + hexagon = circlePose3(6, 1.0) + p0 = hexagon.atPose3(0) + p1 = hexagon.atPose3(1) + + # create a Pose graph with one equality constraint and one measurement + fg = gtsam.NonlinearFactorGraph() + fg.add(gtsam.NonlinearEqualityPose3(0, p0)) + delta = p0.between(p1) + covariance = gtsam.noiseModel_Diagonal.Sigmas( + np.array([0.05, 0.05, 0.05, 5. * pi / 180, 5. * pi / 180, 5. * pi / 180])) + fg.add(gtsam.BetweenFactorPose3(0, 1, delta, covariance)) + fg.add(gtsam.BetweenFactorPose3(1, 2, delta, covariance)) + fg.add(gtsam.BetweenFactorPose3(2, 3, delta, covariance)) + fg.add(gtsam.BetweenFactorPose3(3, 4, delta, covariance)) + fg.add(gtsam.BetweenFactorPose3(4, 5, delta, covariance)) + fg.add(gtsam.BetweenFactorPose3(5, 0, delta, covariance)) + + # Create initial config + initial = gtsam.Values() + s = 0.10 + initial.insert(0, p0) + initial.insert(1, hexagon.atPose3(1).retract(s * np.random.randn(6, 1))) + initial.insert(2, hexagon.atPose3(2).retract(s * np.random.randn(6, 1))) + initial.insert(3, hexagon.atPose3(3).retract(s * np.random.randn(6, 1))) + initial.insert(4, hexagon.atPose3(4).retract(s * np.random.randn(6, 1))) + initial.insert(5, hexagon.atPose3(5).retract(s * np.random.randn(6, 1))) + + # optimize + optimizer = gtsam.LevenbergMarquardtOptimizer(fg, initial) + result = optimizer.optimizeSafely() + + pose_1 = result.atPose3(1) + self.gtsamAssertEquals(pose_1, p1, 1e-4) + +if __name__ == "__main__": + unittest.main() diff --git a/python/gtsam_py/python/tests/test_PriorFactor.py b/python/gtsam_py/python/tests/test_PriorFactor.py new file mode 100644 index 000000000..66207b800 --- /dev/null +++ b/python/gtsam_py/python/tests/test_PriorFactor.py @@ -0,0 +1,61 @@ +""" +GTSAM Copyright 2010-2019, Georgia Tech Research Corporation, +Atlanta, Georgia 30332-0415 +All Rights Reserved + +See LICENSE for the license information + +PriorFactor unit tests. +Author: Frank Dellaert & Duy Nguyen Ta (Python) +""" +import unittest + +import numpy as np + +import gtsam +from gtsam.utils.test_case import GtsamTestCase + + +class TestPriorFactor(GtsamTestCase): + + def test_PriorFactor(self): + values = gtsam.Values() + + key = 5 + priorPose3 = gtsam.Pose3() + model = gtsam.noiseModel_Unit.Create(6) + factor = gtsam.PriorFactorPose3(key, priorPose3, model) + values.insert(key, priorPose3) + self.assertEqual(factor.error(values), 0) + + key = 3 + priorVector = np.array([0., 0., 0.]) + model = gtsam.noiseModel_Unit.Create(3) + factor = gtsam.PriorFactorVector(key, priorVector, model) + values.insert(key, priorVector) + self.assertEqual(factor.error(values), 0) + + def test_AddPrior(self): + """ + Test adding prior factors directly to factor graph via the .addPrior method. + """ + # define factor graph + graph = gtsam.NonlinearFactorGraph() + + # define and add Pose3 prior + key = 5 + priorPose3 = gtsam.Pose3() + model = gtsam.noiseModel_Unit.Create(6) + graph.addPriorPose3(key, priorPose3, model) + self.assertEqual(graph.size(), 1) + + # define and add Vector prior + key = 3 + priorVector = np.array([0., 0., 0.]) + model = gtsam.noiseModel_Unit.Create(3) + graph.addPriorVector(key, priorVector, model) + self.assertEqual(graph.size(), 2) + + +if __name__ == "__main__": + unittest.main() diff --git a/python/gtsam_py/python/tests/test_SFMExample.py b/python/gtsam_py/python/tests/test_SFMExample.py new file mode 100644 index 000000000..e8fa46186 --- /dev/null +++ b/python/gtsam_py/python/tests/test_SFMExample.py @@ -0,0 +1,82 @@ +""" +GTSAM Copyright 2010-2019, Georgia Tech Research Corporation, +Atlanta, Georgia 30332-0415 +All Rights Reserved + +See LICENSE for the license information + +SFM unit tests. +Author: Frank Dellaert & Duy Nguyen Ta (Python) +""" +import unittest + +import numpy as np + +import gtsam +import gtsam.utils.visual_data_generator as generator +from gtsam import symbol +from gtsam.utils.test_case import GtsamTestCase + + +class TestSFMExample(GtsamTestCase): + + def test_SFMExample(self): + options = generator.Options() + options.triangle = False + options.nrCameras = 10 + + [data, truth] = generator.generate_data(options) + + measurementNoiseSigma = 1.0 + pointNoiseSigma = 0.1 + poseNoiseSigmas = np.array([0.001, 0.001, 0.001, 0.1, 0.1, 0.1]) + + graph = gtsam.NonlinearFactorGraph() + + # Add factors for all measurements + measurementNoise = gtsam.noiseModel_Isotropic.Sigma(2, measurementNoiseSigma) + for i in range(len(data.Z)): + for k in range(len(data.Z[i])): + j = data.J[i][k] + graph.add(gtsam.GenericProjectionFactorCal3_S2( + data.Z[i][k], measurementNoise, + symbol(ord('x'), i), symbol(ord('p'), j), data.K)) + + posePriorNoise = gtsam.noiseModel_Diagonal.Sigmas(poseNoiseSigmas) + graph.add(gtsam.PriorFactorPose3(symbol(ord('x'), 0), + truth.cameras[0].pose(), posePriorNoise)) + pointPriorNoise = gtsam.noiseModel_Isotropic.Sigma(3, pointNoiseSigma) + graph.add(gtsam.PriorFactorPoint3(symbol(ord('p'), 0), + truth.points[0], pointPriorNoise)) + + # Initial estimate + initialEstimate = gtsam.Values() + for i in range(len(truth.cameras)): + pose_i = truth.cameras[i].pose() + initialEstimate.insert(symbol(ord('x'), i), pose_i) + for j in range(len(truth.points)): + point_j = truth.points[j] + initialEstimate.insert(symbol(ord('p'), j), point_j) + + # Optimization + optimizer = gtsam.LevenbergMarquardtOptimizer(graph, initialEstimate) + for i in range(5): + optimizer.iterate() + result = optimizer.values() + + # Marginalization + marginals = gtsam.Marginals(graph, result) + marginals.marginalCovariance(symbol(ord('p'), 0)) + marginals.marginalCovariance(symbol(ord('x'), 0)) + + # Check optimized results, should be equal to ground truth + for i in range(len(truth.cameras)): + pose_i = result.atPose3(symbol(ord('x'), i)) + self.gtsamAssertEquals(pose_i, truth.cameras[i].pose(), 1e-5) + + for j in range(len(truth.points)): + point_j = result.atPoint3(symbol(ord('p'), j)) + self.gtsamAssertEquals(point_j, truth.points[j], 1e-5) + +if __name__ == "__main__": + unittest.main() diff --git a/python/gtsam_py/python/tests/test_SO4.py b/python/gtsam_py/python/tests/test_SO4.py new file mode 100644 index 000000000..648bd1710 --- /dev/null +++ b/python/gtsam_py/python/tests/test_SO4.py @@ -0,0 +1,59 @@ +""" +GTSAM Copyright 2010-2019, Georgia Tech Research Corporation, +Atlanta, Georgia 30332-0415 +All Rights Reserved + +See LICENSE for the license information + +SO4 unit tests. +Author: Frank Dellaert +""" +# pylint: disable=no-name-in-module, import-error +import unittest + +import numpy as np +from gtsam import SO4 + +I4 = SO4() +v1 = np.array([0, 0, 0, .1, 0, 0]) +v2 = np.array([0, 0, 0, 0.01, 0.02, 0.03]) +Q1 = SO4.Expmap(v1) +Q2 = SO4.Expmap(v2) + + +class TestSO4(unittest.TestCase): + """Test selected SO4 methods.""" + + def test_constructor(self): + """Construct from matrix.""" + matrix = np.eye(4) + so4 = SO4(matrix) + self.assertIsInstance(so4, SO4) + + def test_retract(self): + """Test retraction to manifold.""" + v = np.zeros((6,), np.float) + actual = I4.retract(v) + self.assertTrue(actual.equals(I4, 1e-9)) + + def test_local(self): + """Check localCoordinates for trivial case.""" + v0 = np.zeros((6,), np.float) + actual = I4.localCoordinates(I4) + np.testing.assert_array_almost_equal(actual, v0) + + def test_compose(self): + """Check compose works in subgroup.""" + expected = SO4.Expmap(2*v1) + actual = Q1.compose(Q1) + self.assertTrue(actual.equals(expected, 1e-9)) + + def test_vec(self): + """Check wrapping of vec.""" + expected = np.array([1, 0, 0, 0, 0, 1, 0, 0, 0, 0, 1, 0, 0, 0, 0, 1]) + actual = I4.vec() + np.testing.assert_array_equal(actual, expected) + + +if __name__ == "__main__": + unittest.main() diff --git a/python/gtsam_py/python/tests/test_SOn.py b/python/gtsam_py/python/tests/test_SOn.py new file mode 100644 index 000000000..7599363e2 --- /dev/null +++ b/python/gtsam_py/python/tests/test_SOn.py @@ -0,0 +1,59 @@ +""" +GTSAM Copyright 2010-2019, Georgia Tech Research Corporation, +Atlanta, Georgia 30332-0415 +All Rights Reserved + +See LICENSE for the license information + +Dynamic SO(n) unit tests. +Author: Frank Dellaert +""" +# pylint: disable=no-name-in-module, import-error +import unittest + +import numpy as np +from gtsam import SOn + +I4 = SOn(4) +v1 = np.array([0, 0, 0, .1, 0, 0]) +v2 = np.array([0, 0, 0, 0.01, 0.02, 0.03]) +Q1 = I4.retract(v1) +Q2 = I4.retract(v2) + + +class TestSO4(unittest.TestCase): + """Test selected SOn methods.""" + + def test_constructor(self): + """Construct from matrix.""" + matrix = np.eye(4) + so4 = SOn.FromMatrix(matrix) + self.assertIsInstance(so4, SOn) + + def test_retract(self): + """Test retraction to manifold.""" + v = np.zeros((6,), np.float) + actual = I4.retract(v) + self.assertTrue(actual.equals(I4, 1e-9)) + + def test_local(self): + """Check localCoordinates for trivial case.""" + v0 = np.zeros((6,), np.float) + actual = I4.localCoordinates(I4) + np.testing.assert_array_almost_equal(actual, v0) + + def test_compose(self): + """Check compose works in subgroup.""" + expected = I4.retract(2*v1) + actual = Q1.compose(Q1) + self.assertTrue(actual.equals(expected, 1e-3)) # not exmap so only approximate + + def test_vec(self): + """Check wrapping of vec.""" + expected = np.array([1, 0, 0, 0, 0, 1, 0, 0, 0, 0, 1, 0, 0, 0, 0, 1]) + actual = I4.vec() + np.testing.assert_array_equal(actual, expected) + + +if __name__ == "__main__": + unittest.main() diff --git a/python/gtsam_py/python/tests/test_Scenario.py b/python/gtsam_py/python/tests/test_Scenario.py new file mode 100644 index 000000000..09601fba5 --- /dev/null +++ b/python/gtsam_py/python/tests/test_Scenario.py @@ -0,0 +1,53 @@ +""" +GTSAM Copyright 2010-2019, Georgia Tech Research Corporation, +Atlanta, Georgia 30332-0415 +All Rights Reserved + +See LICENSE for the license information + +Scenario unit tests. +Author: Frank Dellaert & Duy Nguyen Ta (Python) +""" +from __future__ import print_function + +import math +import unittest + +import numpy as np + +import gtsam +from gtsam.utils.test_case import GtsamTestCase + +# pylint: disable=invalid-name, E1101 + + +class TestScenario(GtsamTestCase): + def setUp(self): + pass + + def test_loop(self): + # Forward velocity 2m/s + # Pitch up with angular velocity 6 degree/sec (negative in FLU) + v = 2 + w = math.radians(6) + W = np.array([0, -w, 0]) + V = np.array([v, 0, 0]) + scenario = gtsam.ConstantTwistScenario(W, V) + + T = 30 + np.testing.assert_almost_equal(W, scenario.omega_b(T)) + np.testing.assert_almost_equal(V, scenario.velocity_b(T)) + np.testing.assert_almost_equal( + np.cross(W, V), scenario.acceleration_b(T)) + + # R = v/w, so test if loop crests at 2*R + R = v / w + T30 = scenario.pose(T) + np.testing.assert_almost_equal( + np.array([math.pi, 0, math.pi]), T30.rotation().xyz()) + self.gtsamAssertEquals(gtsam.Point3( + 0, 0, 2.0 * R), T30.translation(), 1e-9) + + +if __name__ == '__main__': + unittest.main() diff --git a/python/gtsam_py/python/tests/test_SimpleCamera.py b/python/gtsam_py/python/tests/test_SimpleCamera.py new file mode 100644 index 000000000..a3654a5f1 --- /dev/null +++ b/python/gtsam_py/python/tests/test_SimpleCamera.py @@ -0,0 +1,45 @@ +""" +GTSAM Copyright 2010-2019, Georgia Tech Research Corporation, +Atlanta, Georgia 30332-0415 +All Rights Reserved + +See LICENSE for the license information + +PinholeCameraCal3_S2 unit tests. +Author: Frank Dellaert & Duy Nguyen Ta (Python) +""" +import math +import unittest + +import numpy as np + +import gtsam +from gtsam import Cal3_S2, Point3, Pose2, Pose3, Rot3, PinholeCameraCal3_S2 +from gtsam.utils.test_case import GtsamTestCase + +K = Cal3_S2(625, 625, 0, 0, 0) + +class TestSimpleCamera(GtsamTestCase): + + def test_constructor(self): + pose1 = Pose3(Rot3(np.diag([1, -1, -1])), Point3(0, 0, 0.5)) + camera = PinholeCameraCal3_S2(pose1, K) + self.gtsamAssertEquals(camera.calibration(), K, 1e-9) + self.gtsamAssertEquals(camera.pose(), pose1, 1e-9) + + def test_level2(self): + # Create a level camera, looking in Y-direction + pose2 = Pose2(0.4,0.3,math.pi/2.0) + camera = PinholeCameraCal3_S2.Level(K, pose2, 0.1) + + # expected + x = Point3(1,0,0) + y = Point3(0,0,-1) + z = Point3(0,1,0) + wRc = Rot3(x,y,z) + expected = Pose3(wRc,Point3(0.4,0.3,0.1)) + self.gtsamAssertEquals(camera.pose(), expected, 1e-9) + + +if __name__ == "__main__": + unittest.main() diff --git a/python/gtsam_py/python/tests/test_StereoVOExample.py b/python/gtsam_py/python/tests/test_StereoVOExample.py new file mode 100644 index 000000000..3f5f57522 --- /dev/null +++ b/python/gtsam_py/python/tests/test_StereoVOExample.py @@ -0,0 +1,82 @@ +""" +GTSAM Copyright 2010-2019, Georgia Tech Research Corporation, +Atlanta, Georgia 30332-0415 +All Rights Reserved + +See LICENSE for the license information + +Stereo VO unit tests. +Author: Frank Dellaert & Duy Nguyen Ta (Python) +""" +import unittest + +import numpy as np + +import gtsam +from gtsam import symbol +from gtsam.utils.test_case import GtsamTestCase + + +class TestStereoVOExample(GtsamTestCase): + + def test_StereoVOExample(self): + ## Assumptions + # - For simplicity this example is in the camera's coordinate frame + # - X: right, Y: down, Z: forward + # - Pose x1 is at the origin, Pose 2 is 1 meter forward (along Z-axis) + # - x1 is fixed with a constraint, x2 is initialized with noisy values + # - No noise on measurements + + ## Create keys for variables + x1 = symbol(ord('x'),1) + x2 = symbol(ord('x'),2) + l1 = symbol(ord('l'),1) + l2 = symbol(ord('l'),2) + l3 = symbol(ord('l'),3) + + ## Create graph container and add factors to it + graph = gtsam.NonlinearFactorGraph() + + ## add a constraint on the starting pose + first_pose = gtsam.Pose3() + graph.add(gtsam.NonlinearEqualityPose3(x1, first_pose)) + + ## Create realistic calibration and measurement noise model + # format: fx fy skew cx cy baseline + K = gtsam.Cal3_S2Stereo(1000, 1000, 0, 320, 240, 0.2) + stereo_model = gtsam.noiseModel_Diagonal.Sigmas(np.array([1.0, 1.0, 1.0])) + + ## Add measurements + # pose 1 + graph.add(gtsam.GenericStereoFactor3D(gtsam.StereoPoint2(520, 480, 440), stereo_model, x1, l1, K)) + graph.add(gtsam.GenericStereoFactor3D(gtsam.StereoPoint2(120, 80, 440), stereo_model, x1, l2, K)) + graph.add(gtsam.GenericStereoFactor3D(gtsam.StereoPoint2(320, 280, 140), stereo_model, x1, l3, K)) + + #pose 2 + graph.add(gtsam.GenericStereoFactor3D(gtsam.StereoPoint2(570, 520, 490), stereo_model, x2, l1, K)) + graph.add(gtsam.GenericStereoFactor3D(gtsam.StereoPoint2( 70, 20, 490), stereo_model, x2, l2, K)) + graph.add(gtsam.GenericStereoFactor3D(gtsam.StereoPoint2(320, 270, 115), stereo_model, x2, l3, K)) + + ## Create initial estimate for camera poses and landmarks + initialEstimate = gtsam.Values() + initialEstimate.insert(x1, first_pose) + # noisy estimate for pose 2 + initialEstimate.insert(x2, gtsam.Pose3(gtsam.Rot3(), gtsam.Point3(0.1,-.1,1.1))) + expected_l1 = gtsam.Point3( 1, 1, 5) + initialEstimate.insert(l1, expected_l1) + initialEstimate.insert(l2, gtsam.Point3(-1, 1, 5)) + initialEstimate.insert(l3, gtsam.Point3( 0,-.5, 5)) + + ## optimize + optimizer = gtsam.LevenbergMarquardtOptimizer(graph, initialEstimate) + result = optimizer.optimize() + + ## check equality for the first pose and point + pose_x1 = result.atPose3(x1) + self.gtsamAssertEquals(pose_x1, first_pose,1e-4) + + point_l1 = result.atPoint3(l1) + self.gtsamAssertEquals(point_l1, expected_l1,1e-4) + +if __name__ == "__main__": + unittest.main() diff --git a/python/gtsam_py/python/tests/test_Values.py b/python/gtsam_py/python/tests/test_Values.py new file mode 100644 index 000000000..20634a21c --- /dev/null +++ b/python/gtsam_py/python/tests/test_Values.py @@ -0,0 +1,86 @@ +""" +GTSAM Copyright 2010-2019, Georgia Tech Research Corporation, +Atlanta, Georgia 30332-0415 +All Rights Reserved + +See LICENSE for the license information + +Values unit tests. +Author: Frank Dellaert & Duy Nguyen Ta (Python) +""" +# pylint: disable=invalid-name, E1101, E0611 +import unittest + +import numpy as np + +import gtsam +from gtsam import (Cal3_S2, Cal3Bundler, Cal3DS2, EssentialMatrix, Point2, + Point3, Pose2, Pose3, Rot2, Rot3, Unit3, Values, + imuBias_ConstantBias) +from gtsam.utils.test_case import GtsamTestCase + + +class TestValues(GtsamTestCase): + + def test_values(self): + values = Values() + E = EssentialMatrix(Rot3(), Unit3()) + tol = 1e-9 + + values.insert(0, Point2(0, 0)) + values.insert(1, Point3(0, 0, 0)) + values.insert(2, Rot2()) + values.insert(3, Pose2()) + values.insert(4, Rot3()) + values.insert(5, Pose3()) + values.insert(6, Cal3_S2()) + values.insert(7, Cal3DS2()) + values.insert(8, Cal3Bundler()) + values.insert(9, E) + values.insert(10, imuBias_ConstantBias()) + + # Special cases for Vectors and Matrices + # Note that gtsam's Eigen Vectors and Matrices requires double-precision + # floating point numbers in column-major (Fortran style) storage order, + # whereas by default, numpy.array is in row-major order and the type is + # in whatever the number input type is, e.g. np.array([1,2,3]) + # will have 'int' type. + # + # The wrapper will automatically fix the type and storage order for you, + # but for performance reasons, it's recommended to specify the correct + # type and storage order. + # for vectors, the order is not important, but dtype still is + vec = np.array([1., 2., 3.]) + values.insert(11, vec) + mat = np.array([[1., 2.], [3., 4.]], order='F') + values.insert(12, mat) + # Test with dtype int and the default order='C' + # This still works as the wrapper converts to the correct type and order for you + # but is nornally not recommended! + mat2 = np.array([[1, 2, ], [3, 5]]) + values.insert(13, mat2) + + self.gtsamAssertEquals(values.atPoint2(0), Point2(0,0), tol) + self.gtsamAssertEquals(values.atPoint3(1), Point3(0,0,0), tol) + self.gtsamAssertEquals(values.atRot2(2), Rot2(), tol) + self.gtsamAssertEquals(values.atPose2(3), Pose2(), tol) + self.gtsamAssertEquals(values.atRot3(4), Rot3(), tol) + self.gtsamAssertEquals(values.atPose3(5), Pose3(), tol) + self.gtsamAssertEquals(values.atCal3_S2(6), Cal3_S2(), tol) + self.gtsamAssertEquals(values.atCal3DS2(7), Cal3DS2(), tol) + self.gtsamAssertEquals(values.atCal3Bundler(8), Cal3Bundler(), tol) + self.gtsamAssertEquals(values.atEssentialMatrix(9), E, tol) + self.gtsamAssertEquals(values.atimuBias_ConstantBias( + 10), imuBias_ConstantBias(), tol) + + # special cases for Vector and Matrix: + actualVector = values.atVector(11) + np.testing.assert_allclose(vec, actualVector, tol) + actualMatrix = values.atMatrix(12) + np.testing.assert_allclose(mat, actualMatrix, tol) + actualMatrix2 = values.atMatrix(13) + np.testing.assert_allclose(mat2, actualMatrix2, tol) + + +if __name__ == "__main__": + unittest.main() diff --git a/python/gtsam_py/python/tests/test_VisualISAMExample.py b/python/gtsam_py/python/tests/test_VisualISAMExample.py new file mode 100644 index 000000000..99d7e6160 --- /dev/null +++ b/python/gtsam_py/python/tests/test_VisualISAMExample.py @@ -0,0 +1,57 @@ +""" +GTSAM Copyright 2010-2019, Georgia Tech Research Corporation, +Atlanta, Georgia 30332-0415 +All Rights Reserved + +See LICENSE for the license information + +visual_isam unit tests. +Author: Frank Dellaert & Duy Nguyen Ta (Python) +""" +import unittest + +import numpy as np + +import gtsam +import gtsam.utils.visual_data_generator as generator +import gtsam.utils.visual_isam as visual_isam +from gtsam import symbol +from gtsam.utils.test_case import GtsamTestCase + + +class TestVisualISAMExample(GtsamTestCase): + + def test_VisualISAMExample(self): + # Data Options + options = generator.Options() + options.triangle = False + options.nrCameras = 20 + + # iSAM Options + isamOptions = visual_isam.Options() + isamOptions.hardConstraint = False + isamOptions.pointPriors = False + isamOptions.batchInitialization = True + isamOptions.reorderInterval = 10 + isamOptions.alwaysRelinearize = False + + # Generate data + data, truth = generator.generate_data(options) + + # Initialize iSAM with the first pose and points + isam, result, nextPose = visual_isam.initialize(data, truth, isamOptions) + + # Main loop for iSAM: stepping through all poses + for currentPose in range(nextPose, options.nrCameras): + isam, result = visual_isam.step(data, isam, result, truth, currentPose) + + for i in range(len(truth.cameras)): + pose_i = result.atPose3(symbol(ord('x'), i)) + self.gtsamAssertEquals(pose_i, truth.cameras[i].pose(), 1e-5) + + for j in range(len(truth.points)): + point_j = result.atPoint3(symbol(ord('l'), j)) + self.gtsamAssertEquals(point_j, truth.points[j], 1e-5) + +if __name__ == "__main__": + unittest.main() diff --git a/python/gtsam_py/python/tests/test_dataset.py b/python/gtsam_py/python/tests/test_dataset.py new file mode 100644 index 000000000..60fb9450d --- /dev/null +++ b/python/gtsam_py/python/tests/test_dataset.py @@ -0,0 +1,45 @@ +""" +GTSAM Copyright 2010-2019, Georgia Tech Research Corporation, +Atlanta, Georgia 30332-0415 +All Rights Reserved + +See LICENSE for the license information + +Unit tests for testing dataset access. +Author: Frank Dellaert & Duy Nguyen Ta (Python) +""" +# pylint: disable=invalid-name, no-name-in-module, no-member + +from __future__ import print_function + +import unittest + +import gtsam +from gtsam import BetweenFactorPose3, BetweenFactorPose3s +from gtsam.utils.test_case import GtsamTestCase + + +class TestDataset(GtsamTestCase): + """Tests for datasets.h wrapper.""" + + def setUp(self): + """Get some common paths.""" + self.pose3_example_g2o_file = gtsam.findExampleDataFile( + "pose3example.txt") + + def test_readG2o3D(self): + """Test reading directly into factor graph.""" + is3D = True + graph, initial = gtsam.readG2o(self.pose3_example_g2o_file, is3D) + self.assertEqual(graph.size(), 6) + self.assertEqual(initial.size(), 5) + + def test_parse3Dfactors(self): + """Test parsing into data structure.""" + factors = gtsam.parse3DFactors(self.pose3_example_g2o_file) + self.assertEqual(factors.size(), 6) + self.assertIsInstance(factors.at(0), BetweenFactorPose3) + + +if __name__ == '__main__': + unittest.main() diff --git a/python/gtsam_py/python/tests/test_dsf_map.py b/python/gtsam_py/python/tests/test_dsf_map.py new file mode 100644 index 000000000..73ddcb050 --- /dev/null +++ b/python/gtsam_py/python/tests/test_dsf_map.py @@ -0,0 +1,40 @@ +""" +GTSAM Copyright 2010-2019, Georgia Tech Research Corporation, +Atlanta, Georgia 30332-0415 +All Rights Reserved + +See LICENSE for the license information + +Unit tests for Disjoint Set Forest. +Author: Frank Dellaert & Varun Agrawal +""" +# pylint: disable=invalid-name, no-name-in-module, no-member + +from __future__ import print_function + +import unittest + +import gtsam +from gtsam.utils.test_case import GtsamTestCase + + +class TestDSFMap(GtsamTestCase): + """Tests for DSFMap.""" + + def test_all(self): + """Test everything in DFSMap.""" + def key(index_pair): + return index_pair.i(), index_pair.j() + + dsf = gtsam.DSFMapIndexPair() + pair1 = gtsam.IndexPair(1, 18) + self.assertEqual(key(dsf.find(pair1)), key(pair1)) + pair2 = gtsam.IndexPair(2, 2) + + # testing the merge feature of dsf + dsf.merge(pair1, pair2) + self.assertEqual(key(dsf.find(pair1)), key(dsf.find(pair2))) + + +if __name__ == '__main__': + unittest.main() diff --git a/python/gtsam_py/python/tests/test_initialize_pose3.py b/python/gtsam_py/python/tests/test_initialize_pose3.py new file mode 100644 index 000000000..3aa7e3470 --- /dev/null +++ b/python/gtsam_py/python/tests/test_initialize_pose3.py @@ -0,0 +1,89 @@ +""" +GTSAM Copyright 2010-2019, Georgia Tech Research Corporation, +Atlanta, Georgia 30332-0415 +All Rights Reserved + +See LICENSE for the license information + +Unit tests for 3D SLAM initialization, using rotation relaxation. +Author: Luca Carlone and Frank Dellaert (Python) +""" +# pylint: disable=invalid-name, E1101, E0611 +import unittest + +import numpy as np + +import gtsam +from gtsam import NonlinearFactorGraph, Point3, Pose3, Rot3, Values +from gtsam.utils.test_case import GtsamTestCase + +x0, x1, x2, x3 = 0, 1, 2, 3 + + +class TestValues(GtsamTestCase): + + def setUp(self): + + model = gtsam.noiseModel_Isotropic.Sigma(6, 0.1) + + # We consider a small graph: + # symbolic FG + # x2 0 1 + # / | \ 1 2 + # / | \ 2 3 + # x3 | x1 2 0 + # \ | / 0 3 + # \ | / + # x0 + # + p0 = Point3(0, 0, 0) + self.R0 = Rot3.Expmap(np.array([0.0, 0.0, 0.0])) + p1 = Point3(1, 2, 0) + self.R1 = Rot3.Expmap(np.array([0.0, 0.0, 1.570796])) + p2 = Point3(0, 2, 0) + self.R2 = Rot3.Expmap(np.array([0.0, 0.0, 3.141593])) + p3 = Point3(-1, 1, 0) + self.R3 = Rot3.Expmap(np.array([0.0, 0.0, 4.712389])) + + pose0 = Pose3(self.R0, p0) + pose1 = Pose3(self.R1, p1) + pose2 = Pose3(self.R2, p2) + pose3 = Pose3(self.R3, p3) + + g = NonlinearFactorGraph() + g.add(gtsam.BetweenFactorPose3(x0, x1, pose0.between(pose1), model)) + g.add(gtsam.BetweenFactorPose3(x1, x2, pose1.between(pose2), model)) + g.add(gtsam.BetweenFactorPose3(x2, x3, pose2.between(pose3), model)) + g.add(gtsam.BetweenFactorPose3(x2, x0, pose2.between(pose0), model)) + g.add(gtsam.BetweenFactorPose3(x0, x3, pose0.between(pose3), model)) + g.add(gtsam.PriorFactorPose3(x0, pose0, model)) + self.graph = g + + def test_buildPose3graph(self): + pose3graph = gtsam.InitializePose3.buildPose3graph(self.graph) + + def test_orientations(self): + pose3Graph = gtsam.InitializePose3.buildPose3graph(self.graph) + + initial = gtsam.InitializePose3.computeOrientationsChordal(pose3Graph) + + # comparison is up to M_PI, that's why we add some multiples of 2*M_PI + self.gtsamAssertEquals(initial.atRot3(x0), self.R0, 1e-6) + self.gtsamAssertEquals(initial.atRot3(x1), self.R1, 1e-6) + self.gtsamAssertEquals(initial.atRot3(x2), self.R2, 1e-6) + self.gtsamAssertEquals(initial.atRot3(x3), self.R3, 1e-6) + + def test_initializePoses(self): + g2oFile = gtsam.findExampleDataFile("pose3example-grid") + is3D = True + inputGraph, expectedValues = gtsam.readG2o(g2oFile, is3D) + priorModel = gtsam.noiseModel_Unit.Create(6) + inputGraph.add(gtsam.PriorFactorPose3(0, Pose3(), priorModel)) + + initial = gtsam.InitializePose3.initialize(inputGraph) + # TODO(frank): very loose !! + self.gtsamAssertEquals(initial, expectedValues, 0.1) + + +if __name__ == "__main__": + unittest.main() diff --git a/python/gtsam_py/python/tests/test_logging_optimizer.py b/python/gtsam_py/python/tests/test_logging_optimizer.py new file mode 100644 index 000000000..2560a72a2 --- /dev/null +++ b/python/gtsam_py/python/tests/test_logging_optimizer.py @@ -0,0 +1,108 @@ +""" +Unit tests for optimization that logs to comet.ml. +Author: Jing Wu and Frank Dellaert +""" +# pylint: disable=invalid-name + +import sys +if sys.version_info.major >= 3: + from io import StringIO +else: + from cStringIO import StringIO + +import unittest +from datetime import datetime + +import gtsam +import numpy as np +from gtsam import Rot3 +from gtsam.utils.test_case import GtsamTestCase + +from gtsam.utils.logging_optimizer import gtsam_optimize + +KEY = 0 +MODEL = gtsam.noiseModel_Unit.Create(3) + + +class TestOptimizeComet(GtsamTestCase): + """Check correct logging to comet.ml.""" + + def setUp(self): + """Set up a small Karcher mean optimization example.""" + # Grabbed from KarcherMeanFactor unit tests. + R = Rot3.Expmap(np.array([0.1, 0, 0])) + rotations = {R, R.inverse()} # mean is the identity + self.expected = Rot3() + + graph = gtsam.NonlinearFactorGraph() + for R in rotations: + graph.add(gtsam.PriorFactorRot3(KEY, R, MODEL)) + initial = gtsam.Values() + initial.insert(KEY, R) + self.params = gtsam.GaussNewtonParams() + self.optimizer = gtsam.GaussNewtonOptimizer( + graph, initial, self.params) + + self.lmparams = gtsam.LevenbergMarquardtParams() + self.lmoptimizer = gtsam.LevenbergMarquardtOptimizer( + graph, initial, self.lmparams + ) + + # setup output capture + self.capturedOutput = StringIO() + sys.stdout = self.capturedOutput + + def tearDown(self): + """Reset print capture.""" + sys.stdout = sys.__stdout__ + + def test_simple_printing(self): + """Test with a simple hook.""" + + # Provide a hook that just prints + def hook(_, error): + print(error) + + # Only thing we require from optimizer is an iterate method + gtsam_optimize(self.optimizer, self.params, hook) + + # Check that optimizing yields the identity. + actual = self.optimizer.values() + self.gtsamAssertEquals(actual.atRot3(KEY), self.expected, tol=1e-6) + + def test_lm_simple_printing(self): + """Make sure we are properly terminating LM""" + def hook(_, error): + print(error) + + gtsam_optimize(self.lmoptimizer, self.lmparams, hook) + + actual = self.lmoptimizer.values() + self.gtsamAssertEquals(actual.atRot3(KEY), self.expected, tol=1e-6) + + @unittest.skip("Not a test we want run every time, as needs comet.ml account") + def test_comet(self): + """Test with a comet hook.""" + from comet_ml import Experiment + comet = Experiment(project_name="Testing", + auto_output_logging="native") + comet.log_dataset_info(name="Karcher", path="shonan") + comet.add_tag("GaussNewton") + comet.log_parameter("method", "GaussNewton") + time = datetime.now() + comet.set_name("GaussNewton-" + str(time.month) + "/" + str(time.day) + " " + + str(time.hour)+":"+str(time.minute)+":"+str(time.second)) + + # I want to do some comet thing here + def hook(optimizer, error): + comet.log_metric("Karcher error", + error, optimizer.iterations()) + + gtsam_optimize(self.optimizer, self.params, hook) + comet.end() + + actual = self.optimizer.values() + self.gtsamAssertEquals(actual.atRot3(KEY), self.expected) + +if __name__ == "__main__": + unittest.main() diff --git a/python/gtsam_py/python/utils/__init__.py b/python/gtsam_py/python/utils/__init__.py new file mode 100644 index 000000000..e69de29bb diff --git a/python/gtsam_py/python/utils/circlePose3.py b/python/gtsam_py/python/utils/circlePose3.py new file mode 100644 index 000000000..7012548f4 --- /dev/null +++ b/python/gtsam_py/python/utils/circlePose3.py @@ -0,0 +1,38 @@ +import gtsam +import numpy as np +from math import pi, cos, sin + + +def circlePose3(numPoses=8, radius=1.0, symbolChar=0): + """ + circlePose3 generates a set of poses in a circle. This function + returns those poses inside a gtsam.Values object, with sequential + keys starting from 0. An optional character may be provided, which + will be stored in the msb of each key (i.e. gtsam.Symbol). + + We use aerospace/navlab convention, X forward, Y right, Z down + First pose will be at (R,0,0) + ^y ^ X + | | + z-->xZ--> Y (z pointing towards viewer, Z pointing away from viewer) + Vehicle at p0 is looking towards y axis (X-axis points towards world y) + """ + + # Force symbolChar to be a single character + if type(symbolChar) is str: + symbolChar = ord(symbolChar[0]) + + values = gtsam.Values() + theta = 0.0 + dtheta = 2 * pi / numPoses + gRo = gtsam.Rot3( + np.array([[0., 1., 0.], [1., 0., 0.], [0., 0., -1.]], order='F')) + for i in range(numPoses): + key = gtsam.symbol(symbolChar, i) + gti = gtsam.Point3(radius * cos(theta), radius * sin(theta), 0) + oRi = gtsam.Rot3.Yaw( + -theta) # negative yaw goes counterclockwise, with Z down ! + gTi = gtsam.Pose3(gRo.compose(oRi), gti) + values.insert(key, gTi) + theta = theta + dtheta + return values diff --git a/python/gtsam_py/python/utils/logging_optimizer.py b/python/gtsam_py/python/utils/logging_optimizer.py new file mode 100644 index 000000000..3d9175951 --- /dev/null +++ b/python/gtsam_py/python/utils/logging_optimizer.py @@ -0,0 +1,52 @@ +""" +Optimization with logging via a hook. +Author: Jing Wu and Frank Dellaert +""" +# pylint: disable=invalid-name + +from gtsam import NonlinearOptimizer, NonlinearOptimizerParams +import gtsam + + +def optimize(optimizer, check_convergence, hook): + """ Given an optimizer and a convergence check, iterate until convergence. + After each iteration, hook(optimizer, error) is called. + After the function, use values and errors to get the result. + Arguments: + optimizer (T): needs an iterate and an error function. + check_convergence: T * float * float -> bool + hook -- hook function to record the error + """ + # the optimizer is created with default values which incur the error below + current_error = optimizer.error() + hook(optimizer, current_error) + + # Iterative loop + while True: + # Do next iteration + optimizer.iterate() + new_error = optimizer.error() + hook(optimizer, new_error) + if check_convergence(optimizer, current_error, new_error): + return + current_error = new_error + + +def gtsam_optimize(optimizer, + params, + hook): + """ Given an optimizer and params, iterate until convergence. + After each iteration, hook(optimizer) is called. + After the function, use values and errors to get the result. + Arguments: + optimizer {NonlinearOptimizer} -- Nonlinear optimizer + params {NonlinearOptimizarParams} -- Nonlinear optimizer parameters + hook -- hook function to record the error + """ + def check_convergence(optimizer, current_error, new_error): + return (optimizer.iterations() >= params.getMaxIterations()) or ( + gtsam.checkConvergence(params.getRelativeErrorTol(), params.getAbsoluteErrorTol(), params.getErrorTol(), + current_error, new_error)) or ( + isinstance(optimizer, gtsam.LevenbergMarquardtOptimizer) and optimizer.lambda_() > params.getlambdaUpperBound()) + optimize(optimizer, check_convergence, hook) + return optimizer.values() diff --git a/python/gtsam_py/python/utils/plot.py b/python/gtsam_py/python/utils/plot.py new file mode 100644 index 000000000..1e976a69e --- /dev/null +++ b/python/gtsam_py/python/utils/plot.py @@ -0,0 +1,369 @@ +"""Various plotting utlities.""" + +import numpy as np +import matplotlib.pyplot as plt +from matplotlib import patches +from mpl_toolkits.mplot3d import Axes3D + +import gtsam + + +def set_axes_equal(fignum): + """ + Make axes of 3D plot have equal scale so that spheres appear as spheres, + cubes as cubes, etc.. This is one possible solution to Matplotlib's + ax.set_aspect('equal') and ax.axis('equal') not working for 3D. + + Args: + fignum (int): An integer representing the figure number for Matplotlib. + """ + fig = plt.figure(fignum) + ax = fig.gca(projection='3d') + + limits = np.array([ + ax.get_xlim3d(), + ax.get_ylim3d(), + ax.get_zlim3d(), + ]) + + origin = np.mean(limits, axis=1) + radius = 0.5 * np.max(np.abs(limits[:, 1] - limits[:, 0])) + + ax.set_xlim3d([origin[0] - radius, origin[0] + radius]) + ax.set_ylim3d([origin[1] - radius, origin[1] + radius]) + ax.set_zlim3d([origin[2] - radius, origin[2] + radius]) + + +def ellipsoid(xc, yc, zc, rx, ry, rz, n): + """ + Numpy equivalent of Matlab's ellipsoid function. + + Args: + xc (double): Center of ellipsoid in X-axis. + yc (double): Center of ellipsoid in Y-axis. + zc (double): Center of ellipsoid in Z-axis. + rx (double): Radius of ellipsoid in X-axis. + ry (double): Radius of ellipsoid in Y-axis. + rz (double): Radius of ellipsoid in Z-axis. + n (int): The granularity of the ellipsoid plotted. + + Returns: + tuple[numpy.ndarray]: The points in the x, y and z axes to use for the surface plot. + """ + u = np.linspace(0, 2*np.pi, n+1) + v = np.linspace(0, np.pi, n+1) + x = -rx * np.outer(np.cos(u), np.sin(v)).T + y = -ry * np.outer(np.sin(u), np.sin(v)).T + z = -rz * np.outer(np.ones_like(u), np.cos(v)).T + + return x, y, z + + +def plot_covariance_ellipse_3d(axes, origin, P, scale=1, n=8, alpha=0.5): + """ + Plots a Gaussian as an uncertainty ellipse + + Based on Maybeck Vol 1, page 366 + k=2.296 corresponds to 1 std, 68.26% of all probability + k=11.82 corresponds to 3 std, 99.74% of all probability + + Args: + axes (matplotlib.axes.Axes): Matplotlib axes. + origin (gtsam.Point3): The origin in the world frame. + P (numpy.ndarray): The marginal covariance matrix of the 3D point which will be represented as an ellipse. + scale (float): Scaling factor of the radii of the covariance ellipse. + n (int): Defines the granularity of the ellipse. Higher values indicate finer ellipses. + alpha (float): Transparency value for the plotted surface in the range [0, 1]. + """ + k = 11.82 + U, S, _ = np.linalg.svd(P) + + radii = k * np.sqrt(S) + radii = radii * scale + rx, ry, rz = radii + + # generate data for "unrotated" ellipsoid + xc, yc, zc = ellipsoid(0, 0, 0, rx, ry, rz, n) + + # rotate data with orientation matrix U and center c + data = np.kron(U[:, 0:1], xc) + np.kron(U[:, 1:2], yc) + \ + np.kron(U[:, 2:3], zc) + n = data.shape[1] + x = data[0:n, :] + origin[0] + y = data[n:2*n, :] + origin[1] + z = data[2*n:, :] + origin[2] + + axes.plot_surface(x, y, z, alpha=alpha, cmap='hot') + + +def plot_pose2_on_axes(axes, pose, axis_length=0.1, covariance=None): + """ + Plot a 2D pose on given axis `axes` with given `axis_length`. + + Args: + axes (matplotlib.axes.Axes): Matplotlib axes. + pose (gtsam.Pose2): The pose to be plotted. + axis_length (float): The length of the camera axes. + covariance (numpy.ndarray): Marginal covariance matrix to plot the uncertainty of the estimation. + """ + # get rotation and translation (center) + gRp = pose.rotation().matrix() # rotation from pose to global + t = pose.translation() + origin = np.array([t.x(), t.y()]) + + # draw the camera axes + x_axis = origin + gRp[:, 0] * axis_length + line = np.append(origin[np.newaxis], x_axis[np.newaxis], axis=0) + axes.plot(line[:, 0], line[:, 1], 'r-') + + y_axis = origin + gRp[:, 1] * axis_length + line = np.append(origin[np.newaxis], y_axis[np.newaxis], axis=0) + axes.plot(line[:, 0], line[:, 1], 'g-') + + if covariance is not None: + pPp = covariance[0:2, 0:2] + gPp = np.matmul(np.matmul(gRp, pPp), gRp.T) + + w, v = np.linalg.eig(gPp) + + # k = 2.296 + k = 5.0 + + angle = np.arctan2(v[1, 0], v[0, 0]) + e1 = patches.Ellipse(origin, np.sqrt(w[0]*k), np.sqrt(w[1]*k), + np.rad2deg(angle), fill=False) + axes.add_patch(e1) + + +def plot_pose2(fignum, pose, axis_length=0.1, covariance=None, + axis_labels=('X axis', 'Y axis', 'Z axis')): + """ + Plot a 2D pose on given figure with given `axis_length`. + + Args: + fignum (int): Integer representing the figure number to use for plotting. + pose (gtsam.Pose2): The pose to be plotted. + axis_length (float): The length of the camera axes. + covariance (numpy.ndarray): Marginal covariance matrix to plot the uncertainty of the estimation. + axis_labels (iterable[string]): List of axis labels to set. + """ + # get figure object + fig = plt.figure(fignum) + axes = fig.gca() + plot_pose2_on_axes(axes, pose, axis_length=axis_length, + covariance=covariance) + + axes.set_xlabel(axis_labels[0]) + axes.set_ylabel(axis_labels[1]) + axes.set_zlabel(axis_labels[2]) + + return fig + + +def plot_point3_on_axes(axes, point, linespec, P=None): + """ + Plot a 3D point on given axis `axes` with given `linespec`. + + Args: + axes (matplotlib.axes.Axes): Matplotlib axes. + point (gtsam.Point3): The point to be plotted. + linespec (string): String representing formatting options for Matplotlib. + P (numpy.ndarray): Marginal covariance matrix to plot the uncertainty of the estimation. + """ + axes.plot([point.x()], [point.y()], [point.z()], linespec) + if P is not None: + plot_covariance_ellipse_3d(axes, point.vector(), P) + + +def plot_point3(fignum, point, linespec, P=None, + axis_labels=('X axis', 'Y axis', 'Z axis')): + """ + Plot a 3D point on given figure with given `linespec`. + + Args: + fignum (int): Integer representing the figure number to use for plotting. + point (gtsam.Point3): The point to be plotted. + linespec (string): String representing formatting options for Matplotlib. + P (numpy.ndarray): Marginal covariance matrix to plot the uncertainty of the estimation. + axis_labels (iterable[string]): List of axis labels to set. + + Returns: + fig: The matplotlib figure. + + """ + fig = plt.figure(fignum) + axes = fig.gca(projection='3d') + plot_point3_on_axes(axes, point, linespec, P) + + axes.set_xlabel(axis_labels[0]) + axes.set_ylabel(axis_labels[1]) + axes.set_zlabel(axis_labels[2]) + + return fig + + +def plot_3d_points(fignum, values, linespec="g*", marginals=None, + title="3D Points", axis_labels=('X axis', 'Y axis', 'Z axis')): + """ + Plots the Point3s in `values`, with optional covariances. + Finds all the Point3 objects in the given Values object and plots them. + If a Marginals object is given, this function will also plot marginal + covariance ellipses for each point. + + Args: + fignum (int): Integer representing the figure number to use for plotting. + values (gtsam.Values): Values dictionary consisting of points to be plotted. + linespec (string): String representing formatting options for Matplotlib. + marginals (numpy.ndarray): Marginal covariance matrix to plot the uncertainty of the estimation. + title (string): The title of the plot. + axis_labels (iterable[string]): List of axis labels to set. + """ + + keys = values.keys() + + # Plot points and covariance matrices + for i in range(keys.size()): + try: + key = keys.at(i) + point = values.atPoint3(key) + if marginals is not None: + covariance = marginals.marginalCovariance(key) + else: + covariance = None + + fig = plot_point3(fignum, point, linespec, covariance, + axis_labels=axis_labels) + + except RuntimeError: + continue + # I guess it's not a Point3 + + fig.suptitle(title) + fig.canvas.set_window_title(title.lower()) + + +def plot_pose3_on_axes(axes, pose, axis_length=0.1, P=None, scale=1): + """ + Plot a 3D pose on given axis `axes` with given `axis_length`. + + Args: + axes (matplotlib.axes.Axes): Matplotlib axes. + point (gtsam.Point3): The point to be plotted. + linespec (string): String representing formatting options for Matplotlib. + P (numpy.ndarray): Marginal covariance matrix to plot the uncertainty of the estimation. + """ + # get rotation and translation (center) + gRp = pose.rotation().matrix() # rotation from pose to global + origin = pose.translation().vector() + + # draw the camera axes + x_axis = origin + gRp[:, 0] * axis_length + line = np.append(origin[np.newaxis], x_axis[np.newaxis], axis=0) + axes.plot(line[:, 0], line[:, 1], line[:, 2], 'r-') + + y_axis = origin + gRp[:, 1] * axis_length + line = np.append(origin[np.newaxis], y_axis[np.newaxis], axis=0) + axes.plot(line[:, 0], line[:, 1], line[:, 2], 'g-') + + z_axis = origin + gRp[:, 2] * axis_length + line = np.append(origin[np.newaxis], z_axis[np.newaxis], axis=0) + axes.plot(line[:, 0], line[:, 1], line[:, 2], 'b-') + + # plot the covariance + if P is not None: + # covariance matrix in pose coordinate frame + pPp = P[3:6, 3:6] + # convert the covariance matrix to global coordinate frame + gPp = gRp @ pPp @ gRp.T + plot_covariance_ellipse_3d(axes, origin, gPp) + + +def plot_pose3(fignum, pose, axis_length=0.1, P=None, + axis_labels=('X axis', 'Y axis', 'Z axis')): + """ + Plot a 3D pose on given figure with given `axis_length`. + + Args: + fignum (int): Integer representing the figure number to use for plotting. + pose (gtsam.Pose3): 3D pose to be plotted. + linespec (string): String representing formatting options for Matplotlib. + P (numpy.ndarray): Marginal covariance matrix to plot the uncertainty of the estimation. + axis_labels (iterable[string]): List of axis labels to set. + + Returns: + fig: The matplotlib figure. + """ + # get figure object + fig = plt.figure(fignum) + axes = fig.gca(projection='3d') + plot_pose3_on_axes(axes, pose, P=P, + axis_length=axis_length) + + axes.set_xlabel(axis_labels[0]) + axes.set_ylabel(axis_labels[1]) + axes.set_zlabel(axis_labels[2]) + + return fig + + +def plot_trajectory(fignum, values, scale=1, marginals=None, + title="Plot Trajectory", axis_labels=('X axis', 'Y axis', 'Z axis')): + """ + Plot a complete 3D trajectory using poses in `values`. + + Args: + fignum (int): Integer representing the figure number to use for plotting. + values (gtsam.Values): Values dict containing the poses. + scale (float): Value to scale the poses by. + marginals (gtsam.Marginals): Marginalized probability values of the estimation. + Used to plot uncertainty bounds. + title (string): The title of the plot. + axis_labels (iterable[string]): List of axis labels to set. + """ + pose3Values = gtsam.utilities_allPose3s(values) + keys = gtsam.KeyVector(pose3Values.keys()) + lastIndex = None + + for i in range(keys.size()): + key = keys.at(i) + try: + pose = pose3Values.atPose3(key) + except: + print("Warning: no Pose3 at key: {0}".format(key)) + + if lastIndex is not None: + lastKey = keys.at(lastIndex) + try: + lastPose = pose3Values.atPose3(lastKey) + except: + print("Warning: no Pose3 at key: {0}".format(lastKey)) + pass + + if marginals: + covariance = marginals.marginalCovariance(lastKey) + else: + covariance = None + + fig = plot_pose3(fignum, lastPose, P=covariance, + axis_length=scale, axis_labels=axis_labels) + + lastIndex = i + + # Draw final pose + if lastIndex is not None: + lastKey = keys.at(lastIndex) + try: + lastPose = pose3Values.atPose3(lastKey) + if marginals: + covariance = marginals.marginalCovariance(lastKey) + else: + covariance = None + + fig = plot_pose3(fignum, lastPose, P=covariance, + axis_length=scale, axis_labels=axis_labels) + + except: + pass + + fig.suptitle(title) + fig.canvas.set_window_title(title.lower()) diff --git a/python/gtsam_py/python/utils/test_case.py b/python/gtsam_py/python/utils/test_case.py new file mode 100644 index 000000000..7df1e6ee9 --- /dev/null +++ b/python/gtsam_py/python/utils/test_case.py @@ -0,0 +1,27 @@ +""" +GTSAM Copyright 2010-2019, Georgia Tech Research Corporation, +Atlanta, Georgia 30332-0415 +All Rights Reserved + +See LICENSE for the license information + +TestCase class with GTSAM assert utils. +Author: Frank Dellaert +""" +import unittest + + +class GtsamTestCase(unittest.TestCase): + """TestCase class with GTSAM assert utils.""" + + def gtsamAssertEquals(self, actual, expected, tol=1e-9): + """ AssertEqual function that prints out actual and expected if not equal. + Usage: + self.gtsamAssertEqual(actual,expected) + Keyword Arguments: + tol {float} -- tolerance passed to 'equals', default 1e-9 + """ + equal = actual.equals(expected, tol) + if not equal: + raise self.failureException( + "Values are not equal:\n{}!={}".format(actual, expected)) diff --git a/python/gtsam_py/python/utils/visual_data_generator.py b/python/gtsam_py/python/utils/visual_data_generator.py new file mode 100644 index 000000000..f04588e70 --- /dev/null +++ b/python/gtsam_py/python/utils/visual_data_generator.py @@ -0,0 +1,118 @@ +from __future__ import print_function + +import numpy as np + +import gtsam +from gtsam import Cal3_S2, PinholeCameraCal3_S2, Point2, Point3, Pose3 + + +class Options: + """ + Options to generate test scenario + """ + + def __init__(self, triangle=False, nrCameras=3, K=Cal3_S2()): + """ + Options to generate test scenario + @param triangle: generate a triangle scene with 3 points if True, otherwise + a cube with 8 points + @param nrCameras: number of cameras to generate + @param K: camera calibration object + """ + self.triangle = triangle + self.nrCameras = nrCameras + + +class GroundTruth: + """ + Object holding generated ground-truth data + """ + + def __init__(self, K=Cal3_S2(), nrCameras=3, nrPoints=4): + self.K = K + self.cameras = [Pose3()] * nrCameras + self.points = [Point3()] * nrPoints + + def print_(self, s=""): + print(s) + print("K = ", self.K) + print("Cameras: ", len(self.cameras)) + for camera in self.cameras: + print("\t", camera) + print("Points: ", len(self.points)) + for point in self.points: + print("\t", point) + pass + + +class Data: + """ + Object holding generated measurement data + """ + + class NoiseModels: + pass + + def __init__(self, K=Cal3_S2(), nrCameras=3, nrPoints=4): + self.K = K + self.Z = [x[:] for x in [[Point2()] * nrPoints] * nrCameras] + self.J = [x[:] for x in [[0] * nrPoints] * nrCameras] + self.odometry = [Pose3()] * nrCameras + + # Set Noise parameters + self.noiseModels = Data.NoiseModels() + self.noiseModels.posePrior = gtsam.noiseModel_Diagonal.Sigmas( + np.array([0.001, 0.001, 0.001, 0.1, 0.1, 0.1])) + # noiseModels.odometry = gtsam.noiseModel_Diagonal.Sigmas( + # np.array([0.001,0.001,0.001,0.1,0.1,0.1])) + self.noiseModels.odometry = gtsam.noiseModel_Diagonal.Sigmas( + np.array([0.05, 0.05, 0.05, 0.2, 0.2, 0.2])) + self.noiseModels.pointPrior = gtsam.noiseModel_Isotropic.Sigma(3, 0.1) + self.noiseModels.measurement = gtsam.noiseModel_Isotropic.Sigma(2, 1.0) + + +def generate_data(options): + """ Generate ground-truth and measurement data. """ + + K = Cal3_S2(500, 500, 0, 640. / 2., 480. / 2.) + nrPoints = 3 if options.triangle else 8 + + truth = GroundTruth(K=K, nrCameras=options.nrCameras, nrPoints=nrPoints) + data = Data(K, nrCameras=options.nrCameras, nrPoints=nrPoints) + + # Generate simulated data + if options.triangle: # Create a triangle target, just 3 points on a plane + r = 10 + for j in range(len(truth.points)): + theta = j * 2 * np.pi / nrPoints + truth.points[j] = Point3(r * np.cos(theta), r * np.sin(theta), 0) + else: # 3D landmarks as vertices of a cube + truth.points = [ + Point3(10, 10, 10), Point3(-10, 10, 10), + Point3(-10, -10, 10), Point3(10, -10, 10), + Point3(10, 10, -10), Point3(-10, 10, -10), + Point3(-10, -10, -10), Point3(10, -10, -10) + ] + + # Create camera cameras on a circle around the triangle + height = 10 + r = 40 + for i in range(options.nrCameras): + theta = i * 2 * np.pi / options.nrCameras + t = Point3(r * np.cos(theta), r * np.sin(theta), height) + truth.cameras[i] = PinholeCameraCal3_S2.Lookat(t, + Point3(), + Point3(0, 0, 1), + truth.K) + # Create measurements + for j in range(nrPoints): + # All landmarks seen in every frame + data.Z[i][j] = truth.cameras[i].project(truth.points[j]) + data.J[i][j] = j + + # Calculate odometry between cameras + for i in range(1, options.nrCameras): + data.odometry[i] = truth.cameras[i - 1].pose().between( + truth.cameras[i].pose()) + + return data, truth diff --git a/python/gtsam_py/python/utils/visual_isam.py b/python/gtsam_py/python/utils/visual_isam.py new file mode 100644 index 000000000..b0ebe68c3 --- /dev/null +++ b/python/gtsam_py/python/utils/visual_isam.py @@ -0,0 +1,131 @@ +import gtsam +from gtsam import symbol + + +class Options: + """ Options for visual isam example. """ + + def __init__(self): + self.hardConstraint = False + self.pointPriors = False + self.batchInitialization = True + self.reorderInterval = 10 + self.alwaysRelinearize = False + + +def initialize(data, truth, options): + # Initialize iSAM + params = gtsam.ISAM2Params() + if options.alwaysRelinearize: + params.setRelinearizeSkip(1) + isam = gtsam.ISAM2(params=params) + + # Add constraints/priors + # TODO: should not be from ground truth! + newFactors = gtsam.NonlinearFactorGraph() + initialEstimates = gtsam.Values() + for i in range(2): + ii = symbol(ord('x'), i) + if i == 0: + if options.hardConstraint: # add hard constraint + newFactors.add( + gtsam.NonlinearEqualityPose3(ii, truth.cameras[0].pose())) + else: + newFactors.add( + gtsam.PriorFactorPose3(ii, truth.cameras[i].pose(), + data.noiseModels.posePrior)) + initialEstimates.insert(ii, truth.cameras[i].pose()) + + nextPoseIndex = 2 + + # Add visual measurement factors from two first poses and initialize + # observed landmarks + for i in range(2): + ii = symbol(ord('x'), i) + for k in range(len(data.Z[i])): + j = data.J[i][k] + jj = symbol(ord('l'), j) + newFactors.add( + gtsam.GenericProjectionFactorCal3_S2(data.Z[i][ + k], data.noiseModels.measurement, ii, jj, data.K)) + # TODO: initial estimates should not be from ground truth! + if not initialEstimates.exists(jj): + initialEstimates.insert(jj, truth.points[j]) + if options.pointPriors: # add point priors + newFactors.add( + gtsam.PriorFactorPoint3(jj, truth.points[j], + data.noiseModels.pointPrior)) + + # Add odometry between frames 0 and 1 + newFactors.add( + gtsam.BetweenFactorPose3( + symbol(ord('x'), 0), + symbol(ord('x'), 1), data.odometry[1], data.noiseModels.odometry)) + + # Update ISAM + if options.batchInitialization: # Do a full optimize for first two poses + batchOptimizer = gtsam.LevenbergMarquardtOptimizer(newFactors, + initialEstimates) + fullyOptimized = batchOptimizer.optimize() + isam.update(newFactors, fullyOptimized) + else: + isam.update(newFactors, initialEstimates) + + # figure(1)tic + # t=toc plot(frame_i,t,'r.') tic + result = isam.calculateEstimate() + # t=toc plot(frame_i,t,'g.') + + return isam, result, nextPoseIndex + + +def step(data, isam, result, truth, currPoseIndex): + ''' + Do one step isam update + @param[in] data: measurement data (odometry and visual measurements and their noiseModels) + @param[in/out] isam: current isam object, will be updated + @param[in/out] result: current result object, will be updated + @param[in] truth: ground truth data, used to initialize new variables + @param[currPoseIndex]: index of the current pose + ''' + # iSAM expects us to give it a new set of factors + # along with initial estimates for any new variables introduced. + newFactors = gtsam.NonlinearFactorGraph() + initialEstimates = gtsam.Values() + + # Add odometry + prevPoseIndex = currPoseIndex - 1 + odometry = data.odometry[prevPoseIndex] + newFactors.add( + gtsam.BetweenFactorPose3( + symbol(ord('x'), prevPoseIndex), + symbol(ord('x'), currPoseIndex), odometry, + data.noiseModels.odometry)) + + # Add visual measurement factors and initializations as necessary + for k in range(len(data.Z[currPoseIndex])): + zij = data.Z[currPoseIndex][k] + j = data.J[currPoseIndex][k] + jj = symbol(ord('l'), j) + newFactors.add( + gtsam.GenericProjectionFactorCal3_S2( + zij, data.noiseModels.measurement, + symbol(ord('x'), currPoseIndex), jj, data.K)) + # TODO: initialize with something other than truth + if not result.exists(jj) and not initialEstimates.exists(jj): + lmInit = truth.points[j] + initialEstimates.insert(jj, lmInit) + + # Initial estimates for the new pose. + prevPose = result.atPose3(symbol(ord('x'), prevPoseIndex)) + initialEstimates.insert( + symbol(ord('x'), currPoseIndex), prevPose.compose(odometry)) + + # Update ISAM + # figure(1)tic + isam.update(newFactors, initialEstimates) + # t=toc plot(frame_i,t,'r.') tic + newResult = isam.calculateEstimate() + # t=toc plot(frame_i,t,'g.') + + return isam, newResult From 7873c3608878bbba99860a36423afa4ee0a480d8 Mon Sep 17 00:00:00 2001 From: Fan Jiang Date: Mon, 27 Jul 2020 09:30:24 -0400 Subject: [PATCH 269/869] Add unstable files --- python/gtsam_unstable_py/python/__init__.py | 1 + .../examples/FixedLagSmootherExample.py | 102 +++++++++++++ .../python/examples/TimeOfArrivalExample.py | 128 +++++++++++++++++ .../python/examples/__init__.py | 0 .../python/tests/__init__.py | 0 .../tests/test_FixedLagSmootherExample.py | 135 ++++++++++++++++++ 6 files changed, 366 insertions(+) create mode 100644 python/gtsam_unstable_py/python/__init__.py create mode 100644 python/gtsam_unstable_py/python/examples/FixedLagSmootherExample.py create mode 100644 python/gtsam_unstable_py/python/examples/TimeOfArrivalExample.py create mode 100644 python/gtsam_unstable_py/python/examples/__init__.py create mode 100644 python/gtsam_unstable_py/python/tests/__init__.py create mode 100644 python/gtsam_unstable_py/python/tests/test_FixedLagSmootherExample.py diff --git a/python/gtsam_unstable_py/python/__init__.py b/python/gtsam_unstable_py/python/__init__.py new file mode 100644 index 000000000..3195e6da4 --- /dev/null +++ b/python/gtsam_unstable_py/python/__init__.py @@ -0,0 +1 @@ +from .gtsam_unstable import * diff --git a/python/gtsam_unstable_py/python/examples/FixedLagSmootherExample.py b/python/gtsam_unstable_py/python/examples/FixedLagSmootherExample.py new file mode 100644 index 000000000..786701e0f --- /dev/null +++ b/python/gtsam_unstable_py/python/examples/FixedLagSmootherExample.py @@ -0,0 +1,102 @@ +""" +GTSAM Copyright 2010-2018, Georgia Tech Research Corporation, +Atlanta, Georgia 30332-0415 +All Rights Reserved +Authors: Frank Dellaert, et al. (see THANKS for the full author list) + +See LICENSE for the license information + +Demonstration of the fixed-lag smoothers using a planar robot example +and multiple odometry-like sensors +Author: Frank Dellaert (C++), Jeremy Aguilon (Python) +""" + +import numpy as np + +import gtsam +import gtsam_unstable + + +def _timestamp_key_value(key, value): + """ + + """ + return gtsam_unstable.FixedLagSmootherKeyTimestampMapValue( + key, value + ) + + +def BatchFixedLagSmootherExample(): + """ + Runs a batch fixed smoother on an agent with two odometry + sensors that is simply moving to the + """ + + # Define a batch fixed lag smoother, which uses + # Levenberg-Marquardt to perform the nonlinear optimization + lag = 2.0 + smoother_batch = gtsam_unstable.BatchFixedLagSmoother(lag) + + # Create containers to store the factors and linearization points + # that will be sent to the smoothers + new_factors = gtsam.NonlinearFactorGraph() + new_values = gtsam.Values() + new_timestamps = gtsam_unstable.FixedLagSmootherKeyTimestampMap() + + # Create a prior on the first pose, placing it at the origin + prior_mean = gtsam.Pose2(0, 0, 0) + prior_noise = gtsam.noiseModel_Diagonal.Sigmas(np.array([0.3, 0.3, 0.1])) + X1 = 0 + new_factors.push_back(gtsam.PriorFactorPose2(X1, prior_mean, prior_noise)) + new_values.insert(X1, prior_mean) + new_timestamps.insert(_timestamp_key_value(X1, 0.0)) + + delta_time = 0.25 + time = 0.25 + + while time <= 3.0: + previous_key = 1000 * (time - delta_time) + current_key = 1000 * time + + # assign current key to the current timestamp + new_timestamps.insert(_timestamp_key_value(current_key, time)) + + # Add a guess for this pose to the new values + # Assume that the robot moves at 2 m/s. Position is time[s] * 2[m/s] + current_pose = gtsam.Pose2(time * 2, 0, 0) + new_values.insert(current_key, current_pose) + + # Add odometry factors from two different sources with different error + # stats + odometry_measurement_1 = gtsam.Pose2(0.61, -0.08, 0.02) + odometry_noise_1 = gtsam.noiseModel_Diagonal.Sigmas( + np.array([0.1, 0.1, 0.05])) + new_factors.push_back(gtsam.BetweenFactorPose2( + previous_key, current_key, odometry_measurement_1, odometry_noise_1 + )) + + odometry_measurement_2 = gtsam.Pose2(0.47, 0.03, 0.01) + odometry_noise_2 = gtsam.noiseModel_Diagonal.Sigmas( + np.array([0.05, 0.05, 0.05])) + new_factors.push_back(gtsam.BetweenFactorPose2( + previous_key, current_key, odometry_measurement_2, odometry_noise_2 + )) + + # Update the smoothers with the new factors. In this case, + # one iteration must pass for Levenberg-Marquardt to accurately + # estimate + if time >= 0.50: + smoother_batch.update(new_factors, new_values, new_timestamps) + print("Timestamp = " + str(time) + ", Key = " + str(current_key)) + print(smoother_batch.calculateEstimatePose2(current_key)) + + new_timestamps.clear() + new_values.clear() + new_factors.resize(0) + + time += delta_time + + +if __name__ == '__main__': + BatchFixedLagSmootherExample() + print("Example complete") diff --git a/python/gtsam_unstable_py/python/examples/TimeOfArrivalExample.py b/python/gtsam_unstable_py/python/examples/TimeOfArrivalExample.py new file mode 100644 index 000000000..6ba06f0f2 --- /dev/null +++ b/python/gtsam_unstable_py/python/examples/TimeOfArrivalExample.py @@ -0,0 +1,128 @@ +""" +GTSAM Copyright 2010-2020, Georgia Tech Research Corporation, +Atlanta, Georgia 30332-0415 +All Rights Reserved +Authors: Frank Dellaert, et al. (see THANKS for the full author list) + +See LICENSE for the license information + +Track a moving object "Time of Arrival" measurements at 4 microphones. +Author: Frank Dellaert +""" +# pylint: disable=invalid-name, no-name-in-module + +from gtsam import (LevenbergMarquardtOptimizer, LevenbergMarquardtParams, + NonlinearFactorGraph, Point3, Values, noiseModel_Isotropic) +from gtsam_unstable import Event, TimeOfArrival, TOAFactor + +# units +MS = 1e-3 +CM = 1e-2 + +# Instantiate functor with speed of sound value +TIME_OF_ARRIVAL = TimeOfArrival(330) + + +def define_microphones(): + """Create microphones.""" + height = 0.5 + microphones = [] + microphones.append(Point3(0, 0, height)) + microphones.append(Point3(403 * CM, 0, height)) + microphones.append(Point3(403 * CM, 403 * CM, height)) + microphones.append(Point3(0, 403 * CM, 2 * height)) + return microphones + + +def create_trajectory(n): + """Create ground truth trajectory.""" + trajectory = [] + timeOfEvent = 10 + # simulate emitting a sound every second while moving on straight line + for key in range(n): + trajectory.append( + Event(timeOfEvent, 245 * CM + key * 1.0, 201.5 * CM, (212 - 45) * CM)) + timeOfEvent += 1 + + return trajectory + + +def simulate_one_toa(microphones, event): + """Simulate time-of-arrival measurements for a single event.""" + return [TIME_OF_ARRIVAL.measure(event, microphones[i]) + for i in range(len(microphones))] + + +def simulate_toa(microphones, trajectory): + """Simulate time-of-arrival measurements for an entire trajectory.""" + return [simulate_one_toa(microphones, event) + for event in trajectory] + + +def create_graph(microphones, simulatedTOA): + """Create factor graph.""" + graph = NonlinearFactorGraph() + + # Create a noise model for the TOA error + model = noiseModel_Isotropic.Sigma(1, 0.5 * MS) + + K = len(microphones) + key = 0 + for toa in simulatedTOA: + for i in range(K): + factor = TOAFactor(key, microphones[i], toa[i], model) + graph.push_back(factor) + key += 1 + + return graph + + +def create_initial_estimate(n): + """Create initial estimate for n events.""" + initial = Values() + zero = Event() + for key in range(n): + TOAFactor.InsertEvent(key, zero, initial) + return initial + + +def toa_example(): + """Run example with 4 microphones and 5 events in a straight line.""" + # Create microphones + microphones = define_microphones() + K = len(microphones) + for i in range(K): + print("mic {} = {}".format(i, microphones[i])) + + # Create a ground truth trajectory + n = 5 + groundTruth = create_trajectory(n) + for event in groundTruth: + print(event) + + # Simulate time-of-arrival measurements + simulatedTOA = simulate_toa(microphones, groundTruth) + for key in range(n): + for i in range(K): + print("z_{}{} = {} ms".format(key, i, simulatedTOA[key][i] / MS)) + + # create factor graph + graph = create_graph(microphones, simulatedTOA) + print(graph.at(0)) + + # Create initial estimate + initial_estimate = create_initial_estimate(n) + print(initial_estimate) + + # Optimize using Levenberg-Marquardt optimization. + params = LevenbergMarquardtParams() + params.setAbsoluteErrorTol(1e-10) + params.setVerbosityLM("SUMMARY") + optimizer = LevenbergMarquardtOptimizer(graph, initial_estimate, params) + result = optimizer.optimize() + print("Final Result:\n", result) + + +if __name__ == '__main__': + toa_example() + print("Example complete") diff --git a/python/gtsam_unstable_py/python/examples/__init__.py b/python/gtsam_unstable_py/python/examples/__init__.py new file mode 100644 index 000000000..e69de29bb diff --git a/python/gtsam_unstable_py/python/tests/__init__.py b/python/gtsam_unstable_py/python/tests/__init__.py new file mode 100644 index 000000000..e69de29bb diff --git a/python/gtsam_unstable_py/python/tests/test_FixedLagSmootherExample.py b/python/gtsam_unstable_py/python/tests/test_FixedLagSmootherExample.py new file mode 100644 index 000000000..8d3af311f --- /dev/null +++ b/python/gtsam_unstable_py/python/tests/test_FixedLagSmootherExample.py @@ -0,0 +1,135 @@ +""" +GTSAM Copyright 2010-2019, Georgia Tech Research Corporation, +Atlanta, Georgia 30332-0415 +All Rights Reserved + +See LICENSE for the license information + +Cal3Unified unit tests. +Author: Frank Dellaert & Duy Nguyen Ta (Python) +""" +import unittest + +import numpy as np + +import gtsam +import gtsam_unstable +from gtsam.utils.test_case import GtsamTestCase + + +def _timestamp_key_value(key, value): + return gtsam_unstable.FixedLagSmootherKeyTimestampMapValue( + key, value + ) + + +class TestFixedLagSmootherExample(GtsamTestCase): + ''' + Tests the fixed lag smoother wrapper + ''' + + def test_FixedLagSmootherExample(self): + ''' + Simple test that checks for equality between C++ example + file and the Python implementation. See + gtsam_unstable/examples/FixedLagSmootherExample.cpp + ''' + # Define a batch fixed lag smoother, which uses + # Levenberg-Marquardt to perform the nonlinear optimization + lag = 2.0 + smoother_batch = gtsam_unstable.BatchFixedLagSmoother(lag) + + # Create containers to store the factors and linearization points + # that will be sent to the smoothers + new_factors = gtsam.NonlinearFactorGraph() + new_values = gtsam.Values() + new_timestamps = gtsam_unstable.FixedLagSmootherKeyTimestampMap() + + # Create a prior on the first pose, placing it at the origin + prior_mean = gtsam.Pose2(0, 0, 0) + prior_noise = gtsam.noiseModel_Diagonal.Sigmas( + np.array([0.3, 0.3, 0.1])) + X1 = 0 + new_factors.push_back( + gtsam.PriorFactorPose2( + X1, prior_mean, prior_noise)) + new_values.insert(X1, prior_mean) + new_timestamps.insert(_timestamp_key_value(X1, 0.0)) + + delta_time = 0.25 + time = 0.25 + + i = 0 + + ground_truth = [ + gtsam.Pose2(0.995821, 0.0231012, 0.0300001), + gtsam.Pose2(1.49284, 0.0457247, 0.045), + gtsam.Pose2(1.98981, 0.0758879, 0.06), + gtsam.Pose2(2.48627, 0.113502, 0.075), + gtsam.Pose2(2.98211, 0.158558, 0.09), + gtsam.Pose2(3.47722, 0.211047, 0.105), + gtsam.Pose2(3.97149, 0.270956, 0.12), + gtsam.Pose2(4.4648, 0.338272, 0.135), + gtsam.Pose2(4.95705, 0.41298, 0.15), + gtsam.Pose2(5.44812, 0.495063, 0.165), + gtsam.Pose2(5.9379, 0.584503, 0.18), + ] + + # Iterates from 0.25s to 3.0s, adding 0.25s each loop + # In each iteration, the agent moves at a constant speed + # and its two odometers measure the change. The smoothed + # result is then compared to the ground truth + while time <= 3.0: + previous_key = 1000 * (time - delta_time) + current_key = 1000 * time + + # assign current key to the current timestamp + new_timestamps.insert(_timestamp_key_value(current_key, time)) + + # Add a guess for this pose to the new values + # Assume that the robot moves at 2 m/s. Position is time[s] * + # 2[m/s] + current_pose = gtsam.Pose2(time * 2, 0, 0) + new_values.insert(current_key, current_pose) + + # Add odometry factors from two different sources with different + # error stats + odometry_measurement_1 = gtsam.Pose2(0.61, -0.08, 0.02) + odometry_noise_1 = gtsam.noiseModel_Diagonal.Sigmas( + np.array([0.1, 0.1, 0.05])) + new_factors.push_back( + gtsam.BetweenFactorPose2( + previous_key, + current_key, + odometry_measurement_1, + odometry_noise_1)) + + odometry_measurement_2 = gtsam.Pose2(0.47, 0.03, 0.01) + odometry_noise_2 = gtsam.noiseModel_Diagonal.Sigmas( + np.array([0.05, 0.05, 0.05])) + new_factors.push_back( + gtsam.BetweenFactorPose2( + previous_key, + current_key, + odometry_measurement_2, + odometry_noise_2)) + + # Update the smoothers with the new factors. In this case, + # one iteration must pass for Levenberg-Marquardt to accurately + # estimate + if time >= 0.50: + smoother_batch.update(new_factors, new_values, new_timestamps) + + estimate = smoother_batch.calculateEstimatePose2(current_key) + self.assertTrue(estimate.equals(ground_truth[i], 1e-4)) + i += 1 + + new_timestamps.clear() + new_values.clear() + new_factors.resize(0) + + time += delta_time + + +if __name__ == "__main__": + unittest.main() From 9216934ca8295a00200121a687d4378abbcb8350 Mon Sep 17 00:00:00 2001 From: Fan Jiang Date: Mon, 27 Jul 2020 09:32:31 -0400 Subject: [PATCH 270/869] Replace with new python tests --- python/gtsam_py/python/__init__.py | 29 +-- .../python/examples/DogLegOptimizerExample.py | 6 +- .../python/examples/GPSFactorExample.py | 4 +- .../python/examples/ImuFactorExample.py | 50 ++--- .../python/examples/ImuFactorExample2.py | 77 +++---- .../python/examples/OdometryExample.py | 4 +- .../examples/PlanarManipulatorExample.py | 6 +- .../python/examples/PlanarSLAMExample.py | 21 +- .../python/examples/Pose2SLAMExample.py | 4 +- .../python/examples/Pose2SLAMExample_g2o.py | 9 +- .../python/examples/Pose3SLAMExample_g2o.py | 13 +- ...Pose3SLAMExample_initializePose3Chordal.py | 2 +- .../python/examples/PreintegrationExample.py | 4 +- python/gtsam_py/python/examples/README.md | 9 +- python/gtsam_py/python/examples/SFMExample.py | 33 +-- python/gtsam_py/python/examples/SFMdata.py | 3 +- .../python/examples/SimpleRotation.py | 7 +- .../python/examples/VisualISAM2Example.py | 27 ++- .../python/examples/VisualISAMExample.py | 33 +-- python/gtsam_py/python/tests/__init__.py | 0 .../python/tests/testScenarioRunner.py | 2 +- .../python/tests/test_GaussianFactorGraph.py | 13 +- .../python/tests/test_JacobianFactor.py | 6 +- .../python/tests/test_KalmanFilter.py | 4 +- .../python/tests/test_KarcherMeanFactor.py | 6 +- .../python/tests/test_LocalizationExample.py | 4 +- .../python/tests/test_NonlinearOptimizer.py | 15 +- .../python/tests/test_OdometryExample.py | 4 +- .../python/tests/test_PlanarSLAMExample.py | 6 +- .../python/tests/test_Pose2SLAMExample.py | 6 +- .../python/tests/test_Pose3SLAMExample.py | 2 +- .../gtsam_py/python/tests/test_PriorFactor.py | 26 +-- .../gtsam_py/python/tests/test_SFMExample.py | 24 +-- python/gtsam_py/python/tests/test_Scenario.py | 5 +- .../python/tests/test_SimpleCamera.py | 8 +- .../python/tests/test_StereoVOExample.py | 12 +- .../python/tests/test_Triangulation.py | 80 +++++++ python/gtsam_py/python/tests/test_Values.py | 9 +- .../python/tests/test_VisualISAMExample.py | 4 +- python/gtsam_py/python/tests/test_dataset.py | 6 +- .../python/tests/test_initialize_pose3.py | 7 +- .../python/tests/test_logging_optimizer.py | 2 +- python/gtsam_py/python/utils/circlePose3.py | 6 +- python/gtsam_py/python/utils/plot.py | 200 +++--------------- python/gtsam_py/python/utils/test_case.py | 6 +- .../python/utils/visual_data_generator.py | 53 +++-- python/gtsam_py/python/utils/visual_isam.py | 22 +- .../examples/FixedLagSmootherExample.py | 24 +-- .../python/examples/TimeOfArrivalExample.py | 4 +- .../tests/test_FixedLagSmootherExample.py | 21 +- 50 files changed, 408 insertions(+), 520 deletions(-) delete mode 100644 python/gtsam_py/python/tests/__init__.py create mode 100644 python/gtsam_py/python/tests/test_Triangulation.py diff --git a/python/gtsam_py/python/__init__.py b/python/gtsam_py/python/__init__.py index d40ee4502..9e3e19187 100644 --- a/python/gtsam_py/python/__init__.py +++ b/python/gtsam_py/python/__init__.py @@ -1,26 +1,9 @@ from .gtsam import * -try: - import gtsam_unstable - - - def _deprecated_wrapper(item, name): - def wrapper(*args, **kwargs): - from warnings import warn - message = ('importing the unstable item "{}" directly from gtsam is deprecated. '.format(name) + - 'Please import it from gtsam_unstable.') - warn(message) - return item(*args, **kwargs) - return wrapper - - - for name in dir(gtsam_unstable): - if not name.startswith('__'): - item = getattr(gtsam_unstable, name) - if callable(item): - item = _deprecated_wrapper(item, name) - globals()[name] = item - -except ImportError: - pass +def Point2(x=0, y=0): + import numpy as np + return np.array([x, y], dtype=float) +def Point3(x=0, y=0, z=0): + import numpy as np + return np.array([x, y, z], dtype=float) diff --git a/python/gtsam_py/python/examples/DogLegOptimizerExample.py b/python/gtsam_py/python/examples/DogLegOptimizerExample.py index 776ceedc4..26f4fef84 100644 --- a/python/gtsam_py/python/examples/DogLegOptimizerExample.py +++ b/python/gtsam_py/python/examples/DogLegOptimizerExample.py @@ -35,17 +35,17 @@ def run(args): graph = gtsam.NonlinearFactorGraph() # Priors - prior = gtsam.noiseModel_Isotropic.Sigma(3, 1) + prior = gtsam.noiseModel.Isotropic.Sigma(3, 1) graph.add(gtsam.PriorFactorPose2(11, T11, prior)) graph.add(gtsam.PriorFactorPose2(21, T21, prior)) # Odometry - model = gtsam.noiseModel_Diagonal.Sigmas(np.array([0.01, 0.01, 0.3])) + model = gtsam.noiseModel.Diagonal.Sigmas(np.array([0.01, 0.01, 0.3])) graph.add(gtsam.BetweenFactorPose2(11, 12, T11.between(T12), model)) graph.add(gtsam.BetweenFactorPose2(21, 22, T21.between(T22), model)) # Range - model_rho = gtsam.noiseModel_Isotropic.Sigma(1, 0.01) + model_rho = gtsam.noiseModel.Isotropic.Sigma(1, 0.01) graph.add(gtsam.RangeFactorPose2(12, 22, 1.0, model_rho)) params = gtsam.DoglegParams() diff --git a/python/gtsam_py/python/examples/GPSFactorExample.py b/python/gtsam_py/python/examples/GPSFactorExample.py index 493a07725..0bc0d1bf3 100644 --- a/python/gtsam_py/python/examples/GPSFactorExample.py +++ b/python/gtsam_py/python/examples/GPSFactorExample.py @@ -26,8 +26,8 @@ lon0 = -84.30626 h0 = 274 # Create noise models -GPS_NOISE = gtsam.noiseModel_Isotropic.Sigma(3, 0.1) -PRIOR_NOISE = gtsam.noiseModel_Isotropic.Sigma(6, 0.25) +GPS_NOISE = gtsam.noiseModel.Isotropic.Sigma(3, 0.1) +PRIOR_NOISE = gtsam.noiseModel.Isotropic.Sigma(6, 0.25) # Create an empty nonlinear factor graph graph = gtsam.NonlinearFactorGraph() diff --git a/python/gtsam_py/python/examples/ImuFactorExample.py b/python/gtsam_py/python/examples/ImuFactorExample.py index 0e01766e7..adaa3c08a 100644 --- a/python/gtsam_py/python/examples/ImuFactorExample.py +++ b/python/gtsam_py/python/examples/ImuFactorExample.py @@ -5,27 +5,32 @@ All Rights Reserved See LICENSE for the license information -A script validating and demonstrating the ImuFactor inference. - -Author: Frank Dellaert, Varun Agrawal +A script validating the ImuFactor inference. """ from __future__ import print_function import math -import gtsam import matplotlib.pyplot as plt import numpy as np -from gtsam import symbol_shorthand_B as B -from gtsam import symbol_shorthand_V as V -from gtsam import symbol_shorthand_X as X -from gtsam.utils.plot import plot_pose3 from mpl_toolkits.mplot3d import Axes3D +import gtsam +from gtsam.utils.plot import plot_pose3 from PreintegrationExample import POSES_FIG, PreintegrationExample -BIAS_KEY = B(0) +BIAS_KEY = int(gtsam.symbol('b', 0)) + + +def X(key): + """Create symbol for pose key.""" + return gtsam.symbol('x', key) + + +def V(key): + """Create symbol for velocity key.""" + return gtsam.symbol('v', key) np.set_printoptions(precision=3, suppress=True) @@ -35,8 +40,8 @@ class ImuFactorExample(PreintegrationExample): def __init__(self): self.velocity = np.array([2, 0, 0]) - self.priorNoise = gtsam.noiseModel_Isotropic.Sigma(6, 0.1) - self.velNoise = gtsam.noiseModel_Isotropic.Sigma(3, 0.1) + self.priorNoise = gtsam.noiseModel.Isotropic.Sigma(6, 0.1) + self.velNoise = gtsam.noiseModel.Isotropic.Sigma(3, 0.1) # Choose one of these twists to change scenario: zero_twist = (np.zeros(3), np.zeros(3)) @@ -47,7 +52,7 @@ class ImuFactorExample(PreintegrationExample): accBias = np.array([-0.3, 0.1, 0.2]) gyroBias = np.array([0.1, 0.3, -0.1]) - bias = gtsam.imuBias_ConstantBias(accBias, gyroBias) + bias = gtsam.imuBias.ConstantBias(accBias, gyroBias) dt = 1e-2 super(ImuFactorExample, self).__init__(sick_twist, bias, dt) @@ -71,14 +76,8 @@ class ImuFactorExample(PreintegrationExample): initial.insert(BIAS_KEY, self.actualBias) for i in range(num_poses): state_i = self.scenario.navState(float(i)) - - poseNoise = gtsam.Pose3.Expmap(np.random.randn(3)*0.1) - pose = state_i.pose().compose(poseNoise) - - velocity = state_i.velocity() + np.random.randn(3)*0.1 - - initial.insert(X(i), pose) - initial.insert(V(i), velocity) + initial.insert(X(i), state_i.pose()) + initial.insert(V(i), state_i.velocity()) # simulate the loop i = 0 # state index @@ -89,12 +88,6 @@ class ImuFactorExample(PreintegrationExample): measuredAcc = self.runner.measuredSpecificForce(t) pim.integrateMeasurement(measuredAcc, measuredOmega, self.dt) - poseNoise = gtsam.Pose3.Expmap(np.random.randn(3)*0.1) - - actual_state_i = gtsam.NavState( - actual_state_i.pose().compose(poseNoise), - actual_state_i.velocity() + np.random.randn(3)*0.1) - # Plot IMU many times if k % 10 == 0: self.plotImu(t, measuredOmega, measuredAcc) @@ -140,10 +133,7 @@ class ImuFactorExample(PreintegrationExample): pose_i = result.atPose3(X(i)) plot_pose3(POSES_FIG, pose_i, 0.1) i += 1 - - gtsam.utils.plot.set_axes_equal(POSES_FIG) - - print(result.atimuBias_ConstantBias(BIAS_KEY)) + print(result.atimuBias.ConstantBias(BIAS_KEY)) plt.ioff() plt.show() diff --git a/python/gtsam_py/python/examples/ImuFactorExample2.py b/python/gtsam_py/python/examples/ImuFactorExample2.py index 0d98f08fe..39e22eb17 100644 --- a/python/gtsam_py/python/examples/ImuFactorExample2.py +++ b/python/gtsam_py/python/examples/ImuFactorExample2.py @@ -8,20 +8,23 @@ from __future__ import print_function import math -import gtsam -import gtsam.utils.plot as gtsam_plot import matplotlib.pyplot as plt import numpy as np -from gtsam import (ISAM2, BetweenFactorConstantBias, Cal3_S2, - ConstantTwistScenario, ImuFactor, NonlinearFactorGraph, - PinholeCameraCal3_S2, Point3, Pose3, - PriorFactorConstantBias, PriorFactorPose3, - PriorFactorVector, Rot3, Values) -from gtsam import symbol_shorthand_B as B -from gtsam import symbol_shorthand_V as V -from gtsam import symbol_shorthand_X as X from mpl_toolkits.mplot3d import Axes3D # pylint: disable=W0611 +import gtsam +import gtsam.utils.plot as gtsam_plot + + +def X(key): + """Create symbol for pose key.""" + return gtsam.symbol('x', key) + + +def V(key): + """Create symbol for velocity key.""" + return gtsam.symbol('v', key) + def vector3(x, y, z): """Create 3d double numpy array.""" @@ -40,7 +43,7 @@ def ISAM2_plot(values, fignum=0): while values.exists(X(i)): pose_i = values.atPose3(X(i)) gtsam_plot.plot_pose3(fignum, pose_i, 10) - position = pose_i.translation().vector() + position = pose_i.translation() min_bounds = [min(v1, v2) for (v1, v2) in zip(position, min_bounds)] max_bounds = [max(v1, v2) for (v1, v2) in zip(position, max_bounds)] # max_bounds = min(pose_i.x(), max_bounds[0]), 0, 0 @@ -65,20 +68,21 @@ PARAMS.setIntegrationCovariance(I * 0.1) PARAMS.setUse2ndOrderCoriolis(False) PARAMS.setOmegaCoriolis(vector3(0, 0, 0)) -BIAS_COVARIANCE = gtsam.noiseModel_Isotropic.Variance(6, 0.1) -DELTA = Pose3(Rot3.Rodrigues(0, 0, 0), - Point3(0.05, -0.10, 0.20)) +BIAS_COVARIANCE = gtsam.noiseModel.Isotropic.Variance(6, 0.1) +DELTA = gtsam.Pose3(gtsam.Rot3.Rodrigues(0, 0, 0), + gtsam.Point3(0.05, -0.10, 0.20)) def IMU_example(): """Run iSAM 2 example with IMU factor.""" + ZERO_BIAS = gtsam.imuBias.ConstantBias() # Start with a camera on x-axis looking at origin radius = 30 - up = Point3(0, 0, 1) - target = Point3(0, 0, 0) - position = Point3(radius, 0, 0) - camera = PinholeCameraCal3_S2.Lookat(position, target, up, Cal3_S2()) + up = gtsam.Point3(0, 0, 1) + target = gtsam.Point3(0, 0, 0) + position = gtsam.Point3(radius, 0, 0) + camera = gtsam.SimpleCamera.Lookat(position, target, up, gtsam.Cal3_S2()) pose_0 = camera.pose() # Create the set of ground-truth landmarks and poses @@ -87,37 +91,37 @@ def IMU_example(): angular_velocity_vector = vector3(0, -angular_velocity, 0) linear_velocity_vector = vector3(radius * angular_velocity, 0, 0) - scenario = ConstantTwistScenario( + scenario = gtsam.ConstantTwistScenario( angular_velocity_vector, linear_velocity_vector, pose_0) # Create a factor graph - newgraph = NonlinearFactorGraph() + newgraph = gtsam.NonlinearFactorGraph() # Create (incremental) ISAM2 solver - isam = ISAM2() + isam = gtsam.ISAM2() # Create the initial estimate to the solution # Intentionally initialize the variables off from the ground truth - initialEstimate = Values() + initialEstimate = gtsam.Values() # Add a prior on pose x0. This indirectly specifies where the origin is. # 30cm std on x,y,z 0.1 rad on roll,pitch,yaw - noise = gtsam.noiseModel_Diagonal.Sigmas( + noise = gtsam.noiseModel.Diagonal.Sigmas( np.array([0.1, 0.1, 0.1, 0.3, 0.3, 0.3])) - newgraph.push_back(PriorFactorPose3(X(0), pose_0, noise)) + newgraph.push_back(gtsam.PriorFactorPose3(X(0), pose_0, noise)) # Add imu priors - biasKey = B(0) - biasnoise = gtsam.noiseModel_Isotropic.Sigma(6, 0.1) - biasprior = PriorFactorConstantBias(biasKey, gtsam.imuBias_ConstantBias(), - biasnoise) + biasKey = gtsam.symbol('b', 0) + biasnoise = gtsam.noiseModel.Isotropic.Sigma(6, 0.1) + biasprior = gtsam.PriorFactorConstantBias(biasKey, ZERO_BIAS, + biasnoise) newgraph.push_back(biasprior) - initialEstimate.insert(biasKey, gtsam.imuBias_ConstantBias()) - velnoise = gtsam.noiseModel_Isotropic.Sigma(3, 0.1) + initialEstimate.insert(biasKey, ZERO_BIAS) + velnoise = gtsam.noiseModel.Isotropic.Sigma(3, 0.1) # Calculate with correct initial velocity n_velocity = vector3(0, angular_velocity * radius, 0) - velprior = PriorFactorVector(V(0), n_velocity, velnoise) + velprior = gtsam.PriorFactorVector(V(0), n_velocity, velnoise) newgraph.push_back(velprior) initialEstimate.insert(V(0), n_velocity) @@ -138,10 +142,10 @@ def IMU_example(): # Add Bias variables periodically if i % 5 == 0: biasKey += 1 - factor = BetweenFactorConstantBias( - biasKey - 1, biasKey, gtsam.imuBias_ConstantBias(), BIAS_COVARIANCE) + factor = gtsam.BetweenFactorConstantBias( + biasKey - 1, biasKey, ZERO_BIAS, BIAS_COVARIANCE) newgraph.add(factor) - initialEstimate.insert(biasKey, gtsam.imuBias_ConstantBias()) + initialEstimate.insert(biasKey, ZERO_BIAS) # Predict acceleration and gyro measurements in (actual) body frame nRb = scenario.rotation(t).matrix() @@ -151,7 +155,8 @@ def IMU_example(): accum.integrateMeasurement(measuredAcc, measuredOmega, delta_t) # Add Imu Factor - imufac = ImuFactor(X(i - 1), V(i - 1), X(i), V(i), biasKey, accum) + imufac = gtsam.ImuFactor( + X(i - 1), V(i - 1), X(i), V(i), biasKey, accum) newgraph.add(imufac) # insert new velocity, which is wrong @@ -164,7 +169,7 @@ def IMU_example(): ISAM2_plot(result) # reset - newgraph = NonlinearFactorGraph() + newgraph = gtsam.NonlinearFactorGraph() initialEstimate.clear() diff --git a/python/gtsam_py/python/examples/OdometryExample.py b/python/gtsam_py/python/examples/OdometryExample.py index e778e3f85..8b519ce9a 100644 --- a/python/gtsam_py/python/examples/OdometryExample.py +++ b/python/gtsam_py/python/examples/OdometryExample.py @@ -21,8 +21,8 @@ import matplotlib.pyplot as plt import gtsam.utils.plot as gtsam_plot # Create noise models -ODOMETRY_NOISE = gtsam.noiseModel_Diagonal.Sigmas(np.array([0.2, 0.2, 0.1])) -PRIOR_NOISE = gtsam.noiseModel_Diagonal.Sigmas(np.array([0.3, 0.3, 0.1])) +ODOMETRY_NOISE = gtsam.noiseModel.Diagonal.Sigmas(np.array([0.2, 0.2, 0.1])) +PRIOR_NOISE = gtsam.noiseModel.Diagonal.Sigmas(np.array([0.3, 0.3, 0.1])) # Create an empty nonlinear factor graph graph = gtsam.NonlinearFactorGraph() diff --git a/python/gtsam_py/python/examples/PlanarManipulatorExample.py b/python/gtsam_py/python/examples/PlanarManipulatorExample.py index e42ae09d7..9af4f7fcc 100644 --- a/python/gtsam_py/python/examples/PlanarManipulatorExample.py +++ b/python/gtsam_py/python/examples/PlanarManipulatorExample.py @@ -167,13 +167,11 @@ class ThreeLinkArm(object): axes = fig.gca() sXl1 = Pose2(0, 0, math.radians(90)) - t = sXl1.translation() - p1 = np.array([t.x(), t.y()]) + p1 = sXl1.translation() gtsam_plot.plot_pose2_on_axes(axes, sXl1) def plot_line(p, g, color): - t = g.translation() - q = np.array([t.x(), t.y()]) + q = g.translation() line = np.append(p[np.newaxis], q[np.newaxis], axis=0) axes.plot(line[:, 0], line[:, 1], color) return q diff --git a/python/gtsam_py/python/examples/PlanarSLAMExample.py b/python/gtsam_py/python/examples/PlanarSLAMExample.py index c84f0f834..0baf2fa9a 100644 --- a/python/gtsam_py/python/examples/PlanarSLAMExample.py +++ b/python/gtsam_py/python/examples/PlanarSLAMExample.py @@ -13,25 +13,24 @@ Author: Alex Cunningham (C++), Kevin Deng & Frank Dellaert (Python) from __future__ import print_function -import gtsam import numpy as np -from gtsam import symbol_shorthand_L as L -from gtsam import symbol_shorthand_X as X + +import gtsam # Create noise models -PRIOR_NOISE = gtsam.noiseModel_Diagonal.Sigmas(np.array([0.3, 0.3, 0.1])) -ODOMETRY_NOISE = gtsam.noiseModel_Diagonal.Sigmas(np.array([0.2, 0.2, 0.1])) -MEASUREMENT_NOISE = gtsam.noiseModel_Diagonal.Sigmas(np.array([0.1, 0.2])) +PRIOR_NOISE = gtsam.noiseModel.Diagonal.Sigmas(np.array([0.3, 0.3, 0.1])) +ODOMETRY_NOISE = gtsam.noiseModel.Diagonal.Sigmas(np.array([0.2, 0.2, 0.1])) +MEASUREMENT_NOISE = gtsam.noiseModel.Diagonal.Sigmas(np.array([0.1, 0.2])) # Create an empty nonlinear factor graph graph = gtsam.NonlinearFactorGraph() # Create the keys corresponding to unknown variables in the factor graph -X1 = X(1) -X2 = X(2) -X3 = X(3) -L1 = L(4) -L2 = L(5) +X1 = gtsam.symbol('x', 1) +X2 = gtsam.symbol('x', 2) +X3 = gtsam.symbol('x', 3) +L1 = gtsam.symbol('l', 4) +L2 = gtsam.symbol('l', 5) # Add a prior on pose X1 at the origin. A prior factor consists of a mean and a noise model graph.add(gtsam.PriorFactorPose2(X1, gtsam.Pose2(0.0, 0.0, 0.0), PRIOR_NOISE)) diff --git a/python/gtsam_py/python/examples/Pose2SLAMExample.py b/python/gtsam_py/python/examples/Pose2SLAMExample.py index 680f2209f..686da4db3 100644 --- a/python/gtsam_py/python/examples/Pose2SLAMExample.py +++ b/python/gtsam_py/python/examples/Pose2SLAMExample.py @@ -29,8 +29,8 @@ def vector3(x, y, z): # Create noise models -PRIOR_NOISE = gtsam.noiseModel_Diagonal.Sigmas(vector3(0.3, 0.3, 0.1)) -ODOMETRY_NOISE = gtsam.noiseModel_Diagonal.Sigmas(vector3(0.2, 0.2, 0.1)) +PRIOR_NOISE = gtsam.noiseModel.Diagonal.Sigmas(vector3(0.3, 0.3, 0.1)) +ODOMETRY_NOISE = gtsam.noiseModel.Diagonal.Sigmas(vector3(0.2, 0.2, 0.1)) # 1. Create a factor graph container and add factors to it graph = gtsam.NonlinearFactorGraph() diff --git a/python/gtsam_py/python/examples/Pose2SLAMExample_g2o.py b/python/gtsam_py/python/examples/Pose2SLAMExample_g2o.py index 09114370d..d27adfc2c 100644 --- a/python/gtsam_py/python/examples/Pose2SLAMExample_g2o.py +++ b/python/gtsam_py/python/examples/Pose2SLAMExample_g2o.py @@ -53,15 +53,16 @@ graph, initial = gtsam.readG2o(g2oFile, is3D) assert args.kernel == "none", "Supplied kernel type is not yet implemented" # Add prior on the pose having index (key) = 0 -priorModel = gtsam.noiseModel_Diagonal.Variances(vector3(1e-6, 1e-6, 1e-8)) -graph.add(gtsam.PriorFactorPose2(0, gtsam.Pose2(), priorModel)) +graphWithPrior = graph +priorModel = gtsam.noiseModel.Diagonal.Variances(vector3(1e-6, 1e-6, 1e-8)) +graphWithPrior.add(gtsam.PriorFactorPose2(0, gtsam.Pose2(), priorModel)) params = gtsam.GaussNewtonParams() params.setVerbosity("Termination") params.setMaxIterations(maxIterations) # parameters.setRelativeErrorTol(1e-5) # Create the optimizer ... -optimizer = gtsam.GaussNewtonOptimizer(graph, initial, params) +optimizer = gtsam.GaussNewtonOptimizer(graphWithPrior, initial, params) # ... and optimize result = optimizer.optimize() @@ -82,7 +83,7 @@ else: print ("Done!") if args.plot: - resultPoses = gtsam.utilities_extractPose2(result) + resultPoses = gtsam.extractPose2(result) for i in range(resultPoses.shape[0]): plot.plot_pose2(1, gtsam.Pose2(resultPoses[i, :])) plt.show() diff --git a/python/gtsam_py/python/examples/Pose3SLAMExample_g2o.py b/python/gtsam_py/python/examples/Pose3SLAMExample_g2o.py index 3c1a54f7b..20b02500e 100644 --- a/python/gtsam_py/python/examples/Pose3SLAMExample_g2o.py +++ b/python/gtsam_py/python/examples/Pose3SLAMExample_g2o.py @@ -39,21 +39,22 @@ is3D = True graph, initial = gtsam.readG2o(g2oFile, is3D) # Add Prior on the first key -priorModel = gtsam.noiseModel_Diagonal.Variances(vector6(1e-6, 1e-6, 1e-6, +priorModel = gtsam.noiseModel.Diagonal.Variances(vector6(1e-6, 1e-6, 1e-6, 1e-4, 1e-4, 1e-4)) print("Adding prior to g2o file ") +graphWithPrior = graph firstKey = initial.keys().at(0) -graph.add(gtsam.PriorFactorPose3(firstKey, gtsam.Pose3(), priorModel)) +graphWithPrior.add(gtsam.PriorFactorPose3(firstKey, gtsam.Pose3(), priorModel)) params = gtsam.GaussNewtonParams() params.setVerbosity("Termination") # this will show info about stopping conds -optimizer = gtsam.GaussNewtonOptimizer(graph, initial, params) +optimizer = gtsam.GaussNewtonOptimizer(graphWithPrior, initial, params) result = optimizer.optimize() print("Optimization complete") -print("initial error = ", graph.error(initial)) -print("final error = ", graph.error(result)) +print("initial error = ", graphWithPrior.error(initial)) +print("final error = ", graphWithPrior.error(result)) if args.output is None: print("Final Result:\n{}".format(result)) @@ -65,7 +66,7 @@ else: print ("Done!") if args.plot: - resultPoses = gtsam.utilities_allPose3s(result) + resultPoses = gtsam.allPose3s(result) for i in range(resultPoses.size()): plot.plot_pose3(1, resultPoses.atPose3(i)) plt.show() diff --git a/python/gtsam_py/python/examples/Pose3SLAMExample_initializePose3Chordal.py b/python/gtsam_py/python/examples/Pose3SLAMExample_initializePose3Chordal.py index 02c696905..140669c95 100644 --- a/python/gtsam_py/python/examples/Pose3SLAMExample_initializePose3Chordal.py +++ b/python/gtsam_py/python/examples/Pose3SLAMExample_initializePose3Chordal.py @@ -24,7 +24,7 @@ is3D = True graph, initial = gtsam.readG2o(g2oFile, is3D) # Add prior on the first key. TODO: assumes first key ios z -priorModel = gtsam.noiseModel_Diagonal.Variances( +priorModel = gtsam.noiseModel.Diagonal.Variances( np.array([1e-6, 1e-6, 1e-6, 1e-4, 1e-4, 1e-4])) firstKey = initial.keys().at(0) graph.add(gtsam.PriorFactorPose3(0, gtsam.Pose3(), priorModel)) diff --git a/python/gtsam_py/python/examples/PreintegrationExample.py b/python/gtsam_py/python/examples/PreintegrationExample.py index 76520b355..e543e5d82 100644 --- a/python/gtsam_py/python/examples/PreintegrationExample.py +++ b/python/gtsam_py/python/examples/PreintegrationExample.py @@ -68,7 +68,7 @@ class PreintegrationExample(object): else: accBias = np.array([0, 0.1, 0]) gyroBias = np.array([0, 0, 0]) - self.actualBias = gtsam.imuBias_ConstantBias(accBias, gyroBias) + self.actualBias = gtsam.imuBias.ConstantBias(accBias, gyroBias) self.runner = gtsam.ScenarioRunner( self.scenario, self.params, self.dt, self.actualBias) @@ -111,7 +111,7 @@ class PreintegrationExample(object): actualPose = self.scenario.pose(t) plot_pose3(POSES_FIG, actualPose, 0.3) t = actualPose.translation() - self.maxDim = max([abs(t.x()), abs(t.y()), abs(t.z()), self.maxDim]) + self.maxDim = max([max(t), self.maxDim]) ax = plt.gca() ax.set_xlim3d(-self.maxDim, self.maxDim) ax.set_ylim3d(-self.maxDim, self.maxDim) diff --git a/python/gtsam_py/python/examples/README.md b/python/gtsam_py/python/examples/README.md index 99bce00e2..ec4437d4c 100644 --- a/python/gtsam_py/python/examples/README.md +++ b/python/gtsam_py/python/examples/README.md @@ -1,7 +1,8 @@ -These examples are almost identical to the old handwritten python wrapper -examples. However, there are just some slight name changes, for example -`noiseModel.Diagonal` becomes `noiseModel_Diagonal` etc... -Also, instead of `gtsam.Symbol('b', 0)` we can simply say `gtsam.symbol_shorthand_B(0)` or `B(0)` if we use python aliasing. +# THIS FILE IS OUTDATED! + +~~These examples are almost identical to the old handwritten python wrapper examples. However, there are just some slight name changes, for example `noiseModel.Diagonal` becomes `noiseModel.Diagonal` etc...~~ + +~~Also, annoyingly, instead of `gtsam.Symbol('b', 0)` we now need to say `gtsam.symbol('b', 0))`~~ # Porting Progress diff --git a/python/gtsam_py/python/examples/SFMExample.py b/python/gtsam_py/python/examples/SFMExample.py index e02def2f9..0c03a105d 100644 --- a/python/gtsam_py/python/examples/SFMExample.py +++ b/python/gtsam_py/python/examples/SFMExample.py @@ -10,20 +10,24 @@ A structure-from-motion problem on a simulated dataset """ from __future__ import print_function -import gtsam import matplotlib.pyplot as plt import numpy as np -from gtsam import symbol_shorthand_L as L -from gtsam import symbol_shorthand_X as X + +import gtsam from gtsam.examples import SFMdata from gtsam.gtsam import (Cal3_S2, DoglegOptimizer, GenericProjectionFactorCal3_S2, Marginals, - NonlinearFactorGraph, PinholeCameraCal3_S2, Point3, - Pose3, PriorFactorPoint3, PriorFactorPose3, Rot3, + NonlinearFactorGraph, Point3, Pose3, + PriorFactorPoint3, PriorFactorPose3, Rot3, SimpleCamera, Values) from gtsam.utils import plot +def symbol(name: str, index: int) -> int: + """ helper for creating a symbol without explicitly casting 'name' from str to int """ + return gtsam.symbol(name, index) + + def main(): """ Camera observations of landmarks (i.e. pixel coordinates) will be stored as Point2 (x, y). @@ -56,7 +60,7 @@ def main(): K = Cal3_S2(50.0, 50.0, 0.0, 50.0, 50.0) # Define the camera observation noise model - measurement_noise = gtsam.noiseModel_Isotropic.Sigma(2, 1.0) # one pixel in u and v + measurement_noise = gtsam.noiseModel.Isotropic.Sigma(2, 1.0) # one pixel in u and v # Create the set of ground-truth landmarks points = SFMdata.createPoints() @@ -69,24 +73,24 @@ def main(): # Add a prior on pose x1. This indirectly specifies where the origin is. # 0.3 rad std on roll,pitch,yaw and 0.1m on x,y,z - pose_noise = gtsam.noiseModel_Diagonal.Sigmas(np.array([0.3, 0.3, 0.3, 0.1, 0.1, 0.1])) - factor = PriorFactorPose3(X(0), poses[0], pose_noise) + pose_noise = gtsam.noiseModel.Diagonal.Sigmas(np.array([0.3, 0.3, 0.3, 0.1, 0.1, 0.1])) + factor = PriorFactorPose3(symbol('x', 0), poses[0], pose_noise) graph.push_back(factor) # Simulated measurements from each camera pose, adding them to the factor graph for i, pose in enumerate(poses): - camera = PinholeCameraCal3_S2(pose, K) + camera = SimpleCamera(pose, K) for j, point in enumerate(points): measurement = camera.project(point) factor = GenericProjectionFactorCal3_S2( - measurement, measurement_noise, X(i), L(j), K) + measurement, measurement_noise, symbol('x', i), symbol('l', j), K) graph.push_back(factor) # Because the structure-from-motion problem has a scale ambiguity, the problem is still under-constrained # Here we add a prior on the position of the first landmark. This fixes the scale by indicating the distance # between the first camera and the first landmark. All other landmark positions are interpreted using this scale. - point_noise = gtsam.noiseModel_Isotropic.Sigma(3, 0.1) - factor = PriorFactorPoint3(L(0), points[0], point_noise) + point_noise = gtsam.noiseModel.Isotropic.Sigma(3, 0.1) + factor = PriorFactorPoint3(symbol('l', 0), points[0], point_noise) graph.push_back(factor) graph.print_('Factor Graph:\n') @@ -95,10 +99,10 @@ def main(): initial_estimate = Values() for i, pose in enumerate(poses): transformed_pose = pose.retract(0.1*np.random.randn(6,1)) - initial_estimate.insert(X(i), transformed_pose) + initial_estimate.insert(symbol('x', i), transformed_pose) for j, point in enumerate(points): transformed_point = Point3(point.vector() + 0.1*np.random.randn(3)) - initial_estimate.insert(L(j), transformed_point) + initial_estimate.insert(symbol('l', j), transformed_point) initial_estimate.print_('Initial Estimates:\n') # Optimize the graph and print results @@ -117,5 +121,6 @@ def main(): plot.set_axes_equal(1) plt.show() + if __name__ == '__main__': main() diff --git a/python/gtsam_py/python/examples/SFMdata.py b/python/gtsam_py/python/examples/SFMdata.py index c586f7e52..6ac9c5726 100644 --- a/python/gtsam_py/python/examples/SFMdata.py +++ b/python/gtsam_py/python/examples/SFMdata.py @@ -33,7 +33,8 @@ def createPoses(K): poses = [] for theta in angles: position = gtsam.Point3(radius*np.cos(theta), - radius*np.sin(theta), height) + radius*np.sin(theta), + height) camera = gtsam.PinholeCameraCal3_S2.Lookat(position, target, up, K) poses.append(camera.pose()) return poses diff --git a/python/gtsam_py/python/examples/SimpleRotation.py b/python/gtsam_py/python/examples/SimpleRotation.py index 4e82d3778..2dd7b1194 100644 --- a/python/gtsam_py/python/examples/SimpleRotation.py +++ b/python/gtsam_py/python/examples/SimpleRotation.py @@ -10,9 +10,8 @@ This example will perform a relatively trivial optimization on a single variable with a single factor. """ -import gtsam import numpy as np -from gtsam import symbol_shorthand_X as X +import gtsam def main(): @@ -33,8 +32,8 @@ def main(): """ prior = gtsam.Rot2.fromAngle(np.deg2rad(30)) prior.print_('goal angle') - model = gtsam.noiseModel_Isotropic.Sigma(dim=1, sigma=np.deg2rad(1)) - key = X(1) + model = gtsam.noiseModel.Isotropic.Sigma(dim=1, sigma=np.deg2rad(1)) + key = gtsam.symbol('x', 1) factor = gtsam.PriorFactorRot2(key, prior, model) """ diff --git a/python/gtsam_py/python/examples/VisualISAM2Example.py b/python/gtsam_py/python/examples/VisualISAM2Example.py index 49e6ca95c..d33ec98bf 100644 --- a/python/gtsam_py/python/examples/VisualISAM2Example.py +++ b/python/gtsam_py/python/examples/VisualISAM2Example.py @@ -13,15 +13,24 @@ Author: Duy-Nguyen Ta (C++), Frank Dellaert (Python) from __future__ import print_function -import gtsam -import gtsam.utils.plot as gtsam_plot import matplotlib.pyplot as plt import numpy as np -from gtsam import symbol_shorthand_L as L -from gtsam import symbol_shorthand_X as X -from gtsam.examples import SFMdata from mpl_toolkits.mplot3d import Axes3D # pylint: disable=W0611 +import gtsam +import gtsam.utils.plot as gtsam_plot +from gtsam.examples import SFMdata + + +def X(i): + """Create key for pose i.""" + return int(gtsam.symbol('x', i)) + + +def L(j): + """Create key for landmark j.""" + return int(gtsam.symbol('l', j)) + def visual_ISAM2_plot(result): """ @@ -64,7 +73,7 @@ def visual_ISAM2_example(): K = gtsam.Cal3_S2(50.0, 50.0, 0.0, 50.0, 50.0) # Define the camera observation noise model - measurement_noise = gtsam.noiseModel_Isotropic.Sigma( + measurement_noise = gtsam.noiseModel.Isotropic.Sigma( 2, 1.0) # one pixel in u and v # Create the set of ground-truth landmarks @@ -110,12 +119,12 @@ def visual_ISAM2_example(): # at least twice before adding it to iSAM. if i == 0: # Add a prior on pose x0 - pose_noise = gtsam.noiseModel_Diagonal.Sigmas(np.array( + pose_noise = gtsam.noiseModel.Diagonal.Sigmas(np.array( [0.1, 0.1, 0.1, 0.3, 0.3, 0.3])) # 30cm std on x,y,z 0.1 rad on roll,pitch,yaw graph.push_back(gtsam.PriorFactorPose3(X(0), poses[0], pose_noise)) # Add a prior on landmark l0 - point_noise = gtsam.noiseModel_Isotropic.Sigma(3, 0.1) + point_noise = gtsam.noiseModel.Isotropic.Sigma(3, 0.1) graph.push_back(gtsam.PriorFactorPoint3( L(0), points[0], point_noise)) # add directly to graph @@ -123,7 +132,7 @@ def visual_ISAM2_example(): # Intentionally initialize the variables off from the ground truth for j, point in enumerate(points): initial_estimate.insert(L(j), gtsam.Point3( - point.x()-0.25, point.y()+0.20, point.z()+0.15)) + point[0]-0.25, point[1]+0.20, point[2]+0.15)) else: # Update iSAM with the new factors isam.update(graph, initial_estimate) diff --git a/python/gtsam_py/python/examples/VisualISAMExample.py b/python/gtsam_py/python/examples/VisualISAMExample.py index 5cc37867b..2e90ce21b 100644 --- a/python/gtsam_py/python/examples/VisualISAMExample.py +++ b/python/gtsam_py/python/examples/VisualISAMExample.py @@ -15,12 +15,15 @@ from __future__ import print_function import numpy as np import gtsam from gtsam.examples import SFMdata -from gtsam.gtsam import (Cal3_S2, GenericProjectionFactorCal3_S2, - NonlinearFactorGraph, NonlinearISAM, Point3, Pose3, +from gtsam import (Cal3_S2, GenericProjectionFactorCal3_S2, + NonlinearFactorGraph, NonlinearISAM, Pose3, PriorFactorPoint3, PriorFactorPose3, Rot3, - PinholeCameraCal3_S2, Values) -from gtsam import symbol_shorthand_L as L -from gtsam import symbol_shorthand_X as X + SimpleCamera, Values, Point3) + + +def symbol(name: str, index: int) -> int: + """ helper for creating a symbol without explicitly casting 'name' from str to int """ + return gtsam.symbol(name, index) def main(): @@ -34,7 +37,7 @@ def main(): K = Cal3_S2(50.0, 50.0, 0.0, 50.0, 50.0) # Define the camera observation noise model - camera_noise = gtsam.noiseModel_Isotropic.Sigma(2, 1.0) # one pixel in u and v + camera_noise = gtsam.noiseModel.Isotropic.Sigma(2, 1.0) # one pixel in u and v # Create the set of ground-truth landmarks points = SFMdata.createPoints() @@ -51,11 +54,11 @@ def main(): # Loop over the different poses, adding the observations to iSAM incrementally for i, pose in enumerate(poses): - camera = PinholeCameraCal3_S2(pose, K) + camera = SimpleCamera(pose, K) # Add factors for each landmark observation for j, point in enumerate(points): measurement = camera.project(point) - factor = GenericProjectionFactorCal3_S2(measurement, camera_noise, X(i), L(j), K) + factor = GenericProjectionFactorCal3_S2(measurement, camera_noise, symbol('x', i), symbol('l', j), K) graph.push_back(factor) # Intentionally initialize the variables off from the ground truth @@ -63,7 +66,7 @@ def main(): initial_xi = pose.compose(noise) # Add an initial guess for the current pose - initial_estimate.insert(X(i), initial_xi) + initial_estimate.insert(symbol('x', i), initial_xi) # If this is the first iteration, add a prior on the first pose to set the coordinate frame # and a prior on the first landmark to set the scale @@ -71,21 +74,21 @@ def main(): # adding it to iSAM. if i == 0: # Add a prior on pose x0, with 0.3 rad std on roll,pitch,yaw and 0.1m x,y,z - pose_noise = gtsam.noiseModel_Diagonal.Sigmas(np.array([0.3, 0.3, 0.3, 0.1, 0.1, 0.1])) - factor = PriorFactorPose3(X(0), poses[0], pose_noise) + pose_noise = gtsam.noiseModel.Diagonal.Sigmas(np.array([0.3, 0.3, 0.3, 0.1, 0.1, 0.1])) + factor = PriorFactorPose3(symbol('x', 0), poses[0], pose_noise) graph.push_back(factor) # Add a prior on landmark l0 - point_noise = gtsam.noiseModel_Isotropic.Sigma(3, 0.1) - factor = PriorFactorPoint3(L(0), points[0], point_noise) + point_noise = gtsam.noiseModel.Isotropic.Sigma(3, 0.1) + factor = PriorFactorPoint3(symbol('l', 0), points[0], point_noise) graph.push_back(factor) # Add initial guesses to all observed landmarks noise = np.array([-0.25, 0.20, 0.15]) for j, point in enumerate(points): # Intentionally initialize the variables off from the ground truth - initial_lj = points[j].vector() + noise - initial_estimate.insert(L(j), Point3(initial_lj)) + initial_lj = points[j] + noise + initial_estimate.insert(symbol('l', j), initial_lj) else: # Update iSAM with the new factors isam.update(graph, initial_estimate) diff --git a/python/gtsam_py/python/tests/__init__.py b/python/gtsam_py/python/tests/__init__.py deleted file mode 100644 index e69de29bb..000000000 diff --git a/python/gtsam_py/python/tests/testScenarioRunner.py b/python/gtsam_py/python/tests/testScenarioRunner.py index 97a97b0ec..2af16a794 100644 --- a/python/gtsam_py/python/tests/testScenarioRunner.py +++ b/python/gtsam_py/python/tests/testScenarioRunner.py @@ -32,7 +32,7 @@ class TestScenarioRunner(GtsamTestCase): dt = 0.1 params = gtsam.PreintegrationParams.MakeSharedU(self.g) - bias = gtsam.imuBias_ConstantBias() + bias = gtsam.imuBias.ConstantBias() runner = gtsam.ScenarioRunner( scenario, params, dt, bias) diff --git a/python/gtsam_py/python/tests/test_GaussianFactorGraph.py b/python/gtsam_py/python/tests/test_GaussianFactorGraph.py index 983825d8b..759de0f3b 100644 --- a/python/gtsam_py/python/tests/test_GaussianFactorGraph.py +++ b/python/gtsam_py/python/tests/test_GaussianFactorGraph.py @@ -15,21 +15,20 @@ from __future__ import print_function import unittest import gtsam -import numpy as np -from gtsam import symbol_shorthand_X as X from gtsam.utils.test_case import GtsamTestCase +import numpy as np def create_graph(): """Create a basic linear factor graph for testing""" graph = gtsam.GaussianFactorGraph() - x0 = X(0) - x1 = X(1) - x2 = X(2) + x0 = gtsam.symbol('x', 0) + x1 = gtsam.symbol('x', 1) + x2 = gtsam.symbol('x', 2) - BETWEEN_NOISE = gtsam.noiseModel_Diagonal.Sigmas(np.ones(1)) - PRIOR_NOISE = gtsam.noiseModel_Diagonal.Sigmas(np.ones(1)) + BETWEEN_NOISE = gtsam.noiseModel.Diagonal.Sigmas(np.ones(1)) + PRIOR_NOISE = gtsam.noiseModel.Diagonal.Sigmas(np.ones(1)) graph.add(x1, np.eye(1), x0, -np.eye(1), np.ones(1), BETWEEN_NOISE) graph.add(x2, np.eye(1), x1, -np.eye(1), 2*np.ones(1), BETWEEN_NOISE) diff --git a/python/gtsam_py/python/tests/test_JacobianFactor.py b/python/gtsam_py/python/tests/test_JacobianFactor.py index 04433492b..6e049ed47 100644 --- a/python/gtsam_py/python/tests/test_JacobianFactor.py +++ b/python/gtsam_py/python/tests/test_JacobianFactor.py @@ -48,7 +48,7 @@ class TestJacobianFactor(GtsamTestCase): # the RHS b2 = np.array([-1., 1.5, 2., -1.]) sigmas = np.array([1., 1., 1., 1.]) - model4 = gtsam.noiseModel_Diagonal.Sigmas(sigmas) + model4 = gtsam.noiseModel.Diagonal.Sigmas(sigmas) combined = gtsam.JacobianFactor(x2, Ax2, l1, Al1, x1, Ax1, b2, model4) # eliminate the first variable (x2) in the combined factor, destructive @@ -66,7 +66,7 @@ class TestJacobianFactor(GtsamTestCase): [+0.00, -8.94427]]) d = np.array([2.23607, -1.56525]) expectedCG = gtsam.GaussianConditional( - x2, d, R11, l1, S12, x1, S13, gtsam.noiseModel_Unit.Create(2)) + x2, d, R11, l1, S12, x1, S13, gtsam.noiseModel.Unit.Create(2)) # check if the result matches self.gtsamAssertEquals(actualCG, expectedCG, 1e-4) @@ -82,7 +82,7 @@ class TestJacobianFactor(GtsamTestCase): # the RHS b1 = np.array([0.0, 0.894427]) - model2 = gtsam.noiseModel_Diagonal.Sigmas(np.array([1., 1.])) + model2 = gtsam.noiseModel.Diagonal.Sigmas(np.array([1., 1.])) expectedLF = gtsam.JacobianFactor(l1, Bl1, x1, Bx1, b1, model2) # check if the result matches the combined (reduced) factor diff --git a/python/gtsam_py/python/tests/test_KalmanFilter.py b/python/gtsam_py/python/tests/test_KalmanFilter.py index 94c41df72..48a91b96c 100644 --- a/python/gtsam_py/python/tests/test_KalmanFilter.py +++ b/python/gtsam_py/python/tests/test_KalmanFilter.py @@ -22,13 +22,13 @@ class TestKalmanFilter(GtsamTestCase): F = np.eye(2) B = np.eye(2) u = np.array([1.0, 0.0]) - modelQ = gtsam.noiseModel_Diagonal.Sigmas(np.array([0.1, 0.1])) + modelQ = gtsam.noiseModel.Diagonal.Sigmas(np.array([0.1, 0.1])) Q = 0.01 * np.eye(2) H = np.eye(2) z1 = np.array([1.0, 0.0]) z2 = np.array([2.0, 0.0]) z3 = np.array([3.0, 0.0]) - modelR = gtsam.noiseModel_Diagonal.Sigmas(np.array([0.1, 0.1])) + modelR = gtsam.noiseModel.Diagonal.Sigmas(np.array([0.1, 0.1])) R = 0.01 * np.eye(2) # Create the set of expected output TestValues diff --git a/python/gtsam_py/python/tests/test_KarcherMeanFactor.py b/python/gtsam_py/python/tests/test_KarcherMeanFactor.py index 6976decc1..a315a506c 100644 --- a/python/gtsam_py/python/tests/test_KarcherMeanFactor.py +++ b/python/gtsam_py/python/tests/test_KarcherMeanFactor.py @@ -18,7 +18,7 @@ import numpy as np from gtsam.utils.test_case import GtsamTestCase KEY = 0 -MODEL = gtsam.noiseModel_Unit.Create(3) +MODEL = gtsam.noiseModel.Unit.Create(3) def find_Karcher_mean_Rot3(rotations): @@ -59,8 +59,8 @@ class TestKarcherMean(GtsamTestCase): R12 = R.compose(R.compose(R)) graph.add(gtsam.BetweenFactorRot3(1, 2, R12, MODEL)) keys = gtsam.KeyVector() - keys.push_back(1) - keys.push_back(2) + keys.append(1) + keys.append(2) graph.add(gtsam.KarcherMeanFactorRot3(keys)) initial = gtsam.Values() diff --git a/python/gtsam_py/python/tests/test_LocalizationExample.py b/python/gtsam_py/python/tests/test_LocalizationExample.py index 6ce65f087..8ae3583f0 100644 --- a/python/gtsam_py/python/tests/test_LocalizationExample.py +++ b/python/gtsam_py/python/tests/test_LocalizationExample.py @@ -26,7 +26,7 @@ class TestLocalizationExample(GtsamTestCase): # Add two odometry factors # create a measurement for both factors (the same in this case) odometry = gtsam.Pose2(2.0, 0.0, 0.0) - odometryNoise = gtsam.noiseModel_Diagonal.Sigmas( + odometryNoise = gtsam.noiseModel.Diagonal.Sigmas( np.array([0.2, 0.2, 0.1])) # 20cm std on x,y, 0.1 rad on theta graph.add(gtsam.BetweenFactorPose2(0, 1, odometry, odometryNoise)) graph.add(gtsam.BetweenFactorPose2(1, 2, odometry, odometryNoise)) @@ -37,7 +37,7 @@ class TestLocalizationExample(GtsamTestCase): groundTruth.insert(0, gtsam.Pose2(0.0, 0.0, 0.0)) groundTruth.insert(1, gtsam.Pose2(2.0, 0.0, 0.0)) groundTruth.insert(2, gtsam.Pose2(4.0, 0.0, 0.0)) - model = gtsam.noiseModel_Diagonal.Sigmas(np.array([0.1, 0.1, 10.])) + model = gtsam.noiseModel.Diagonal.Sigmas(np.array([0.1, 0.1, 10.])) for i in range(3): graph.add(gtsam.PriorFactorPose2(i, groundTruth.atPose2(i), model)) diff --git a/python/gtsam_py/python/tests/test_NonlinearOptimizer.py b/python/gtsam_py/python/tests/test_NonlinearOptimizer.py index 985dc30a2..3041e325c 100644 --- a/python/gtsam_py/python/tests/test_NonlinearOptimizer.py +++ b/python/gtsam_py/python/tests/test_NonlinearOptimizer.py @@ -17,8 +17,7 @@ import unittest import gtsam from gtsam import (DoglegOptimizer, DoglegParams, GaussNewtonOptimizer, GaussNewtonParams, LevenbergMarquardtOptimizer, - LevenbergMarquardtParams, PCGSolverParameters, - DummyPreconditionerParameters, NonlinearFactorGraph, Ordering, + LevenbergMarquardtParams, NonlinearFactorGraph, Ordering, Point2, PriorFactorPoint2, Values) from gtsam.utils.test_case import GtsamTestCase @@ -30,7 +29,7 @@ class TestScenario(GtsamTestCase): def test_optimize(self): """Do trivial test with three optimizer variants.""" fg = NonlinearFactorGraph() - model = gtsam.noiseModel_Unit.Create(2) + model = gtsam.noiseModel.Unit.Create(2) fg.add(PriorFactorPoint2(KEY1, Point2(0, 0), model)) # test error at minimum @@ -62,16 +61,6 @@ class TestScenario(GtsamTestCase): fg, initial_values, lmParams).optimize() self.assertAlmostEqual(0, fg.error(actual2)) - # Levenberg-Marquardt - lmParams = LevenbergMarquardtParams.CeresDefaults() - lmParams.setLinearSolverType("ITERATIVE") - cgParams = PCGSolverParameters() - cgParams.setPreconditionerParams(DummyPreconditionerParameters()) - lmParams.setIterativeParams(cgParams) - actual2 = LevenbergMarquardtOptimizer( - fg, initial_values, lmParams).optimize() - self.assertAlmostEqual(0, fg.error(actual2)) - # Dogleg dlParams = DoglegParams() dlParams.setOrdering(ordering) diff --git a/python/gtsam_py/python/tests/test_OdometryExample.py b/python/gtsam_py/python/tests/test_OdometryExample.py index c8ea95588..72e532f20 100644 --- a/python/gtsam_py/python/tests/test_OdometryExample.py +++ b/python/gtsam_py/python/tests/test_OdometryExample.py @@ -25,7 +25,7 @@ class TestOdometryExample(GtsamTestCase): # Add a Gaussian prior on pose x_1 priorMean = gtsam.Pose2(0.0, 0.0, 0.0) # prior mean is at origin - priorNoise = gtsam.noiseModel_Diagonal.Sigmas( + priorNoise = gtsam.noiseModel.Diagonal.Sigmas( np.array([0.3, 0.3, 0.1])) # 30cm std on x,y, 0.1 rad on theta # add directly to graph graph.add(gtsam.PriorFactorPose2(1, priorMean, priorNoise)) @@ -33,7 +33,7 @@ class TestOdometryExample(GtsamTestCase): # Add two odometry factors # create a measurement for both factors (the same in this case) odometry = gtsam.Pose2(2.0, 0.0, 0.0) - odometryNoise = gtsam.noiseModel_Diagonal.Sigmas( + odometryNoise = gtsam.noiseModel.Diagonal.Sigmas( np.array([0.2, 0.2, 0.1])) # 20cm std on x,y, 0.1 rad on theta graph.add(gtsam.BetweenFactorPose2(1, 2, odometry, odometryNoise)) graph.add(gtsam.BetweenFactorPose2(2, 3, odometry, odometryNoise)) diff --git a/python/gtsam_py/python/tests/test_PlanarSLAMExample.py b/python/gtsam_py/python/tests/test_PlanarSLAMExample.py index ae813d35c..8cb3ad2ac 100644 --- a/python/gtsam_py/python/tests/test_PlanarSLAMExample.py +++ b/python/gtsam_py/python/tests/test_PlanarSLAMExample.py @@ -32,13 +32,13 @@ class TestPlanarSLAM(GtsamTestCase): # Add prior # gaussian for prior priorMean = gtsam.Pose2(0.0, 0.0, 0.0) # prior at origin - priorNoise = gtsam.noiseModel_Diagonal.Sigmas(np.array([0.3, 0.3, 0.1])) + priorNoise = gtsam.noiseModel.Diagonal.Sigmas(np.array([0.3, 0.3, 0.1])) # add directly to graph graph.add(gtsam.PriorFactorPose2(1, priorMean, priorNoise)) # Add odometry # general noisemodel for odometry - odometryNoise = gtsam.noiseModel_Diagonal.Sigmas(np.array([0.2, 0.2, 0.1])) + odometryNoise = gtsam.noiseModel.Diagonal.Sigmas(np.array([0.2, 0.2, 0.1])) graph.add(gtsam.BetweenFactorPose2( 1, 2, gtsam.Pose2(2.0, 0.0, 0.0), odometryNoise)) graph.add(gtsam.BetweenFactorPose2( @@ -49,7 +49,7 @@ class TestPlanarSLAM(GtsamTestCase): 4, 5, gtsam.Pose2(2.0, 0.0, pi / 2), odometryNoise)) # Add pose constraint - model = gtsam.noiseModel_Diagonal.Sigmas(np.array([0.2, 0.2, 0.1])) + model = gtsam.noiseModel.Diagonal.Sigmas(np.array([0.2, 0.2, 0.1])) graph.add(gtsam.BetweenFactorPose2(5, 2, gtsam.Pose2(2.0, 0.0, pi / 2), model)) # Initialize to noisy points diff --git a/python/gtsam_py/python/tests/test_Pose2SLAMExample.py b/python/gtsam_py/python/tests/test_Pose2SLAMExample.py index a79b6b18c..e47b9fbff 100644 --- a/python/gtsam_py/python/tests/test_Pose2SLAMExample.py +++ b/python/gtsam_py/python/tests/test_Pose2SLAMExample.py @@ -32,13 +32,13 @@ class TestPose2SLAMExample(GtsamTestCase): # Add prior # gaussian for prior priorMean = gtsam.Pose2(0.0, 0.0, 0.0) # prior at origin - priorNoise = gtsam.noiseModel_Diagonal.Sigmas(np.array([0.3, 0.3, 0.1])) + priorNoise = gtsam.noiseModel.Diagonal.Sigmas(np.array([0.3, 0.3, 0.1])) # add directly to graph graph.add(gtsam.PriorFactorPose2(1, priorMean, priorNoise)) # Add odometry # general noisemodel for odometry - odometryNoise = gtsam.noiseModel_Diagonal.Sigmas(np.array([0.2, 0.2, 0.1])) + odometryNoise = gtsam.noiseModel.Diagonal.Sigmas(np.array([0.2, 0.2, 0.1])) graph.add(gtsam.BetweenFactorPose2( 1, 2, gtsam.Pose2(2.0, 0.0, 0.0), odometryNoise)) graph.add(gtsam.BetweenFactorPose2( @@ -49,7 +49,7 @@ class TestPose2SLAMExample(GtsamTestCase): 4, 5, gtsam.Pose2(2.0, 0.0, pi / 2), odometryNoise)) # Add pose constraint - model = gtsam.noiseModel_Diagonal.Sigmas(np.array([0.2, 0.2, 0.1])) + model = gtsam.noiseModel.Diagonal.Sigmas(np.array([0.2, 0.2, 0.1])) graph.add(gtsam.BetweenFactorPose2(5, 2, gtsam.Pose2(2.0, 0.0, pi / 2), model)) # Initialize to noisy points diff --git a/python/gtsam_py/python/tests/test_Pose3SLAMExample.py b/python/gtsam_py/python/tests/test_Pose3SLAMExample.py index 1e9eaac67..fce171b55 100644 --- a/python/gtsam_py/python/tests/test_Pose3SLAMExample.py +++ b/python/gtsam_py/python/tests/test_Pose3SLAMExample.py @@ -30,7 +30,7 @@ class TestPose3SLAMExample(GtsamTestCase): fg = gtsam.NonlinearFactorGraph() fg.add(gtsam.NonlinearEqualityPose3(0, p0)) delta = p0.between(p1) - covariance = gtsam.noiseModel_Diagonal.Sigmas( + covariance = gtsam.noiseModel.Diagonal.Sigmas( np.array([0.05, 0.05, 0.05, 5. * pi / 180, 5. * pi / 180, 5. * pi / 180])) fg.add(gtsam.BetweenFactorPose3(0, 1, delta, covariance)) fg.add(gtsam.BetweenFactorPose3(1, 2, delta, covariance)) diff --git a/python/gtsam_py/python/tests/test_PriorFactor.py b/python/gtsam_py/python/tests/test_PriorFactor.py index 66207b800..da072d0bd 100644 --- a/python/gtsam_py/python/tests/test_PriorFactor.py +++ b/python/gtsam_py/python/tests/test_PriorFactor.py @@ -23,39 +23,17 @@ class TestPriorFactor(GtsamTestCase): key = 5 priorPose3 = gtsam.Pose3() - model = gtsam.noiseModel_Unit.Create(6) + model = gtsam.noiseModel.Unit.Create(6) factor = gtsam.PriorFactorPose3(key, priorPose3, model) values.insert(key, priorPose3) self.assertEqual(factor.error(values), 0) key = 3 priorVector = np.array([0., 0., 0.]) - model = gtsam.noiseModel_Unit.Create(3) + model = gtsam.noiseModel.Unit.Create(3) factor = gtsam.PriorFactorVector(key, priorVector, model) values.insert(key, priorVector) self.assertEqual(factor.error(values), 0) - def test_AddPrior(self): - """ - Test adding prior factors directly to factor graph via the .addPrior method. - """ - # define factor graph - graph = gtsam.NonlinearFactorGraph() - - # define and add Pose3 prior - key = 5 - priorPose3 = gtsam.Pose3() - model = gtsam.noiseModel_Unit.Create(6) - graph.addPriorPose3(key, priorPose3, model) - self.assertEqual(graph.size(), 1) - - # define and add Vector prior - key = 3 - priorVector = np.array([0., 0., 0.]) - model = gtsam.noiseModel_Unit.Create(3) - graph.addPriorVector(key, priorVector, model) - self.assertEqual(graph.size(), 2) - - if __name__ == "__main__": unittest.main() diff --git a/python/gtsam_py/python/tests/test_SFMExample.py b/python/gtsam_py/python/tests/test_SFMExample.py index e8fa46186..8b5473ff0 100644 --- a/python/gtsam_py/python/tests/test_SFMExample.py +++ b/python/gtsam_py/python/tests/test_SFMExample.py @@ -34,29 +34,29 @@ class TestSFMExample(GtsamTestCase): graph = gtsam.NonlinearFactorGraph() # Add factors for all measurements - measurementNoise = gtsam.noiseModel_Isotropic.Sigma(2, measurementNoiseSigma) + measurementNoise = gtsam.noiseModel.Isotropic.Sigma(2, measurementNoiseSigma) for i in range(len(data.Z)): for k in range(len(data.Z[i])): j = data.J[i][k] graph.add(gtsam.GenericProjectionFactorCal3_S2( data.Z[i][k], measurementNoise, - symbol(ord('x'), i), symbol(ord('p'), j), data.K)) + symbol('x', i), symbol('p', j), data.K)) - posePriorNoise = gtsam.noiseModel_Diagonal.Sigmas(poseNoiseSigmas) - graph.add(gtsam.PriorFactorPose3(symbol(ord('x'), 0), + posePriorNoise = gtsam.noiseModel.Diagonal.Sigmas(poseNoiseSigmas) + graph.add(gtsam.PriorFactorPose3(symbol('x', 0), truth.cameras[0].pose(), posePriorNoise)) - pointPriorNoise = gtsam.noiseModel_Isotropic.Sigma(3, pointNoiseSigma) - graph.add(gtsam.PriorFactorPoint3(symbol(ord('p'), 0), + pointPriorNoise = gtsam.noiseModel.Isotropic.Sigma(3, pointNoiseSigma) + graph.add(gtsam.PriorFactorPoint3(symbol('p', 0), truth.points[0], pointPriorNoise)) # Initial estimate initialEstimate = gtsam.Values() for i in range(len(truth.cameras)): pose_i = truth.cameras[i].pose() - initialEstimate.insert(symbol(ord('x'), i), pose_i) + initialEstimate.insert(symbol('x', i), pose_i) for j in range(len(truth.points)): point_j = truth.points[j] - initialEstimate.insert(symbol(ord('p'), j), point_j) + initialEstimate.insert(symbol('p', j), point_j) # Optimization optimizer = gtsam.LevenbergMarquardtOptimizer(graph, initialEstimate) @@ -66,16 +66,16 @@ class TestSFMExample(GtsamTestCase): # Marginalization marginals = gtsam.Marginals(graph, result) - marginals.marginalCovariance(symbol(ord('p'), 0)) - marginals.marginalCovariance(symbol(ord('x'), 0)) + marginals.marginalCovariance(symbol('p', 0)) + marginals.marginalCovariance(symbol('x', 0)) # Check optimized results, should be equal to ground truth for i in range(len(truth.cameras)): - pose_i = result.atPose3(symbol(ord('x'), i)) + pose_i = result.atPose3(symbol('x', i)) self.gtsamAssertEquals(pose_i, truth.cameras[i].pose(), 1e-5) for j in range(len(truth.points)): - point_j = result.atPoint3(symbol(ord('p'), j)) + point_j = result.atPoint3(symbol('p', j)) self.gtsamAssertEquals(point_j, truth.points[j], 1e-5) if __name__ == "__main__": diff --git a/python/gtsam_py/python/tests/test_Scenario.py b/python/gtsam_py/python/tests/test_Scenario.py index 09601fba5..fc5965829 100644 --- a/python/gtsam_py/python/tests/test_Scenario.py +++ b/python/gtsam_py/python/tests/test_Scenario.py @@ -43,8 +43,11 @@ class TestScenario(GtsamTestCase): # R = v/w, so test if loop crests at 2*R R = v / w T30 = scenario.pose(T) + xyz = T30.rotation().xyz() + if xyz[0] < 0: + xyz = -xyz np.testing.assert_almost_equal( - np.array([math.pi, 0, math.pi]), T30.rotation().xyz()) + np.array([math.pi, 0, math.pi]), xyz) self.gtsamAssertEquals(gtsam.Point3( 0, 0, 2.0 * R), T30.translation(), 1e-9) diff --git a/python/gtsam_py/python/tests/test_SimpleCamera.py b/python/gtsam_py/python/tests/test_SimpleCamera.py index a3654a5f1..efdfec561 100644 --- a/python/gtsam_py/python/tests/test_SimpleCamera.py +++ b/python/gtsam_py/python/tests/test_SimpleCamera.py @@ -5,7 +5,7 @@ All Rights Reserved See LICENSE for the license information -PinholeCameraCal3_S2 unit tests. +SimpleCamera unit tests. Author: Frank Dellaert & Duy Nguyen Ta (Python) """ import math @@ -14,7 +14,7 @@ import unittest import numpy as np import gtsam -from gtsam import Cal3_S2, Point3, Pose2, Pose3, Rot3, PinholeCameraCal3_S2 +from gtsam import Cal3_S2, Point3, Pose2, Pose3, Rot3, SimpleCamera from gtsam.utils.test_case import GtsamTestCase K = Cal3_S2(625, 625, 0, 0, 0) @@ -23,14 +23,14 @@ class TestSimpleCamera(GtsamTestCase): def test_constructor(self): pose1 = Pose3(Rot3(np.diag([1, -1, -1])), Point3(0, 0, 0.5)) - camera = PinholeCameraCal3_S2(pose1, K) + camera = SimpleCamera(pose1, K) self.gtsamAssertEquals(camera.calibration(), K, 1e-9) self.gtsamAssertEquals(camera.pose(), pose1, 1e-9) def test_level2(self): # Create a level camera, looking in Y-direction pose2 = Pose2(0.4,0.3,math.pi/2.0) - camera = PinholeCameraCal3_S2.Level(K, pose2, 0.1) + camera = SimpleCamera.Level(K, pose2, 0.1) # expected x = Point3(1,0,0) diff --git a/python/gtsam_py/python/tests/test_StereoVOExample.py b/python/gtsam_py/python/tests/test_StereoVOExample.py index 3f5f57522..cefc08aab 100644 --- a/python/gtsam_py/python/tests/test_StereoVOExample.py +++ b/python/gtsam_py/python/tests/test_StereoVOExample.py @@ -28,11 +28,11 @@ class TestStereoVOExample(GtsamTestCase): # - No noise on measurements ## Create keys for variables - x1 = symbol(ord('x'),1) - x2 = symbol(ord('x'),2) - l1 = symbol(ord('l'),1) - l2 = symbol(ord('l'),2) - l3 = symbol(ord('l'),3) + x1 = symbol('x',1) + x2 = symbol('x',2) + l1 = symbol('l',1) + l2 = symbol('l',2) + l3 = symbol('l',3) ## Create graph container and add factors to it graph = gtsam.NonlinearFactorGraph() @@ -44,7 +44,7 @@ class TestStereoVOExample(GtsamTestCase): ## Create realistic calibration and measurement noise model # format: fx fy skew cx cy baseline K = gtsam.Cal3_S2Stereo(1000, 1000, 0, 320, 240, 0.2) - stereo_model = gtsam.noiseModel_Diagonal.Sigmas(np.array([1.0, 1.0, 1.0])) + stereo_model = gtsam.noiseModel.Diagonal.Sigmas(np.array([1.0, 1.0, 1.0])) ## Add measurements # pose 1 diff --git a/python/gtsam_py/python/tests/test_Triangulation.py b/python/gtsam_py/python/tests/test_Triangulation.py new file mode 100644 index 000000000..b43ad9b57 --- /dev/null +++ b/python/gtsam_py/python/tests/test_Triangulation.py @@ -0,0 +1,80 @@ +""" +GTSAM Copyright 2010-2019, Georgia Tech Research Corporation, +Atlanta, Georgia 30332-0415 +All Rights Reserved + +See LICENSE for the license information + +Test Triangulation +Author: Frank Dellaert & Fan Jiang (Python) +""" +import unittest + +import numpy as np + +import gtsam as g +from gtsam.utils.test_case import GtsamTestCase +from gtsam import Cal3_S2, Cal3Bundler, Rot3, Pose3, \ + PinholeCameraCal3_S2, Point3, Point2Vector, Pose3Vector, triangulatePoint3 + +class TestVisualISAMExample(GtsamTestCase): + def test_TriangulationExample(self): + # Some common constants + sharedCal = Cal3_S2(1500, 1200, 0, 640, 480) + + # Looking along X-axis, 1 meter above ground plane (x-y) + upright = Rot3.Ypr(-np.pi / 2, 0., -np.pi / 2) + pose1 = Pose3(upright, Point3(0, 0, 1)) + camera1 = PinholeCameraCal3_S2(pose1, sharedCal) + + # create second camera 1 meter to the right of first camera + pose2 = pose1.compose(Pose3(Rot3(), Point3(1, 0, 0))) + camera2 = PinholeCameraCal3_S2(pose2, sharedCal) + + # landmark ~5 meters infront of camera + landmark = Point3(5, 0.5, 1.2) + + # 1. Project two landmarks into two cameras and triangulate + z1 = camera1.project(landmark) + z2 = camera2.project(landmark) + + # twoPoses + poses = Pose3Vector() + measurements = Point2Vector() + + poses.append(pose1) + poses.append(pose2) + measurements.append(z1) + measurements.append(z2) + + optimize = True + rank_tol = 1e-9 + + triangulated_landmark = triangulatePoint3(poses,sharedCal, measurements, rank_tol, optimize) + self.gtsamAssertEquals(landmark, triangulated_landmark,1e-9) + + # 2. Add some noise and try again: result should be ~ (4.995, 0.499167, 1.19814) + measurements = Point2Vector() + measurements.append(z1 - np.array([0.1, 0.5])) + measurements.append(z2 - np.array([-0.2, 0.3])) + + triangulated_landmark = triangulatePoint3(poses,sharedCal, measurements, rank_tol, optimize) + self.gtsamAssertEquals(landmark, triangulated_landmark,1e-2) + # + # # two Poses with Bundler Calibration + # bundlerCal = Cal3Bundler(1500, 0, 0, 640, 480) + # camera1 = PinholeCameraCal3Bundler(pose1, bundlerCal) + # camera2 = PinholeCameraCal3Bundler(pose2, bundlerCal) + # + # z1 = camera1.project(landmark) + # z2 = camera2.project(landmark) + # + # measurements = Point2Vector() + # measurements.append(z1) + # measurements.append(z2) + # + # triangulated_landmark = triangulatePoint3(poses,bundlerCal, measurements, rank_tol, optimize) + # self.gtsamAssertEquals(landmark, triangulated_landmark,1e-9) + +if __name__ == "__main__": + unittest.main() diff --git a/python/gtsam_py/python/tests/test_Values.py b/python/gtsam_py/python/tests/test_Values.py index 20634a21c..dddd11c40 100644 --- a/python/gtsam_py/python/tests/test_Values.py +++ b/python/gtsam_py/python/tests/test_Values.py @@ -15,8 +15,7 @@ import numpy as np import gtsam from gtsam import (Cal3_S2, Cal3Bundler, Cal3DS2, EssentialMatrix, Point2, - Point3, Pose2, Pose3, Rot2, Rot3, Unit3, Values, - imuBias_ConstantBias) + Point3, Pose2, Pose3, Rot2, Rot3, Unit3, Values, imuBias) from gtsam.utils.test_case import GtsamTestCase @@ -37,7 +36,7 @@ class TestValues(GtsamTestCase): values.insert(7, Cal3DS2()) values.insert(8, Cal3Bundler()) values.insert(9, E) - values.insert(10, imuBias_ConstantBias()) + values.insert(10, imuBias.ConstantBias()) # Special cases for Vectors and Matrices # Note that gtsam's Eigen Vectors and Matrices requires double-precision @@ -70,8 +69,8 @@ class TestValues(GtsamTestCase): self.gtsamAssertEquals(values.atCal3DS2(7), Cal3DS2(), tol) self.gtsamAssertEquals(values.atCal3Bundler(8), Cal3Bundler(), tol) self.gtsamAssertEquals(values.atEssentialMatrix(9), E, tol) - self.gtsamAssertEquals(values.atimuBias_ConstantBias( - 10), imuBias_ConstantBias(), tol) + self.gtsamAssertEquals(values.atConstantBias( + 10), imuBias.ConstantBias(), tol) # special cases for Vector and Matrix: actualVector = values.atVector(11) diff --git a/python/gtsam_py/python/tests/test_VisualISAMExample.py b/python/gtsam_py/python/tests/test_VisualISAMExample.py index 99d7e6160..6eb05eeee 100644 --- a/python/gtsam_py/python/tests/test_VisualISAMExample.py +++ b/python/gtsam_py/python/tests/test_VisualISAMExample.py @@ -46,11 +46,11 @@ class TestVisualISAMExample(GtsamTestCase): isam, result = visual_isam.step(data, isam, result, truth, currentPose) for i in range(len(truth.cameras)): - pose_i = result.atPose3(symbol(ord('x'), i)) + pose_i = result.atPose3(symbol('x', i)) self.gtsamAssertEquals(pose_i, truth.cameras[i].pose(), 1e-5) for j in range(len(truth.points)): - point_j = result.atPoint3(symbol(ord('l'), j)) + point_j = result.atPoint3(symbol('l', j)) self.gtsamAssertEquals(point_j, truth.points[j], 1e-5) if __name__ == "__main__": diff --git a/python/gtsam_py/python/tests/test_dataset.py b/python/gtsam_py/python/tests/test_dataset.py index 60fb9450d..87fc2ad54 100644 --- a/python/gtsam_py/python/tests/test_dataset.py +++ b/python/gtsam_py/python/tests/test_dataset.py @@ -15,7 +15,7 @@ from __future__ import print_function import unittest import gtsam -from gtsam import BetweenFactorPose3, BetweenFactorPose3s +from gtsam import BetweenFactorPose3 from gtsam.utils.test_case import GtsamTestCase @@ -37,8 +37,8 @@ class TestDataset(GtsamTestCase): def test_parse3Dfactors(self): """Test parsing into data structure.""" factors = gtsam.parse3DFactors(self.pose3_example_g2o_file) - self.assertEqual(factors.size(), 6) - self.assertIsInstance(factors.at(0), BetweenFactorPose3) + self.assertEqual(len(factors), 6) + self.assertIsInstance(factors[0], BetweenFactorPose3) if __name__ == '__main__': diff --git a/python/gtsam_py/python/tests/test_initialize_pose3.py b/python/gtsam_py/python/tests/test_initialize_pose3.py index 3aa7e3470..6d7f66653 100644 --- a/python/gtsam_py/python/tests/test_initialize_pose3.py +++ b/python/gtsam_py/python/tests/test_initialize_pose3.py @@ -24,7 +24,7 @@ class TestValues(GtsamTestCase): def setUp(self): - model = gtsam.noiseModel_Isotropic.Sigma(6, 0.1) + model = gtsam.noiseModel.Isotropic.Sigma(6, 0.1) # We consider a small graph: # symbolic FG @@ -64,9 +64,8 @@ class TestValues(GtsamTestCase): def test_orientations(self): pose3Graph = gtsam.InitializePose3.buildPose3graph(self.graph) - initial = gtsam.InitializePose3.computeOrientationsChordal(pose3Graph) - + # comparison is up to M_PI, that's why we add some multiples of 2*M_PI self.gtsamAssertEquals(initial.atRot3(x0), self.R0, 1e-6) self.gtsamAssertEquals(initial.atRot3(x1), self.R1, 1e-6) @@ -77,7 +76,7 @@ class TestValues(GtsamTestCase): g2oFile = gtsam.findExampleDataFile("pose3example-grid") is3D = True inputGraph, expectedValues = gtsam.readG2o(g2oFile, is3D) - priorModel = gtsam.noiseModel_Unit.Create(6) + priorModel = gtsam.noiseModel.Unit.Create(6) inputGraph.add(gtsam.PriorFactorPose3(0, Pose3(), priorModel)) initial = gtsam.InitializePose3.initialize(inputGraph) diff --git a/python/gtsam_py/python/tests/test_logging_optimizer.py b/python/gtsam_py/python/tests/test_logging_optimizer.py index 2560a72a2..47eb32e7b 100644 --- a/python/gtsam_py/python/tests/test_logging_optimizer.py +++ b/python/gtsam_py/python/tests/test_logging_optimizer.py @@ -21,7 +21,7 @@ from gtsam.utils.test_case import GtsamTestCase from gtsam.utils.logging_optimizer import gtsam_optimize KEY = 0 -MODEL = gtsam.noiseModel_Unit.Create(3) +MODEL = gtsam.noiseModel.Unit.Create(3) class TestOptimizeComet(GtsamTestCase): diff --git a/python/gtsam_py/python/utils/circlePose3.py b/python/gtsam_py/python/utils/circlePose3.py index 7012548f4..37e7c5568 100644 --- a/python/gtsam_py/python/utils/circlePose3.py +++ b/python/gtsam_py/python/utils/circlePose3.py @@ -3,7 +3,7 @@ import numpy as np from math import pi, cos, sin -def circlePose3(numPoses=8, radius=1.0, symbolChar=0): +def circlePose3(numPoses=8, radius=1.0, symbolChar='\0'): """ circlePose3 generates a set of poses in a circle. This function returns those poses inside a gtsam.Values object, with sequential @@ -18,10 +18,6 @@ def circlePose3(numPoses=8, radius=1.0, symbolChar=0): Vehicle at p0 is looking towards y axis (X-axis points towards world y) """ - # Force symbolChar to be a single character - if type(symbolChar) is str: - symbolChar = ord(symbolChar[0]) - values = gtsam.Values() theta = 0.0 dtheta = 2 * pi / numPoses diff --git a/python/gtsam_py/python/utils/plot.py b/python/gtsam_py/python/utils/plot.py index 1e976a69e..7b8da0f06 100644 --- a/python/gtsam_py/python/utils/plot.py +++ b/python/gtsam_py/python/utils/plot.py @@ -13,9 +13,8 @@ def set_axes_equal(fignum): Make axes of 3D plot have equal scale so that spheres appear as spheres, cubes as cubes, etc.. This is one possible solution to Matplotlib's ax.set_aspect('equal') and ax.axis('equal') not working for 3D. - - Args: - fignum (int): An integer representing the figure number for Matplotlib. + Input + ax: a matplotlib axis, e.g., as output from plt.gca(). """ fig = plt.figure(fignum) ax = fig.gca(projection='3d') @@ -35,21 +34,7 @@ def set_axes_equal(fignum): def ellipsoid(xc, yc, zc, rx, ry, rz, n): - """ - Numpy equivalent of Matlab's ellipsoid function. - - Args: - xc (double): Center of ellipsoid in X-axis. - yc (double): Center of ellipsoid in Y-axis. - zc (double): Center of ellipsoid in Z-axis. - rx (double): Radius of ellipsoid in X-axis. - ry (double): Radius of ellipsoid in Y-axis. - rz (double): Radius of ellipsoid in Z-axis. - n (int): The granularity of the ellipsoid plotted. - - Returns: - tuple[numpy.ndarray]: The points in the x, y and z axes to use for the surface plot. - """ + """Numpy equivalent of Matlab's ellipsoid function""" u = np.linspace(0, 2*np.pi, n+1) v = np.linspace(0, np.pi, n+1) x = -rx * np.outer(np.cos(u), np.sin(v)).T @@ -62,18 +47,9 @@ def ellipsoid(xc, yc, zc, rx, ry, rz, n): def plot_covariance_ellipse_3d(axes, origin, P, scale=1, n=8, alpha=0.5): """ Plots a Gaussian as an uncertainty ellipse - Based on Maybeck Vol 1, page 366 k=2.296 corresponds to 1 std, 68.26% of all probability k=11.82 corresponds to 3 std, 99.74% of all probability - - Args: - axes (matplotlib.axes.Axes): Matplotlib axes. - origin (gtsam.Point3): The origin in the world frame. - P (numpy.ndarray): The marginal covariance matrix of the 3D point which will be represented as an ellipse. - scale (float): Scaling factor of the radii of the covariance ellipse. - n (int): Defines the granularity of the ellipse. Higher values indicate finer ellipses. - alpha (float): Transparency value for the plotted surface in the range [0, 1]. """ k = 11.82 U, S, _ = np.linalg.svd(P) @@ -97,19 +73,10 @@ def plot_covariance_ellipse_3d(axes, origin, P, scale=1, n=8, alpha=0.5): def plot_pose2_on_axes(axes, pose, axis_length=0.1, covariance=None): - """ - Plot a 2D pose on given axis `axes` with given `axis_length`. - - Args: - axes (matplotlib.axes.Axes): Matplotlib axes. - pose (gtsam.Pose2): The pose to be plotted. - axis_length (float): The length of the camera axes. - covariance (numpy.ndarray): Marginal covariance matrix to plot the uncertainty of the estimation. - """ + """Plot a 2D pose on given axis 'axes' with given 'axis_length'.""" # get rotation and translation (center) gRp = pose.rotation().matrix() # rotation from pose to global - t = pose.translation() - origin = np.array([t.x(), t.y()]) + origin = pose.translation() # draw the camera axes x_axis = origin + gRp[:, 0] * axis_length @@ -134,89 +101,34 @@ def plot_pose2_on_axes(axes, pose, axis_length=0.1, covariance=None): np.rad2deg(angle), fill=False) axes.add_patch(e1) - -def plot_pose2(fignum, pose, axis_length=0.1, covariance=None, - axis_labels=('X axis', 'Y axis', 'Z axis')): - """ - Plot a 2D pose on given figure with given `axis_length`. - - Args: - fignum (int): Integer representing the figure number to use for plotting. - pose (gtsam.Pose2): The pose to be plotted. - axis_length (float): The length of the camera axes. - covariance (numpy.ndarray): Marginal covariance matrix to plot the uncertainty of the estimation. - axis_labels (iterable[string]): List of axis labels to set. - """ +def plot_pose2(fignum, pose, axis_length=0.1, covariance=None): + """Plot a 2D pose on given figure with given 'axis_length'.""" # get figure object fig = plt.figure(fignum) axes = fig.gca() - plot_pose2_on_axes(axes, pose, axis_length=axis_length, - covariance=covariance) - - axes.set_xlabel(axis_labels[0]) - axes.set_ylabel(axis_labels[1]) - axes.set_zlabel(axis_labels[2]) - - return fig + plot_pose2_on_axes(axes, pose, axis_length, covariance) def plot_point3_on_axes(axes, point, linespec, P=None): - """ - Plot a 3D point on given axis `axes` with given `linespec`. - - Args: - axes (matplotlib.axes.Axes): Matplotlib axes. - point (gtsam.Point3): The point to be plotted. - linespec (string): String representing formatting options for Matplotlib. - P (numpy.ndarray): Marginal covariance matrix to plot the uncertainty of the estimation. - """ - axes.plot([point.x()], [point.y()], [point.z()], linespec) + """Plot a 3D point on given axis 'axes' with given 'linespec' and optional covariance 'P'.""" + axes.plot([point[0]], [point[1]], [point[2]], linespec) if P is not None: plot_covariance_ellipse_3d(axes, point.vector(), P) -def plot_point3(fignum, point, linespec, P=None, - axis_labels=('X axis', 'Y axis', 'Z axis')): - """ - Plot a 3D point on given figure with given `linespec`. - - Args: - fignum (int): Integer representing the figure number to use for plotting. - point (gtsam.Point3): The point to be plotted. - linespec (string): String representing formatting options for Matplotlib. - P (numpy.ndarray): Marginal covariance matrix to plot the uncertainty of the estimation. - axis_labels (iterable[string]): List of axis labels to set. - - Returns: - fig: The matplotlib figure. - - """ +def plot_point3(fignum, point, linespec, P=None): + """Plot a 3D point on given figure with given 'linespec' and optional covariance 'P'.""" fig = plt.figure(fignum) axes = fig.gca(projection='3d') plot_point3_on_axes(axes, point, linespec, P) - axes.set_xlabel(axis_labels[0]) - axes.set_ylabel(axis_labels[1]) - axes.set_zlabel(axis_labels[2]) - return fig - - -def plot_3d_points(fignum, values, linespec="g*", marginals=None, - title="3D Points", axis_labels=('X axis', 'Y axis', 'Z axis')): +def plot_3d_points(fignum, values, linespec="g*", marginals=None): """ - Plots the Point3s in `values`, with optional covariances. + Plots the Point3s in 'values', with optional covariances. Finds all the Point3 objects in the given Values object and plots them. If a Marginals object is given, this function will also plot marginal covariance ellipses for each point. - - Args: - fignum (int): Integer representing the figure number to use for plotting. - values (gtsam.Values): Values dictionary consisting of points to be plotted. - linespec (string): String representing formatting options for Matplotlib. - marginals (numpy.ndarray): Marginal covariance matrix to plot the uncertainty of the estimation. - title (string): The title of the plot. - axis_labels (iterable[string]): List of axis labels to set. """ keys = values.keys() @@ -227,34 +139,25 @@ def plot_3d_points(fignum, values, linespec="g*", marginals=None, key = keys.at(i) point = values.atPoint3(key) if marginals is not None: - covariance = marginals.marginalCovariance(key) + P = marginals.marginalCovariance(key); else: - covariance = None + P = None - fig = plot_point3(fignum, point, linespec, covariance, - axis_labels=axis_labels) + plot_point3(fignum, point, linespec, P) except RuntimeError: continue # I guess it's not a Point3 - fig.suptitle(title) - fig.canvas.set_window_title(title.lower()) - -def plot_pose3_on_axes(axes, pose, axis_length=0.1, P=None, scale=1): +def plot_pose3_on_axes(axes, pose, P=None, scale=1, axis_length=0.1): """ - Plot a 3D pose on given axis `axes` with given `axis_length`. - - Args: - axes (matplotlib.axes.Axes): Matplotlib axes. - point (gtsam.Point3): The point to be plotted. - linespec (string): String representing formatting options for Matplotlib. - P (numpy.ndarray): Marginal covariance matrix to plot the uncertainty of the estimation. + Plot a 3D pose on given axis 'axes' with given 'axis_length'. + Optional 'scale' the pose and plot the covariance 'P'. """ # get rotation and translation (center) gRp = pose.rotation().matrix() # rotation from pose to global - origin = pose.translation().vector() + origin = pose.translation() # draw the camera axes x_axis = origin + gRp[:, 0] * axis_length @@ -269,7 +172,6 @@ def plot_pose3_on_axes(axes, pose, axis_length=0.1, P=None, scale=1): line = np.append(origin[np.newaxis], z_axis[np.newaxis], axis=0) axes.plot(line[:, 0], line[:, 1], line[:, 2], 'b-') - # plot the covariance if P is not None: # covariance matrix in pose coordinate frame pPp = P[3:6, 3:6] @@ -278,49 +180,16 @@ def plot_pose3_on_axes(axes, pose, axis_length=0.1, P=None, scale=1): plot_covariance_ellipse_3d(axes, origin, gPp) -def plot_pose3(fignum, pose, axis_length=0.1, P=None, - axis_labels=('X axis', 'Y axis', 'Z axis')): - """ - Plot a 3D pose on given figure with given `axis_length`. - - Args: - fignum (int): Integer representing the figure number to use for plotting. - pose (gtsam.Pose3): 3D pose to be plotted. - linespec (string): String representing formatting options for Matplotlib. - P (numpy.ndarray): Marginal covariance matrix to plot the uncertainty of the estimation. - axis_labels (iterable[string]): List of axis labels to set. - - Returns: - fig: The matplotlib figure. - """ +def plot_pose3(fignum, pose, P, axis_length=0.1): + """Plot a 3D pose on given figure with given 'axis_length'.""" # get figure object fig = plt.figure(fignum) axes = fig.gca(projection='3d') - plot_pose3_on_axes(axes, pose, P=P, - axis_length=axis_length) - - axes.set_xlabel(axis_labels[0]) - axes.set_ylabel(axis_labels[1]) - axes.set_zlabel(axis_labels[2]) - - return fig + plot_pose3_on_axes(axes, pose, P=P, axis_length=axis_length) -def plot_trajectory(fignum, values, scale=1, marginals=None, - title="Plot Trajectory", axis_labels=('X axis', 'Y axis', 'Z axis')): - """ - Plot a complete 3D trajectory using poses in `values`. - - Args: - fignum (int): Integer representing the figure number to use for plotting. - values (gtsam.Values): Values dict containing the poses. - scale (float): Value to scale the poses by. - marginals (gtsam.Marginals): Marginalized probability values of the estimation. - Used to plot uncertainty bounds. - title (string): The title of the plot. - axis_labels (iterable[string]): List of axis labels to set. - """ - pose3Values = gtsam.utilities_allPose3s(values) +def plot_trajectory(fignum, values, scale=1, marginals=None): + pose3Values = gtsam.allPose3s(values) keys = gtsam.KeyVector(pose3Values.keys()) lastIndex = None @@ -340,12 +209,11 @@ def plot_trajectory(fignum, values, scale=1, marginals=None, pass if marginals: - covariance = marginals.marginalCovariance(lastKey) + P = marginals.marginalCovariance(lastKey) else: - covariance = None + P = None - fig = plot_pose3(fignum, lastPose, P=covariance, - axis_length=scale, axis_labels=axis_labels) + plot_pose3(fignum, lastPose, P, scale) lastIndex = i @@ -355,15 +223,11 @@ def plot_trajectory(fignum, values, scale=1, marginals=None, try: lastPose = pose3Values.atPose3(lastKey) if marginals: - covariance = marginals.marginalCovariance(lastKey) + P = marginals.marginalCovariance(lastKey) else: - covariance = None + P = None - fig = plot_pose3(fignum, lastPose, P=covariance, - axis_length=scale, axis_labels=axis_labels) + plot_pose3(fignum, lastPose, P, scale) except: pass - - fig.suptitle(title) - fig.canvas.set_window_title(title.lower()) diff --git a/python/gtsam_py/python/utils/test_case.py b/python/gtsam_py/python/utils/test_case.py index 7df1e6ee9..3effd7f65 100644 --- a/python/gtsam_py/python/utils/test_case.py +++ b/python/gtsam_py/python/utils/test_case.py @@ -21,7 +21,11 @@ class GtsamTestCase(unittest.TestCase): Keyword Arguments: tol {float} -- tolerance passed to 'equals', default 1e-9 """ - equal = actual.equals(expected, tol) + import numpy + if isinstance(expected, numpy.ndarray): + equal = numpy.allclose(actual, expected, atol=tol) + else: + equal = actual.equals(expected, tol) if not equal: raise self.failureException( "Values are not equal:\n{}!={}".format(actual, expected)) diff --git a/python/gtsam_py/python/utils/visual_data_generator.py b/python/gtsam_py/python/utils/visual_data_generator.py index f04588e70..bc60dcd70 100644 --- a/python/gtsam_py/python/utils/visual_data_generator.py +++ b/python/gtsam_py/python/utils/visual_data_generator.py @@ -1,9 +1,8 @@ from __future__ import print_function import numpy as np - +from math import pi, cos, sin import gtsam -from gtsam import Cal3_S2, PinholeCameraCal3_S2, Point2, Point3, Pose3 class Options: @@ -11,7 +10,7 @@ class Options: Options to generate test scenario """ - def __init__(self, triangle=False, nrCameras=3, K=Cal3_S2()): + def __init__(self, triangle=False, nrCameras=3, K=gtsam.Cal3_S2()): """ Options to generate test scenario @param triangle: generate a triangle scene with 3 points if True, otherwise @@ -28,10 +27,10 @@ class GroundTruth: Object holding generated ground-truth data """ - def __init__(self, K=Cal3_S2(), nrCameras=3, nrPoints=4): + def __init__(self, K=gtsam.Cal3_S2(), nrCameras=3, nrPoints=4): self.K = K - self.cameras = [Pose3()] * nrCameras - self.points = [Point3()] * nrPoints + self.cameras = [gtsam.Pose3()] * nrCameras + self.points = [gtsam.Point3(0, 0, 0)] * nrPoints def print_(self, s=""): print(s) @@ -53,28 +52,28 @@ class Data: class NoiseModels: pass - def __init__(self, K=Cal3_S2(), nrCameras=3, nrPoints=4): + def __init__(self, K=gtsam.Cal3_S2(), nrCameras=3, nrPoints=4): self.K = K - self.Z = [x[:] for x in [[Point2()] * nrPoints] * nrCameras] + self.Z = [x[:] for x in [[gtsam.Point2()] * nrPoints] * nrCameras] self.J = [x[:] for x in [[0] * nrPoints] * nrCameras] - self.odometry = [Pose3()] * nrCameras + self.odometry = [gtsam.Pose3()] * nrCameras # Set Noise parameters self.noiseModels = Data.NoiseModels() - self.noiseModels.posePrior = gtsam.noiseModel_Diagonal.Sigmas( + self.noiseModels.posePrior = gtsam.noiseModel.Diagonal.Sigmas( np.array([0.001, 0.001, 0.001, 0.1, 0.1, 0.1])) - # noiseModels.odometry = gtsam.noiseModel_Diagonal.Sigmas( + # noiseModels.odometry = gtsam.noiseModel.Diagonal.Sigmas( # np.array([0.001,0.001,0.001,0.1,0.1,0.1])) - self.noiseModels.odometry = gtsam.noiseModel_Diagonal.Sigmas( + self.noiseModels.odometry = gtsam.noiseModel.Diagonal.Sigmas( np.array([0.05, 0.05, 0.05, 0.2, 0.2, 0.2])) - self.noiseModels.pointPrior = gtsam.noiseModel_Isotropic.Sigma(3, 0.1) - self.noiseModels.measurement = gtsam.noiseModel_Isotropic.Sigma(2, 1.0) + self.noiseModels.pointPrior = gtsam.noiseModel.Isotropic.Sigma(3, 0.1) + self.noiseModels.measurement = gtsam.noiseModel.Isotropic.Sigma(2, 1.0) def generate_data(options): """ Generate ground-truth and measurement data. """ - K = Cal3_S2(500, 500, 0, 640. / 2., 480. / 2.) + K = gtsam.Cal3_S2(500, 500, 0, 640. / 2., 480. / 2.) nrPoints = 3 if options.triangle else 8 truth = GroundTruth(K=K, nrCameras=options.nrCameras, nrPoints=nrPoints) @@ -84,26 +83,26 @@ def generate_data(options): if options.triangle: # Create a triangle target, just 3 points on a plane r = 10 for j in range(len(truth.points)): - theta = j * 2 * np.pi / nrPoints - truth.points[j] = Point3(r * np.cos(theta), r * np.sin(theta), 0) + theta = j * 2 * pi / nrPoints + truth.points[j] = gtsam.Point3(r * cos(theta), r * sin(theta), 0) else: # 3D landmarks as vertices of a cube truth.points = [ - Point3(10, 10, 10), Point3(-10, 10, 10), - Point3(-10, -10, 10), Point3(10, -10, 10), - Point3(10, 10, -10), Point3(-10, 10, -10), - Point3(-10, -10, -10), Point3(10, -10, -10) + gtsam.Point3(10, 10, 10), gtsam.Point3(-10, 10, 10), + gtsam.Point3(-10, -10, 10), gtsam.Point3(10, -10, 10), + gtsam.Point3(10, 10, -10), gtsam.Point3(-10, 10, -10), + gtsam.Point3(-10, -10, -10), gtsam.Point3(10, -10, -10) ] # Create camera cameras on a circle around the triangle height = 10 r = 40 for i in range(options.nrCameras): - theta = i * 2 * np.pi / options.nrCameras - t = Point3(r * np.cos(theta), r * np.sin(theta), height) - truth.cameras[i] = PinholeCameraCal3_S2.Lookat(t, - Point3(), - Point3(0, 0, 1), - truth.K) + theta = i * 2 * pi / options.nrCameras + t = gtsam.Point3(r * cos(theta), r * sin(theta), height) + truth.cameras[i] = gtsam.SimpleCamera.Lookat(t, + gtsam.Point3(0, 0, 0), + gtsam.Point3(0, 0, 1), + truth.K) # Create measurements for j in range(nrPoints): # All landmarks seen in every frame diff --git a/python/gtsam_py/python/utils/visual_isam.py b/python/gtsam_py/python/utils/visual_isam.py index b0ebe68c3..a8fed4b23 100644 --- a/python/gtsam_py/python/utils/visual_isam.py +++ b/python/gtsam_py/python/utils/visual_isam.py @@ -25,7 +25,7 @@ def initialize(data, truth, options): newFactors = gtsam.NonlinearFactorGraph() initialEstimates = gtsam.Values() for i in range(2): - ii = symbol(ord('x'), i) + ii = symbol('x', i) if i == 0: if options.hardConstraint: # add hard constraint newFactors.add( @@ -41,10 +41,10 @@ def initialize(data, truth, options): # Add visual measurement factors from two first poses and initialize # observed landmarks for i in range(2): - ii = symbol(ord('x'), i) + ii = symbol('x', i) for k in range(len(data.Z[i])): j = data.J[i][k] - jj = symbol(ord('l'), j) + jj = symbol('l', j) newFactors.add( gtsam.GenericProjectionFactorCal3_S2(data.Z[i][ k], data.noiseModels.measurement, ii, jj, data.K)) @@ -59,8 +59,8 @@ def initialize(data, truth, options): # Add odometry between frames 0 and 1 newFactors.add( gtsam.BetweenFactorPose3( - symbol(ord('x'), 0), - symbol(ord('x'), 1), data.odometry[1], data.noiseModels.odometry)) + symbol('x', 0), + symbol('x', 1), data.odometry[1], data.noiseModels.odometry)) # Update ISAM if options.batchInitialization: # Do a full optimize for first two poses @@ -98,28 +98,28 @@ def step(data, isam, result, truth, currPoseIndex): odometry = data.odometry[prevPoseIndex] newFactors.add( gtsam.BetweenFactorPose3( - symbol(ord('x'), prevPoseIndex), - symbol(ord('x'), currPoseIndex), odometry, + symbol('x', prevPoseIndex), + symbol('x', currPoseIndex), odometry, data.noiseModels.odometry)) # Add visual measurement factors and initializations as necessary for k in range(len(data.Z[currPoseIndex])): zij = data.Z[currPoseIndex][k] j = data.J[currPoseIndex][k] - jj = symbol(ord('l'), j) + jj = symbol('l', j) newFactors.add( gtsam.GenericProjectionFactorCal3_S2( zij, data.noiseModels.measurement, - symbol(ord('x'), currPoseIndex), jj, data.K)) + symbol('x', currPoseIndex), jj, data.K)) # TODO: initialize with something other than truth if not result.exists(jj) and not initialEstimates.exists(jj): lmInit = truth.points[j] initialEstimates.insert(jj, lmInit) # Initial estimates for the new pose. - prevPose = result.atPose3(symbol(ord('x'), prevPoseIndex)) + prevPose = result.atPose3(symbol('x', prevPoseIndex)) initialEstimates.insert( - symbol(ord('x'), currPoseIndex), prevPose.compose(odometry)) + symbol('x', currPoseIndex), prevPose.compose(odometry)) # Update ISAM # figure(1)tic diff --git a/python/gtsam_unstable_py/python/examples/FixedLagSmootherExample.py b/python/gtsam_unstable_py/python/examples/FixedLagSmootherExample.py index 786701e0f..7d2cea8ae 100644 --- a/python/gtsam_unstable_py/python/examples/FixedLagSmootherExample.py +++ b/python/gtsam_unstable_py/python/examples/FixedLagSmootherExample.py @@ -16,16 +16,6 @@ import numpy as np import gtsam import gtsam_unstable - -def _timestamp_key_value(key, value): - """ - - """ - return gtsam_unstable.FixedLagSmootherKeyTimestampMapValue( - key, value - ) - - def BatchFixedLagSmootherExample(): """ Runs a batch fixed smoother on an agent with two odometry @@ -45,21 +35,21 @@ def BatchFixedLagSmootherExample(): # Create a prior on the first pose, placing it at the origin prior_mean = gtsam.Pose2(0, 0, 0) - prior_noise = gtsam.noiseModel_Diagonal.Sigmas(np.array([0.3, 0.3, 0.1])) + prior_noise = gtsam.noiseModel.Diagonal.Sigmas(np.array([0.3, 0.3, 0.1])) X1 = 0 new_factors.push_back(gtsam.PriorFactorPose2(X1, prior_mean, prior_noise)) new_values.insert(X1, prior_mean) - new_timestamps.insert(_timestamp_key_value(X1, 0.0)) + new_timestamps.insert((X1, 0.0)) delta_time = 0.25 time = 0.25 while time <= 3.0: - previous_key = 1000 * (time - delta_time) - current_key = 1000 * time + previous_key = int(1000 * (time - delta_time)) + current_key = int(1000 * time) # assign current key to the current timestamp - new_timestamps.insert(_timestamp_key_value(current_key, time)) + new_timestamps.insert((current_key, time)) # Add a guess for this pose to the new values # Assume that the robot moves at 2 m/s. Position is time[s] * 2[m/s] @@ -69,14 +59,14 @@ def BatchFixedLagSmootherExample(): # Add odometry factors from two different sources with different error # stats odometry_measurement_1 = gtsam.Pose2(0.61, -0.08, 0.02) - odometry_noise_1 = gtsam.noiseModel_Diagonal.Sigmas( + odometry_noise_1 = gtsam.noiseModel.Diagonal.Sigmas( np.array([0.1, 0.1, 0.05])) new_factors.push_back(gtsam.BetweenFactorPose2( previous_key, current_key, odometry_measurement_1, odometry_noise_1 )) odometry_measurement_2 = gtsam.Pose2(0.47, 0.03, 0.01) - odometry_noise_2 = gtsam.noiseModel_Diagonal.Sigmas( + odometry_noise_2 = gtsam.noiseModel.Diagonal.Sigmas( np.array([0.05, 0.05, 0.05])) new_factors.push_back(gtsam.BetweenFactorPose2( previous_key, current_key, odometry_measurement_2, odometry_noise_2 diff --git a/python/gtsam_unstable_py/python/examples/TimeOfArrivalExample.py b/python/gtsam_unstable_py/python/examples/TimeOfArrivalExample.py index 6ba06f0f2..59f008a05 100644 --- a/python/gtsam_unstable_py/python/examples/TimeOfArrivalExample.py +++ b/python/gtsam_unstable_py/python/examples/TimeOfArrivalExample.py @@ -12,7 +12,7 @@ Author: Frank Dellaert # pylint: disable=invalid-name, no-name-in-module from gtsam import (LevenbergMarquardtOptimizer, LevenbergMarquardtParams, - NonlinearFactorGraph, Point3, Values, noiseModel_Isotropic) + NonlinearFactorGraph, Point3, Values, noiseModel) from gtsam_unstable import Event, TimeOfArrival, TOAFactor # units @@ -64,7 +64,7 @@ def create_graph(microphones, simulatedTOA): graph = NonlinearFactorGraph() # Create a noise model for the TOA error - model = noiseModel_Isotropic.Sigma(1, 0.5 * MS) + model = noiseModel.Isotropic.Sigma(1, 0.5 * MS) K = len(microphones) key = 0 diff --git a/python/gtsam_unstable_py/python/tests/test_FixedLagSmootherExample.py b/python/gtsam_unstable_py/python/tests/test_FixedLagSmootherExample.py index 8d3af311f..c1ccd1ea1 100644 --- a/python/gtsam_unstable_py/python/tests/test_FixedLagSmootherExample.py +++ b/python/gtsam_unstable_py/python/tests/test_FixedLagSmootherExample.py @@ -16,13 +16,6 @@ import gtsam import gtsam_unstable from gtsam.utils.test_case import GtsamTestCase - -def _timestamp_key_value(key, value): - return gtsam_unstable.FixedLagSmootherKeyTimestampMapValue( - key, value - ) - - class TestFixedLagSmootherExample(GtsamTestCase): ''' Tests the fixed lag smoother wrapper @@ -47,14 +40,14 @@ class TestFixedLagSmootherExample(GtsamTestCase): # Create a prior on the first pose, placing it at the origin prior_mean = gtsam.Pose2(0, 0, 0) - prior_noise = gtsam.noiseModel_Diagonal.Sigmas( + prior_noise = gtsam.noiseModel.Diagonal.Sigmas( np.array([0.3, 0.3, 0.1])) X1 = 0 new_factors.push_back( gtsam.PriorFactorPose2( X1, prior_mean, prior_noise)) new_values.insert(X1, prior_mean) - new_timestamps.insert(_timestamp_key_value(X1, 0.0)) + new_timestamps.insert((X1, 0.0)) delta_time = 0.25 time = 0.25 @@ -80,11 +73,11 @@ class TestFixedLagSmootherExample(GtsamTestCase): # and its two odometers measure the change. The smoothed # result is then compared to the ground truth while time <= 3.0: - previous_key = 1000 * (time - delta_time) - current_key = 1000 * time + previous_key = int(1000 * (time - delta_time)) + current_key = int(1000 * time) # assign current key to the current timestamp - new_timestamps.insert(_timestamp_key_value(current_key, time)) + new_timestamps.insert((current_key, time)) # Add a guess for this pose to the new values # Assume that the robot moves at 2 m/s. Position is time[s] * @@ -95,7 +88,7 @@ class TestFixedLagSmootherExample(GtsamTestCase): # Add odometry factors from two different sources with different # error stats odometry_measurement_1 = gtsam.Pose2(0.61, -0.08, 0.02) - odometry_noise_1 = gtsam.noiseModel_Diagonal.Sigmas( + odometry_noise_1 = gtsam.noiseModel.Diagonal.Sigmas( np.array([0.1, 0.1, 0.05])) new_factors.push_back( gtsam.BetweenFactorPose2( @@ -105,7 +98,7 @@ class TestFixedLagSmootherExample(GtsamTestCase): odometry_noise_1)) odometry_measurement_2 = gtsam.Pose2(0.47, 0.03, 0.01) - odometry_noise_2 = gtsam.noiseModel_Diagonal.Sigmas( + odometry_noise_2 = gtsam.noiseModel.Diagonal.Sigmas( np.array([0.05, 0.05, 0.05])) new_factors.push_back( gtsam.BetweenFactorPose2( From 2bda74950a6fc2f97f4323029d7340a67de15958 Mon Sep 17 00:00:00 2001 From: Fan Jiang Date: Mon, 27 Jul 2020 10:56:09 -0400 Subject: [PATCH 271/869] Sync ImuFactorExample --- .../python/examples/ImuFactorExample.py | 46 ++-- python/gtsam_py/python/utils/plot.py | 200 +++++++++++++++--- 2 files changed, 197 insertions(+), 49 deletions(-) diff --git a/python/gtsam_py/python/examples/ImuFactorExample.py b/python/gtsam_py/python/examples/ImuFactorExample.py index adaa3c08a..e041afd87 100644 --- a/python/gtsam_py/python/examples/ImuFactorExample.py +++ b/python/gtsam_py/python/examples/ImuFactorExample.py @@ -5,32 +5,29 @@ All Rights Reserved See LICENSE for the license information -A script validating the ImuFactor inference. +A script validating and demonstrating the ImuFactor inference. + +Author: Frank Dellaert, Varun Agrawal """ from __future__ import print_function import math +import gtsam import matplotlib.pyplot as plt import numpy as np +from gtsam import symbol_shorthand +B = symbol_shorthand.B +V = symbol_shorthand.V +X = symbol_shorthand.X + +from gtsam.utils.plot import plot_pose3 from mpl_toolkits.mplot3d import Axes3D -import gtsam -from gtsam.utils.plot import plot_pose3 from PreintegrationExample import POSES_FIG, PreintegrationExample -BIAS_KEY = int(gtsam.symbol('b', 0)) - - -def X(key): - """Create symbol for pose key.""" - return gtsam.symbol('x', key) - - -def V(key): - """Create symbol for velocity key.""" - return gtsam.symbol('v', key) +BIAS_KEY = B(0) np.set_printoptions(precision=3, suppress=True) @@ -76,8 +73,14 @@ class ImuFactorExample(PreintegrationExample): initial.insert(BIAS_KEY, self.actualBias) for i in range(num_poses): state_i = self.scenario.navState(float(i)) - initial.insert(X(i), state_i.pose()) - initial.insert(V(i), state_i.velocity()) + + poseNoise = gtsam.Pose3.Expmap(np.random.randn(3)*0.1) + pose = state_i.pose().compose(poseNoise) + + velocity = state_i.velocity() + np.random.randn(3)*0.1 + + initial.insert(X(i), pose) + initial.insert(V(i), velocity) # simulate the loop i = 0 # state index @@ -88,6 +91,12 @@ class ImuFactorExample(PreintegrationExample): measuredAcc = self.runner.measuredSpecificForce(t) pim.integrateMeasurement(measuredAcc, measuredOmega, self.dt) + poseNoise = gtsam.Pose3.Expmap(np.random.randn(3)*0.1) + + actual_state_i = gtsam.NavState( + actual_state_i.pose().compose(poseNoise), + actual_state_i.velocity() + np.random.randn(3)*0.1) + # Plot IMU many times if k % 10 == 0: self.plotImu(t, measuredOmega, measuredAcc) @@ -133,7 +142,10 @@ class ImuFactorExample(PreintegrationExample): pose_i = result.atPose3(X(i)) plot_pose3(POSES_FIG, pose_i, 0.1) i += 1 - print(result.atimuBias.ConstantBias(BIAS_KEY)) + + gtsam.utils.plot.set_axes_equal(POSES_FIG) + + print(result.atConstantBias(BIAS_KEY)) plt.ioff() plt.show() diff --git a/python/gtsam_py/python/utils/plot.py b/python/gtsam_py/python/utils/plot.py index 7b8da0f06..276cefd54 100644 --- a/python/gtsam_py/python/utils/plot.py +++ b/python/gtsam_py/python/utils/plot.py @@ -13,8 +13,9 @@ def set_axes_equal(fignum): Make axes of 3D plot have equal scale so that spheres appear as spheres, cubes as cubes, etc.. This is one possible solution to Matplotlib's ax.set_aspect('equal') and ax.axis('equal') not working for 3D. - Input - ax: a matplotlib axis, e.g., as output from plt.gca(). + + Args: + fignum (int): An integer representing the figure number for Matplotlib. """ fig = plt.figure(fignum) ax = fig.gca(projection='3d') @@ -34,7 +35,21 @@ def set_axes_equal(fignum): def ellipsoid(xc, yc, zc, rx, ry, rz, n): - """Numpy equivalent of Matlab's ellipsoid function""" + """ + Numpy equivalent of Matlab's ellipsoid function. + + Args: + xc (double): Center of ellipsoid in X-axis. + yc (double): Center of ellipsoid in Y-axis. + zc (double): Center of ellipsoid in Z-axis. + rx (double): Radius of ellipsoid in X-axis. + ry (double): Radius of ellipsoid in Y-axis. + rz (double): Radius of ellipsoid in Z-axis. + n (int): The granularity of the ellipsoid plotted. + + Returns: + tuple[numpy.ndarray]: The points in the x, y and z axes to use for the surface plot. + """ u = np.linspace(0, 2*np.pi, n+1) v = np.linspace(0, np.pi, n+1) x = -rx * np.outer(np.cos(u), np.sin(v)).T @@ -47,9 +62,18 @@ def ellipsoid(xc, yc, zc, rx, ry, rz, n): def plot_covariance_ellipse_3d(axes, origin, P, scale=1, n=8, alpha=0.5): """ Plots a Gaussian as an uncertainty ellipse + Based on Maybeck Vol 1, page 366 k=2.296 corresponds to 1 std, 68.26% of all probability k=11.82 corresponds to 3 std, 99.74% of all probability + + Args: + axes (matplotlib.axes.Axes): Matplotlib axes. + origin (gtsam.Point3): The origin in the world frame. + P (numpy.ndarray): The marginal covariance matrix of the 3D point which will be represented as an ellipse. + scale (float): Scaling factor of the radii of the covariance ellipse. + n (int): Defines the granularity of the ellipse. Higher values indicate finer ellipses. + alpha (float): Transparency value for the plotted surface in the range [0, 1]. """ k = 11.82 U, S, _ = np.linalg.svd(P) @@ -73,10 +97,19 @@ def plot_covariance_ellipse_3d(axes, origin, P, scale=1, n=8, alpha=0.5): def plot_pose2_on_axes(axes, pose, axis_length=0.1, covariance=None): - """Plot a 2D pose on given axis 'axes' with given 'axis_length'.""" + """ + Plot a 2D pose on given axis `axes` with given `axis_length`. + + Args: + axes (matplotlib.axes.Axes): Matplotlib axes. + pose (gtsam.Pose2): The pose to be plotted. + axis_length (float): The length of the camera axes. + covariance (numpy.ndarray): Marginal covariance matrix to plot the uncertainty of the estimation. + """ # get rotation and translation (center) gRp = pose.rotation().matrix() # rotation from pose to global - origin = pose.translation() + t = pose.translation() + origin = np.array([t.x(), t.y()]) # draw the camera axes x_axis = origin + gRp[:, 0] * axis_length @@ -101,34 +134,89 @@ def plot_pose2_on_axes(axes, pose, axis_length=0.1, covariance=None): np.rad2deg(angle), fill=False) axes.add_patch(e1) -def plot_pose2(fignum, pose, axis_length=0.1, covariance=None): - """Plot a 2D pose on given figure with given 'axis_length'.""" + +def plot_pose2(fignum, pose, axis_length=0.1, covariance=None, + axis_labels=('X axis', 'Y axis', 'Z axis')): + """ + Plot a 2D pose on given figure with given `axis_length`. + + Args: + fignum (int): Integer representing the figure number to use for plotting. + pose (gtsam.Pose2): The pose to be plotted. + axis_length (float): The length of the camera axes. + covariance (numpy.ndarray): Marginal covariance matrix to plot the uncertainty of the estimation. + axis_labels (iterable[string]): List of axis labels to set. + """ # get figure object fig = plt.figure(fignum) axes = fig.gca() - plot_pose2_on_axes(axes, pose, axis_length, covariance) + plot_pose2_on_axes(axes, pose, axis_length=axis_length, + covariance=covariance) + + axes.set_xlabel(axis_labels[0]) + axes.set_ylabel(axis_labels[1]) + axes.set_zlabel(axis_labels[2]) + + return fig def plot_point3_on_axes(axes, point, linespec, P=None): - """Plot a 3D point on given axis 'axes' with given 'linespec' and optional covariance 'P'.""" - axes.plot([point[0]], [point[1]], [point[2]], linespec) + """ + Plot a 3D point on given axis `axes` with given `linespec`. + + Args: + axes (matplotlib.axes.Axes): Matplotlib axes. + point (gtsam.Point3): The point to be plotted. + linespec (string): String representing formatting options for Matplotlib. + P (numpy.ndarray): Marginal covariance matrix to plot the uncertainty of the estimation. + """ + axes.plot([point.x()], [point.y()], [point.z()], linespec) if P is not None: - plot_covariance_ellipse_3d(axes, point.vector(), P) + plot_covariance_ellipse_3d(axes, point, P) -def plot_point3(fignum, point, linespec, P=None): - """Plot a 3D point on given figure with given 'linespec' and optional covariance 'P'.""" +def plot_point3(fignum, point, linespec, P=None, + axis_labels=('X axis', 'Y axis', 'Z axis')): + """ + Plot a 3D point on given figure with given `linespec`. + + Args: + fignum (int): Integer representing the figure number to use for plotting. + point (gtsam.Point3): The point to be plotted. + linespec (string): String representing formatting options for Matplotlib. + P (numpy.ndarray): Marginal covariance matrix to plot the uncertainty of the estimation. + axis_labels (iterable[string]): List of axis labels to set. + + Returns: + fig: The matplotlib figure. + + """ fig = plt.figure(fignum) axes = fig.gca(projection='3d') plot_point3_on_axes(axes, point, linespec, P) + axes.set_xlabel(axis_labels[0]) + axes.set_ylabel(axis_labels[1]) + axes.set_zlabel(axis_labels[2]) -def plot_3d_points(fignum, values, linespec="g*", marginals=None): + return fig + + +def plot_3d_points(fignum, values, linespec="g*", marginals=None, + title="3D Points", axis_labels=('X axis', 'Y axis', 'Z axis')): """ - Plots the Point3s in 'values', with optional covariances. + Plots the Point3s in `values`, with optional covariances. Finds all the Point3 objects in the given Values object and plots them. If a Marginals object is given, this function will also plot marginal covariance ellipses for each point. + + Args: + fignum (int): Integer representing the figure number to use for plotting. + values (gtsam.Values): Values dictionary consisting of points to be plotted. + linespec (string): String representing formatting options for Matplotlib. + marginals (numpy.ndarray): Marginal covariance matrix to plot the uncertainty of the estimation. + title (string): The title of the plot. + axis_labels (iterable[string]): List of axis labels to set. """ keys = values.keys() @@ -139,21 +227,30 @@ def plot_3d_points(fignum, values, linespec="g*", marginals=None): key = keys.at(i) point = values.atPoint3(key) if marginals is not None: - P = marginals.marginalCovariance(key); + covariance = marginals.marginalCovariance(key) else: - P = None + covariance = None - plot_point3(fignum, point, linespec, P) + fig = plot_point3(fignum, point, linespec, covariance, + axis_labels=axis_labels) except RuntimeError: continue # I guess it's not a Point3 + fig.suptitle(title) + fig.canvas.set_window_title(title.lower()) -def plot_pose3_on_axes(axes, pose, P=None, scale=1, axis_length=0.1): + +def plot_pose3_on_axes(axes, pose, axis_length=0.1, P=None, scale=1): """ - Plot a 3D pose on given axis 'axes' with given 'axis_length'. - Optional 'scale' the pose and plot the covariance 'P'. + Plot a 3D pose on given axis `axes` with given `axis_length`. + + Args: + axes (matplotlib.axes.Axes): Matplotlib axes. + point (gtsam.Point3): The point to be plotted. + linespec (string): String representing formatting options for Matplotlib. + P (numpy.ndarray): Marginal covariance matrix to plot the uncertainty of the estimation. """ # get rotation and translation (center) gRp = pose.rotation().matrix() # rotation from pose to global @@ -172,6 +269,7 @@ def plot_pose3_on_axes(axes, pose, P=None, scale=1, axis_length=0.1): line = np.append(origin[np.newaxis], z_axis[np.newaxis], axis=0) axes.plot(line[:, 0], line[:, 1], line[:, 2], 'b-') + # plot the covariance if P is not None: # covariance matrix in pose coordinate frame pPp = P[3:6, 3:6] @@ -180,16 +278,49 @@ def plot_pose3_on_axes(axes, pose, P=None, scale=1, axis_length=0.1): plot_covariance_ellipse_3d(axes, origin, gPp) -def plot_pose3(fignum, pose, P, axis_length=0.1): - """Plot a 3D pose on given figure with given 'axis_length'.""" +def plot_pose3(fignum, pose, axis_length=0.1, P=None, + axis_labels=('X axis', 'Y axis', 'Z axis')): + """ + Plot a 3D pose on given figure with given `axis_length`. + + Args: + fignum (int): Integer representing the figure number to use for plotting. + pose (gtsam.Pose3): 3D pose to be plotted. + linespec (string): String representing formatting options for Matplotlib. + P (numpy.ndarray): Marginal covariance matrix to plot the uncertainty of the estimation. + axis_labels (iterable[string]): List of axis labels to set. + + Returns: + fig: The matplotlib figure. + """ # get figure object fig = plt.figure(fignum) axes = fig.gca(projection='3d') - plot_pose3_on_axes(axes, pose, P=P, axis_length=axis_length) + plot_pose3_on_axes(axes, pose, P=P, + axis_length=axis_length) + + axes.set_xlabel(axis_labels[0]) + axes.set_ylabel(axis_labels[1]) + axes.set_zlabel(axis_labels[2]) + + return fig -def plot_trajectory(fignum, values, scale=1, marginals=None): - pose3Values = gtsam.allPose3s(values) +def plot_trajectory(fignum, values, scale=1, marginals=None, + title="Plot Trajectory", axis_labels=('X axis', 'Y axis', 'Z axis')): + """ + Plot a complete 3D trajectory using poses in `values`. + + Args: + fignum (int): Integer representing the figure number to use for plotting. + values (gtsam.Values): Values dict containing the poses. + scale (float): Value to scale the poses by. + marginals (gtsam.Marginals): Marginalized probability values of the estimation. + Used to plot uncertainty bounds. + title (string): The title of the plot. + axis_labels (iterable[string]): List of axis labels to set. + """ + pose3Values = gtsam.utilities_allPose3s(values) keys = gtsam.KeyVector(pose3Values.keys()) lastIndex = None @@ -209,11 +340,12 @@ def plot_trajectory(fignum, values, scale=1, marginals=None): pass if marginals: - P = marginals.marginalCovariance(lastKey) + covariance = marginals.marginalCovariance(lastKey) else: - P = None + covariance = None - plot_pose3(fignum, lastPose, P, scale) + fig = plot_pose3(fignum, lastPose, P=covariance, + axis_length=scale, axis_labels=axis_labels) lastIndex = i @@ -223,11 +355,15 @@ def plot_trajectory(fignum, values, scale=1, marginals=None): try: lastPose = pose3Values.atPose3(lastKey) if marginals: - P = marginals.marginalCovariance(lastKey) + covariance = marginals.marginalCovariance(lastKey) else: - P = None + covariance = None - plot_pose3(fignum, lastPose, P, scale) + fig = plot_pose3(fignum, lastPose, P=covariance, + axis_length=scale, axis_labels=axis_labels) except: pass + + fig.suptitle(title) + fig.canvas.set_window_title(title.lower()) From 48b0c845dc92d46389c8bd57097cd2ce80f644fe Mon Sep 17 00:00:00 2001 From: Fan Jiang Date: Mon, 27 Jul 2020 11:01:59 -0400 Subject: [PATCH 272/869] Sync ImuFactorExample2 --- .../python/examples/ImuFactorExample2.py | 70 +++++++++---------- 1 file changed, 33 insertions(+), 37 deletions(-) diff --git a/python/gtsam_py/python/examples/ImuFactorExample2.py b/python/gtsam_py/python/examples/ImuFactorExample2.py index 39e22eb17..4f4b02f63 100644 --- a/python/gtsam_py/python/examples/ImuFactorExample2.py +++ b/python/gtsam_py/python/examples/ImuFactorExample2.py @@ -8,22 +8,20 @@ from __future__ import print_function import math -import matplotlib.pyplot as plt -import numpy as np -from mpl_toolkits.mplot3d import Axes3D # pylint: disable=W0611 - import gtsam import gtsam.utils.plot as gtsam_plot - - -def X(key): - """Create symbol for pose key.""" - return gtsam.symbol('x', key) - - -def V(key): - """Create symbol for velocity key.""" - return gtsam.symbol('v', key) +import matplotlib.pyplot as plt +import numpy as np +from gtsam import (ISAM2, BetweenFactorConstantBias, Cal3_S2, + ConstantTwistScenario, ImuFactor, NonlinearFactorGraph, + PinholeCameraCal3_S2, Point3, Pose3, + PriorFactorConstantBias, PriorFactorPose3, + PriorFactorVector, Rot3, Values) +from gtsam import symbol_shorthand +B = symbol_shorthand.B +V = symbol_shorthand.V +X = symbol_shorthand.X +from mpl_toolkits.mplot3d import Axes3D # pylint: disable=W0611 def vector3(x, y, z): @@ -69,20 +67,19 @@ PARAMS.setUse2ndOrderCoriolis(False) PARAMS.setOmegaCoriolis(vector3(0, 0, 0)) BIAS_COVARIANCE = gtsam.noiseModel.Isotropic.Variance(6, 0.1) -DELTA = gtsam.Pose3(gtsam.Rot3.Rodrigues(0, 0, 0), - gtsam.Point3(0.05, -0.10, 0.20)) +DELTA = Pose3(Rot3.Rodrigues(0, 0, 0), + Point3(0.05, -0.10, 0.20)) def IMU_example(): """Run iSAM 2 example with IMU factor.""" - ZERO_BIAS = gtsam.imuBias.ConstantBias() # Start with a camera on x-axis looking at origin radius = 30 - up = gtsam.Point3(0, 0, 1) - target = gtsam.Point3(0, 0, 0) - position = gtsam.Point3(radius, 0, 0) - camera = gtsam.SimpleCamera.Lookat(position, target, up, gtsam.Cal3_S2()) + up = Point3(0, 0, 1) + target = Point3(0, 0, 0) + position = Point3(radius, 0, 0) + camera = PinholeCameraCal3_S2.Lookat(position, target, up, Cal3_S2()) pose_0 = camera.pose() # Create the set of ground-truth landmarks and poses @@ -91,37 +88,37 @@ def IMU_example(): angular_velocity_vector = vector3(0, -angular_velocity, 0) linear_velocity_vector = vector3(radius * angular_velocity, 0, 0) - scenario = gtsam.ConstantTwistScenario( + scenario = ConstantTwistScenario( angular_velocity_vector, linear_velocity_vector, pose_0) # Create a factor graph - newgraph = gtsam.NonlinearFactorGraph() + newgraph = NonlinearFactorGraph() # Create (incremental) ISAM2 solver - isam = gtsam.ISAM2() + isam = ISAM2() # Create the initial estimate to the solution # Intentionally initialize the variables off from the ground truth - initialEstimate = gtsam.Values() + initialEstimate = Values() # Add a prior on pose x0. This indirectly specifies where the origin is. # 30cm std on x,y,z 0.1 rad on roll,pitch,yaw noise = gtsam.noiseModel.Diagonal.Sigmas( np.array([0.1, 0.1, 0.1, 0.3, 0.3, 0.3])) - newgraph.push_back(gtsam.PriorFactorPose3(X(0), pose_0, noise)) + newgraph.push_back(PriorFactorPose3(X(0), pose_0, noise)) # Add imu priors - biasKey = gtsam.symbol('b', 0) + biasKey = B(0) biasnoise = gtsam.noiseModel.Isotropic.Sigma(6, 0.1) - biasprior = gtsam.PriorFactorConstantBias(biasKey, ZERO_BIAS, - biasnoise) + biasprior = PriorFactorConstantBias(biasKey, gtsam.imuBias.ConstantBias(), + biasnoise) newgraph.push_back(biasprior) - initialEstimate.insert(biasKey, ZERO_BIAS) + initialEstimate.insert(biasKey, gtsam.imuBias.ConstantBias()) velnoise = gtsam.noiseModel.Isotropic.Sigma(3, 0.1) # Calculate with correct initial velocity n_velocity = vector3(0, angular_velocity * radius, 0) - velprior = gtsam.PriorFactorVector(V(0), n_velocity, velnoise) + velprior = PriorFactorVector(V(0), n_velocity, velnoise) newgraph.push_back(velprior) initialEstimate.insert(V(0), n_velocity) @@ -142,10 +139,10 @@ def IMU_example(): # Add Bias variables periodically if i % 5 == 0: biasKey += 1 - factor = gtsam.BetweenFactorConstantBias( - biasKey - 1, biasKey, ZERO_BIAS, BIAS_COVARIANCE) + factor = BetweenFactorConstantBias( + biasKey - 1, biasKey, gtsam.imuBias.ConstantBias(), BIAS_COVARIANCE) newgraph.add(factor) - initialEstimate.insert(biasKey, ZERO_BIAS) + initialEstimate.insert(biasKey, gtsam.imuBias.ConstantBias()) # Predict acceleration and gyro measurements in (actual) body frame nRb = scenario.rotation(t).matrix() @@ -155,8 +152,7 @@ def IMU_example(): accum.integrateMeasurement(measuredAcc, measuredOmega, delta_t) # Add Imu Factor - imufac = gtsam.ImuFactor( - X(i - 1), V(i - 1), X(i), V(i), biasKey, accum) + imufac = ImuFactor(X(i - 1), V(i - 1), X(i), V(i), biasKey, accum) newgraph.add(imufac) # insert new velocity, which is wrong @@ -169,7 +165,7 @@ def IMU_example(): ISAM2_plot(result) # reset - newgraph = gtsam.NonlinearFactorGraph() + newgraph = NonlinearFactorGraph() initialEstimate.clear() From 128db80fec87a261a27bc3b55377b2c834ca9457 Mon Sep 17 00:00:00 2001 From: Fan Jiang Date: Mon, 27 Jul 2020 11:17:06 -0400 Subject: [PATCH 273/869] Fix Pose2 plot --- python/gtsam_py/python/utils/plot.py | 5 ++--- 1 file changed, 2 insertions(+), 3 deletions(-) diff --git a/python/gtsam_py/python/utils/plot.py b/python/gtsam_py/python/utils/plot.py index 276cefd54..eef08ac88 100644 --- a/python/gtsam_py/python/utils/plot.py +++ b/python/gtsam_py/python/utils/plot.py @@ -109,7 +109,7 @@ def plot_pose2_on_axes(axes, pose, axis_length=0.1, covariance=None): # get rotation and translation (center) gRp = pose.rotation().matrix() # rotation from pose to global t = pose.translation() - origin = np.array([t.x(), t.y()]) + origin = np.array(t) # draw the camera axes x_axis = origin + gRp[:, 0] * axis_length @@ -155,7 +155,6 @@ def plot_pose2(fignum, pose, axis_length=0.1, covariance=None, axes.set_xlabel(axis_labels[0]) axes.set_ylabel(axis_labels[1]) - axes.set_zlabel(axis_labels[2]) return fig @@ -170,7 +169,7 @@ def plot_point3_on_axes(axes, point, linespec, P=None): linespec (string): String representing formatting options for Matplotlib. P (numpy.ndarray): Marginal covariance matrix to plot the uncertainty of the estimation. """ - axes.plot([point.x()], [point.y()], [point.z()], linespec) + axes.plot([point[0]], [point[1]], [point[2]], linespec) if P is not None: plot_covariance_ellipse_3d(axes, point, P) From 7b4266ed6be3b601b04dc7edba1df9957a270321 Mon Sep 17 00:00:00 2001 From: Fan Jiang Date: Mon, 27 Jul 2020 14:35:28 -0400 Subject: [PATCH 274/869] Update to match cython --- .../python/examples/ImuFactorExample.py | 5 +-- .../python/examples/ImuFactorExample2.py | 5 +-- .../python/examples/PlanarSLAMExample.py | 11 ++++--- .../python/examples/Pose2SLAMExample_g2o.py | 2 +- .../python/examples/Pose3SLAMExample_g2o.py | 4 +-- .../python/examples/PreintegrationExample.py | 2 +- python/gtsam_py/python/examples/README.md | 14 +++----- python/gtsam_py/python/examples/SFMExample.py | 32 ++++++++----------- python/gtsam_py/python/utils/plot.py | 14 ++++---- 9 files changed, 37 insertions(+), 52 deletions(-) diff --git a/python/gtsam_py/python/examples/ImuFactorExample.py b/python/gtsam_py/python/examples/ImuFactorExample.py index e041afd87..1f8dfca07 100644 --- a/python/gtsam_py/python/examples/ImuFactorExample.py +++ b/python/gtsam_py/python/examples/ImuFactorExample.py @@ -17,10 +17,7 @@ import math import gtsam import matplotlib.pyplot as plt import numpy as np -from gtsam import symbol_shorthand -B = symbol_shorthand.B -V = symbol_shorthand.V -X = symbol_shorthand.X +from gtsam.gtsam.symbol_shorthand import B, V, X from gtsam.utils.plot import plot_pose3 from mpl_toolkits.mplot3d import Axes3D diff --git a/python/gtsam_py/python/examples/ImuFactorExample2.py b/python/gtsam_py/python/examples/ImuFactorExample2.py index 4f4b02f63..d5be69f47 100644 --- a/python/gtsam_py/python/examples/ImuFactorExample2.py +++ b/python/gtsam_py/python/examples/ImuFactorExample2.py @@ -17,10 +17,7 @@ from gtsam import (ISAM2, BetweenFactorConstantBias, Cal3_S2, PinholeCameraCal3_S2, Point3, Pose3, PriorFactorConstantBias, PriorFactorPose3, PriorFactorVector, Rot3, Values) -from gtsam import symbol_shorthand -B = symbol_shorthand.B -V = symbol_shorthand.V -X = symbol_shorthand.X +from gtsam.gtsam.symbol_shorthand import B, V, X from mpl_toolkits.mplot3d import Axes3D # pylint: disable=W0611 diff --git a/python/gtsam_py/python/examples/PlanarSLAMExample.py b/python/gtsam_py/python/examples/PlanarSLAMExample.py index 0baf2fa9a..ba0529479 100644 --- a/python/gtsam_py/python/examples/PlanarSLAMExample.py +++ b/python/gtsam_py/python/examples/PlanarSLAMExample.py @@ -16,6 +16,7 @@ from __future__ import print_function import numpy as np import gtsam +from gtsam.gtsam.symbol_shorthand import X, L # Create noise models PRIOR_NOISE = gtsam.noiseModel.Diagonal.Sigmas(np.array([0.3, 0.3, 0.1])) @@ -26,11 +27,11 @@ MEASUREMENT_NOISE = gtsam.noiseModel.Diagonal.Sigmas(np.array([0.1, 0.2])) graph = gtsam.NonlinearFactorGraph() # Create the keys corresponding to unknown variables in the factor graph -X1 = gtsam.symbol('x', 1) -X2 = gtsam.symbol('x', 2) -X3 = gtsam.symbol('x', 3) -L1 = gtsam.symbol('l', 4) -L2 = gtsam.symbol('l', 5) +X1 = X(1) +X2 = X(2) +X3 = X(3) +L1 = L(4) +L2 = L(5) # Add a prior on pose X1 at the origin. A prior factor consists of a mean and a noise model graph.add(gtsam.PriorFactorPose2(X1, gtsam.Pose2(0.0, 0.0, 0.0), PRIOR_NOISE)) diff --git a/python/gtsam_py/python/examples/Pose2SLAMExample_g2o.py b/python/gtsam_py/python/examples/Pose2SLAMExample_g2o.py index d27adfc2c..1ea7fc300 100644 --- a/python/gtsam_py/python/examples/Pose2SLAMExample_g2o.py +++ b/python/gtsam_py/python/examples/Pose2SLAMExample_g2o.py @@ -83,7 +83,7 @@ else: print ("Done!") if args.plot: - resultPoses = gtsam.extractPose2(result) + resultPoses = gtsam.utilities.extractPose2(result) for i in range(resultPoses.shape[0]): plot.plot_pose2(1, gtsam.Pose2(resultPoses[i, :])) plt.show() diff --git a/python/gtsam_py/python/examples/Pose3SLAMExample_g2o.py b/python/gtsam_py/python/examples/Pose3SLAMExample_g2o.py index 20b02500e..c06a9d12f 100644 --- a/python/gtsam_py/python/examples/Pose3SLAMExample_g2o.py +++ b/python/gtsam_py/python/examples/Pose3SLAMExample_g2o.py @@ -44,7 +44,7 @@ priorModel = gtsam.noiseModel.Diagonal.Variances(vector6(1e-6, 1e-6, 1e-6, print("Adding prior to g2o file ") graphWithPrior = graph -firstKey = initial.keys().at(0) +firstKey = initial.keys()[0] graphWithPrior.add(gtsam.PriorFactorPose3(firstKey, gtsam.Pose3(), priorModel)) params = gtsam.GaussNewtonParams() @@ -66,7 +66,7 @@ else: print ("Done!") if args.plot: - resultPoses = gtsam.allPose3s(result) + resultPoses = gtsam.utilities.allPose3s(result) for i in range(resultPoses.size()): plot.plot_pose3(1, resultPoses.atPose3(i)) plt.show() diff --git a/python/gtsam_py/python/examples/PreintegrationExample.py b/python/gtsam_py/python/examples/PreintegrationExample.py index e543e5d82..ee7f9cd8f 100644 --- a/python/gtsam_py/python/examples/PreintegrationExample.py +++ b/python/gtsam_py/python/examples/PreintegrationExample.py @@ -111,7 +111,7 @@ class PreintegrationExample(object): actualPose = self.scenario.pose(t) plot_pose3(POSES_FIG, actualPose, 0.3) t = actualPose.translation() - self.maxDim = max([max(t), self.maxDim]) + self.maxDim = max([max(np.abs(t)), self.maxDim]) ax = plt.gca() ax.set_xlim3d(-self.maxDim, self.maxDim) ax.set_ylim3d(-self.maxDim, self.maxDim) diff --git a/python/gtsam_py/python/examples/README.md b/python/gtsam_py/python/examples/README.md index ec4437d4c..46b87f079 100644 --- a/python/gtsam_py/python/examples/README.md +++ b/python/gtsam_py/python/examples/README.md @@ -1,18 +1,12 @@ -# THIS FILE IS OUTDATED! - -~~These examples are almost identical to the old handwritten python wrapper examples. However, there are just some slight name changes, for example `noiseModel.Diagonal` becomes `noiseModel.Diagonal` etc...~~ - -~~Also, annoyingly, instead of `gtsam.Symbol('b', 0)` we now need to say `gtsam.symbol('b', 0))`~~ - # Porting Progress | C++ Example Name | Ported | |-------------------------------------------------------|--------| | CameraResectioning | | | CreateSFMExampleData | | -| DiscreteBayesNet_FG | none of the required discrete functionality is exposed through cython | -| easyPoint2KalmanFilter | ExtendedKalmanFilter not exposed through cython | -| elaboratePoint2KalmanFilter | GaussianSequentialSolver not exposed through cython | +| DiscreteBayesNet_FG | none of the required discrete functionality is exposed through Python | +| easyPoint2KalmanFilter | ExtendedKalmanFilter not exposed through Python | +| elaboratePoint2KalmanFilter | GaussianSequentialSolver not exposed through Python | | ImuFactorExample2 | X | | ImuFactorsExample | | | ISAM2Example_SmartFactor | | @@ -26,7 +20,7 @@ | Pose2SLAMExample_g2o | X | | Pose2SLAMExample_graph | | | Pose2SLAMExample_graphviz | | -| Pose2SLAMExample_lago | lago not exposed through cython | +| Pose2SLAMExample_lago | lago not exposed through Python | | Pose2SLAMStressTest | | | Pose2SLAMwSPCG | | | Pose3SLAMExample_changeKeys | | diff --git a/python/gtsam_py/python/examples/SFMExample.py b/python/gtsam_py/python/examples/SFMExample.py index 0c03a105d..f0c4c82ba 100644 --- a/python/gtsam_py/python/examples/SFMExample.py +++ b/python/gtsam_py/python/examples/SFMExample.py @@ -10,24 +10,21 @@ A structure-from-motion problem on a simulated dataset """ from __future__ import print_function +import gtsam import matplotlib.pyplot as plt import numpy as np +from gtsam import symbol_shorthand +L = symbol_shorthand.L +X = symbol_shorthand.X -import gtsam from gtsam.examples import SFMdata -from gtsam.gtsam import (Cal3_S2, DoglegOptimizer, +from gtsam import (Cal3_S2, DoglegOptimizer, GenericProjectionFactorCal3_S2, Marginals, - NonlinearFactorGraph, Point3, Pose3, - PriorFactorPoint3, PriorFactorPose3, Rot3, - SimpleCamera, Values) + NonlinearFactorGraph, PinholeCameraCal3_S2, Point3, + Pose3, PriorFactorPoint3, PriorFactorPose3, Rot3, Values) from gtsam.utils import plot -def symbol(name: str, index: int) -> int: - """ helper for creating a symbol without explicitly casting 'name' from str to int """ - return gtsam.symbol(name, index) - - def main(): """ Camera observations of landmarks (i.e. pixel coordinates) will be stored as Point2 (x, y). @@ -74,23 +71,23 @@ def main(): # Add a prior on pose x1. This indirectly specifies where the origin is. # 0.3 rad std on roll,pitch,yaw and 0.1m on x,y,z pose_noise = gtsam.noiseModel.Diagonal.Sigmas(np.array([0.3, 0.3, 0.3, 0.1, 0.1, 0.1])) - factor = PriorFactorPose3(symbol('x', 0), poses[0], pose_noise) + factor = PriorFactorPose3(X(0), poses[0], pose_noise) graph.push_back(factor) # Simulated measurements from each camera pose, adding them to the factor graph for i, pose in enumerate(poses): - camera = SimpleCamera(pose, K) + camera = PinholeCameraCal3_S2(pose, K) for j, point in enumerate(points): measurement = camera.project(point) factor = GenericProjectionFactorCal3_S2( - measurement, measurement_noise, symbol('x', i), symbol('l', j), K) + measurement, measurement_noise, X(i), L(j), K) graph.push_back(factor) # Because the structure-from-motion problem has a scale ambiguity, the problem is still under-constrained # Here we add a prior on the position of the first landmark. This fixes the scale by indicating the distance # between the first camera and the first landmark. All other landmark positions are interpreted using this scale. point_noise = gtsam.noiseModel.Isotropic.Sigma(3, 0.1) - factor = PriorFactorPoint3(symbol('l', 0), points[0], point_noise) + factor = PriorFactorPoint3(L(0), points[0], point_noise) graph.push_back(factor) graph.print_('Factor Graph:\n') @@ -99,10 +96,10 @@ def main(): initial_estimate = Values() for i, pose in enumerate(poses): transformed_pose = pose.retract(0.1*np.random.randn(6,1)) - initial_estimate.insert(symbol('x', i), transformed_pose) + initial_estimate.insert(X(i), transformed_pose) for j, point in enumerate(points): - transformed_point = Point3(point.vector() + 0.1*np.random.randn(3)) - initial_estimate.insert(symbol('l', j), transformed_point) + transformed_point = point + 0.1*np.random.randn(3) + initial_estimate.insert(L(j), transformed_point) initial_estimate.print_('Initial Estimates:\n') # Optimize the graph and print results @@ -121,6 +118,5 @@ def main(): plot.set_axes_equal(1) plt.show() - if __name__ == '__main__': main() diff --git a/python/gtsam_py/python/utils/plot.py b/python/gtsam_py/python/utils/plot.py index eef08ac88..ce602f506 100644 --- a/python/gtsam_py/python/utils/plot.py +++ b/python/gtsam_py/python/utils/plot.py @@ -221,9 +221,9 @@ def plot_3d_points(fignum, values, linespec="g*", marginals=None, keys = values.keys() # Plot points and covariance matrices - for i in range(keys.size()): + for i in range(len(keys)): try: - key = keys.at(i) + key = keys[i] point = values.atPoint3(key) if marginals is not None: covariance = marginals.marginalCovariance(key) @@ -319,19 +319,19 @@ def plot_trajectory(fignum, values, scale=1, marginals=None, title (string): The title of the plot. axis_labels (iterable[string]): List of axis labels to set. """ - pose3Values = gtsam.utilities_allPose3s(values) + pose3Values = gtsam.utilities.allPose3s(values) keys = gtsam.KeyVector(pose3Values.keys()) lastIndex = None - for i in range(keys.size()): - key = keys.at(i) + for i in range(len(keys)): + key = keys[i] try: pose = pose3Values.atPose3(key) except: print("Warning: no Pose3 at key: {0}".format(key)) if lastIndex is not None: - lastKey = keys.at(lastIndex) + lastKey = keys[lastIndex] try: lastPose = pose3Values.atPose3(lastKey) except: @@ -350,7 +350,7 @@ def plot_trajectory(fignum, values, scale=1, marginals=None, # Draw final pose if lastIndex is not None: - lastKey = keys.at(lastIndex) + lastKey = keys[lastIndex] try: lastPose = pose3Values.atPose3(lastKey) if marginals: From bc95b41efcb7f70eba92c13c3a5bad33ebeb6e75 Mon Sep 17 00:00:00 2001 From: Fan Jiang Date: Mon, 27 Jul 2020 15:16:26 -0400 Subject: [PATCH 275/869] Update more to match cython --- .../python/examples/Pose2SLAMExample_g2o.py | 5 ++--- .../python/examples/Pose3SLAMExample_g2o.py | 9 ++++----- .../gtsam_py/python/examples/SimpleRotation.py | 4 ++-- .../python/examples/VisualISAM2Example.py | 18 ++++-------------- 4 files changed, 12 insertions(+), 24 deletions(-) diff --git a/python/gtsam_py/python/examples/Pose2SLAMExample_g2o.py b/python/gtsam_py/python/examples/Pose2SLAMExample_g2o.py index 1ea7fc300..b2ba9c5bc 100644 --- a/python/gtsam_py/python/examples/Pose2SLAMExample_g2o.py +++ b/python/gtsam_py/python/examples/Pose2SLAMExample_g2o.py @@ -53,16 +53,15 @@ graph, initial = gtsam.readG2o(g2oFile, is3D) assert args.kernel == "none", "Supplied kernel type is not yet implemented" # Add prior on the pose having index (key) = 0 -graphWithPrior = graph priorModel = gtsam.noiseModel.Diagonal.Variances(vector3(1e-6, 1e-6, 1e-8)) -graphWithPrior.add(gtsam.PriorFactorPose2(0, gtsam.Pose2(), priorModel)) +graph.add(gtsam.PriorFactorPose2(0, gtsam.Pose2(), priorModel)) params = gtsam.GaussNewtonParams() params.setVerbosity("Termination") params.setMaxIterations(maxIterations) # parameters.setRelativeErrorTol(1e-5) # Create the optimizer ... -optimizer = gtsam.GaussNewtonOptimizer(graphWithPrior, initial, params) +optimizer = gtsam.GaussNewtonOptimizer(graph, initial, params) # ... and optimize result = optimizer.optimize() diff --git a/python/gtsam_py/python/examples/Pose3SLAMExample_g2o.py b/python/gtsam_py/python/examples/Pose3SLAMExample_g2o.py index c06a9d12f..82b3bda98 100644 --- a/python/gtsam_py/python/examples/Pose3SLAMExample_g2o.py +++ b/python/gtsam_py/python/examples/Pose3SLAMExample_g2o.py @@ -43,18 +43,17 @@ priorModel = gtsam.noiseModel.Diagonal.Variances(vector6(1e-6, 1e-6, 1e-6, 1e-4, 1e-4, 1e-4)) print("Adding prior to g2o file ") -graphWithPrior = graph firstKey = initial.keys()[0] -graphWithPrior.add(gtsam.PriorFactorPose3(firstKey, gtsam.Pose3(), priorModel)) +graph.add(gtsam.PriorFactorPose3(firstKey, gtsam.Pose3(), priorModel)) params = gtsam.GaussNewtonParams() params.setVerbosity("Termination") # this will show info about stopping conds -optimizer = gtsam.GaussNewtonOptimizer(graphWithPrior, initial, params) +optimizer = gtsam.GaussNewtonOptimizer(graph, initial, params) result = optimizer.optimize() print("Optimization complete") -print("initial error = ", graphWithPrior.error(initial)) -print("final error = ", graphWithPrior.error(result)) +print("initial error = ", graph.error(initial)) +print("final error = ", graph.error(result)) if args.output is None: print("Final Result:\n{}".format(result)) diff --git a/python/gtsam_py/python/examples/SimpleRotation.py b/python/gtsam_py/python/examples/SimpleRotation.py index 2dd7b1194..de8ab07c3 100644 --- a/python/gtsam_py/python/examples/SimpleRotation.py +++ b/python/gtsam_py/python/examples/SimpleRotation.py @@ -12,7 +12,7 @@ a single variable with a single factor. import numpy as np import gtsam - +from gtsam.gtsam.symbol_shorthand import X def main(): """ @@ -33,7 +33,7 @@ def main(): prior = gtsam.Rot2.fromAngle(np.deg2rad(30)) prior.print_('goal angle') model = gtsam.noiseModel.Isotropic.Sigma(dim=1, sigma=np.deg2rad(1)) - key = gtsam.symbol('x', 1) + key = X(1) factor = gtsam.PriorFactorRot2(key, prior, model) """ diff --git a/python/gtsam_py/python/examples/VisualISAM2Example.py b/python/gtsam_py/python/examples/VisualISAM2Example.py index d33ec98bf..e4c0c8b8d 100644 --- a/python/gtsam_py/python/examples/VisualISAM2Example.py +++ b/python/gtsam_py/python/examples/VisualISAM2Example.py @@ -13,23 +13,13 @@ Author: Duy-Nguyen Ta (C++), Frank Dellaert (Python) from __future__ import print_function -import matplotlib.pyplot as plt -import numpy as np -from mpl_toolkits.mplot3d import Axes3D # pylint: disable=W0611 - import gtsam import gtsam.utils.plot as gtsam_plot +import matplotlib.pyplot as plt +import numpy as np +from gtsam.gtsam.symbol_shorthand import L, X from gtsam.examples import SFMdata - - -def X(i): - """Create key for pose i.""" - return int(gtsam.symbol('x', i)) - - -def L(j): - """Create key for landmark j.""" - return int(gtsam.symbol('l', j)) +from mpl_toolkits.mplot3d import Axes3D # pylint: disable=W0611 def visual_ISAM2_plot(result): From 7114cf93d336ddf08d8e368e34882ed65de9d759 Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Mon, 27 Jul 2020 20:35:23 -0500 Subject: [PATCH 276/869] update ImuFactorExample.py --- .../python/examples/ImuFactorExample.py | 138 +++++++++++------- 1 file changed, 84 insertions(+), 54 deletions(-) diff --git a/python/gtsam_py/python/examples/ImuFactorExample.py b/python/gtsam_py/python/examples/ImuFactorExample.py index 1f8dfca07..03b16098d 100644 --- a/python/gtsam_py/python/examples/ImuFactorExample.py +++ b/python/gtsam_py/python/examples/ImuFactorExample.py @@ -12,15 +12,17 @@ Author: Frank Dellaert, Varun Agrawal from __future__ import print_function +import argparse import math -import gtsam import matplotlib.pyplot as plt -import numpy as np -from gtsam.gtsam.symbol_shorthand import B, V, X - -from gtsam.utils.plot import plot_pose3 from mpl_toolkits.mplot3d import Axes3D +import numpy as np + +import gtsam +from gtsam.gtsam.symbol_shorthand import B, V, X +from gtsam.utils.plot import plot_pose3 + from PreintegrationExample import POSES_FIG, PreintegrationExample @@ -32,24 +34,27 @@ np.set_printoptions(precision=3, suppress=True) class ImuFactorExample(PreintegrationExample): - def __init__(self): + def __init__(self, twist_scenario="sick_twist"): self.velocity = np.array([2, 0, 0]) self.priorNoise = gtsam.noiseModel.Isotropic.Sigma(6, 0.1) self.velNoise = gtsam.noiseModel.Isotropic.Sigma(3, 0.1) # Choose one of these twists to change scenario: - zero_twist = (np.zeros(3), np.zeros(3)) - forward_twist = (np.zeros(3), self.velocity) - loop_twist = (np.array([0, -math.radians(30), 0]), self.velocity) - sick_twist = ( - np.array([math.radians(30), -math.radians(30), 0]), self.velocity) + twist_scenarios = dict( + zero_twist=(np.zeros(3), np.zeros(3)), + forward_twist=(np.zeros(3), self.velocity), + loop_twist=(np.array([0, -math.radians(30), 0]), self.velocity), + sick_twist=(np.array([math.radians(30), -math.radians(30), 0]), + self.velocity) + ) accBias = np.array([-0.3, 0.1, 0.2]) gyroBias = np.array([0.1, 0.3, -0.1]) bias = gtsam.imuBias.ConstantBias(accBias, gyroBias) dt = 1e-2 - super(ImuFactorExample, self).__init__(sick_twist, bias, dt) + super(ImuFactorExample, self).__init__(twist_scenarios[twist_scenario], + bias, dt) def addPrior(self, i, graph): state = self.scenario.navState(i) @@ -58,65 +63,73 @@ class ImuFactorExample(PreintegrationExample): graph.push_back(gtsam.PriorFactorVector( V(i), state.velocity(), self.velNoise)) - def run(self): + def run(self, T=12, compute_covariances=False, verbose=True): graph = gtsam.NonlinearFactorGraph() # initialize data structure for pre-integrated IMU measurements pim = gtsam.PreintegratedImuMeasurements(self.params, self.actualBias) T = 12 - num_poses = T + 1 # assumes 1 factor per second + num_poses = T # assumes 1 factor per second initial = gtsam.Values() initial.insert(BIAS_KEY, self.actualBias) - for i in range(num_poses): - state_i = self.scenario.navState(float(i)) - - poseNoise = gtsam.Pose3.Expmap(np.random.randn(3)*0.1) - pose = state_i.pose().compose(poseNoise) - - velocity = state_i.velocity() + np.random.randn(3)*0.1 - - initial.insert(X(i), pose) - initial.insert(V(i), velocity) # simulate the loop i = 0 # state index - actual_state_i = self.scenario.navState(0) + initial_state_i = self.scenario.navState(0) + initial.insert(X(i), initial_state_i.pose()) + initial.insert(V(i), initial_state_i.velocity()) + + # add prior on beginning + self.addPrior(0, graph) + for k, t in enumerate(np.arange(0, T, self.dt)): # get measurements and add them to PIM measuredOmega = self.runner.measuredAngularVelocity(t) measuredAcc = self.runner.measuredSpecificForce(t) pim.integrateMeasurement(measuredAcc, measuredOmega, self.dt) - poseNoise = gtsam.Pose3.Expmap(np.random.randn(3)*0.1) - - actual_state_i = gtsam.NavState( - actual_state_i.pose().compose(poseNoise), - actual_state_i.velocity() + np.random.randn(3)*0.1) - # Plot IMU many times if k % 10 == 0: self.plotImu(t, measuredOmega, measuredAcc) - # Plot every second - if k % int(1 / self.dt) == 0: - self.plotGroundTruthPose(t) + if (k+1) % int(1 / self.dt) == 0: + # Plot every second + self.plotGroundTruthPose(t, scale=1) + plt.title("Ground Truth Trajectory") - # create IMU factor every second - if (k + 1) % int(1 / self.dt) == 0: - factor = gtsam.ImuFactor(X(i), V(i), X( - i + 1), V(i + 1), BIAS_KEY, pim) + # create IMU factor every second + factor = gtsam.ImuFactor(X(i), V(i), + X(i + 1), V(i + 1), + BIAS_KEY, pim) graph.push_back(factor) - if True: + + if verbose: print(factor) print(pim.predict(actual_state_i, self.actualBias)) + pim.resetIntegration() + + rotationNoise = gtsam.Rot3.Expmap(np.random.randn(3)*0.1) + translationNoise = gtsam.Point3(*np.random.randn(3)*1) + poseNoise = gtsam.Pose3(rotationNoise, translationNoise) + actual_state_i = self.scenario.navState(t + self.dt) + print("Actual state at {0}:\n{1}".format( + t+self.dt, actual_state_i)) + + noisy_state_i = gtsam.NavState( + actual_state_i.pose().compose(poseNoise), + actual_state_i.velocity() + np.random.randn(3)*0.1) + + initial.insert(X(i+1), noisy_state_i.pose()) + initial.insert(V(i+1), noisy_state_i.velocity()) i += 1 - # add priors on beginning and end - self.addPrior(0, graph) - self.addPrior(num_poses - 1, graph) + # add priors on end + # self.addPrior(num_poses - 1, graph) + + initial.print_("Initial values:") # optimize using Levenberg-Marquardt optimization params = gtsam.LevenbergMarquardtParams() @@ -124,29 +137,46 @@ class ImuFactorExample(PreintegrationExample): optimizer = gtsam.LevenbergMarquardtOptimizer(graph, initial, params) result = optimizer.optimize() - # Calculate and print marginal covariances - marginals = gtsam.Marginals(graph, result) - print("Covariance on bias:\n", marginals.marginalCovariance(BIAS_KEY)) - for i in range(num_poses): - print("Covariance on pose {}:\n{}\n".format( - i, marginals.marginalCovariance(X(i)))) - print("Covariance on vel {}:\n{}\n".format( - i, marginals.marginalCovariance(V(i)))) + result.print_("Optimized values:") + + if compute_covariances: + # Calculate and print marginal covariances + marginals = gtsam.Marginals(graph, result) + print("Covariance on bias:\n", + marginals.marginalCovariance(BIAS_KEY)) + for i in range(num_poses): + print("Covariance on pose {}:\n{}\n".format( + i, marginals.marginalCovariance(X(i)))) + print("Covariance on vel {}:\n{}\n".format( + i, marginals.marginalCovariance(V(i)))) # Plot resulting poses i = 0 while result.exists(X(i)): pose_i = result.atPose3(X(i)) - plot_pose3(POSES_FIG, pose_i, 0.1) + plot_pose3(POSES_FIG+1, pose_i, 1) i += 1 + plt.title("Estimated Trajectory") - gtsam.utils.plot.set_axes_equal(POSES_FIG) + gtsam.utils.plot.set_axes_equal(POSES_FIG+1) - print(result.atConstantBias(BIAS_KEY)) + print("Bias Values", result.atConstantBias(BIAS_KEY)) plt.ioff() plt.show() if __name__ == '__main__': - ImuFactorExample().run() + parser = argparse.ArgumentParser("ImuFactorExample.py") + parser.add_argument("--twist_scenario", + default="sick_twist", + choices=("zero_twist", "forward_twist", "loop_twist", "sick_twist")) + parser.add_argument("--time", "-T", default=12, + type=int, help="Total time in seconds") + parser.add_argument("--compute_covariances", + default=False, action='store_true') + parser.add_argument("--verbose", default=False, action='store_true') + args = parser.parse_args() + + ImuFactorExample(args.twist_scenario).run( + args.time, args.compute_covariances, args.verbose) From e92c5e2ed42640df1991c675a83cc66ef988c2a9 Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Mon, 27 Jul 2020 21:00:08 -0500 Subject: [PATCH 277/869] fix warnings from subplots and improve code --- .../python/examples/PreintegrationExample.py | 38 ++++++++++--------- 1 file changed, 20 insertions(+), 18 deletions(-) diff --git a/python/gtsam_py/python/examples/PreintegrationExample.py b/python/gtsam_py/python/examples/PreintegrationExample.py index ee7f9cd8f..e35722571 100644 --- a/python/gtsam_py/python/examples/PreintegrationExample.py +++ b/python/gtsam_py/python/examples/PreintegrationExample.py @@ -73,40 +73,43 @@ class PreintegrationExample(object): self.runner = gtsam.ScenarioRunner( self.scenario, self.params, self.dt, self.actualBias) + fig, self.axes = plt.subplots(4, 3) + fig.set_tight_layout(True) + def plotImu(self, t, measuredOmega, measuredAcc): plt.figure(IMU_FIG) # plot angular velocity omega_b = self.scenario.omega_b(t) for i, (label, color) in enumerate(zip(self.labels, self.colors)): - plt.subplot(4, 3, i + 1) - plt.scatter(t, omega_b[i], color='k', marker='.') - plt.scatter(t, measuredOmega[i], color=color, marker='.') - plt.xlabel('angular velocity ' + label) + ax = self.axes[0][i] + ax.scatter(t, omega_b[i], color='k', marker='.') + ax.scatter(t, measuredOmega[i], color=color, marker='.') + ax.set_xlabel('angular velocity ' + label) # plot acceleration in nav acceleration_n = self.scenario.acceleration_n(t) for i, (label, color) in enumerate(zip(self.labels, self.colors)): - plt.subplot(4, 3, i + 4) - plt.scatter(t, acceleration_n[i], color=color, marker='.') - plt.xlabel('acceleration in nav ' + label) + ax = self.axes[1][i] + ax.scatter(t, acceleration_n[i], color=color, marker='.') + ax.set_xlabel('acceleration in nav ' + label) # plot acceleration in body acceleration_b = self.scenario.acceleration_b(t) for i, (label, color) in enumerate(zip(self.labels, self.colors)): - plt.subplot(4, 3, i + 7) - plt.scatter(t, acceleration_b[i], color=color, marker='.') - plt.xlabel('acceleration in body ' + label) + ax = self.axes[2][i] + ax.scatter(t, acceleration_b[i], color=color, marker='.') + ax.set_xlabel('acceleration in body ' + label) # plot actual specific force, as well as corrupted actual = self.runner.actualSpecificForce(t) for i, (label, color) in enumerate(zip(self.labels, self.colors)): - plt.subplot(4, 3, i + 10) - plt.scatter(t, actual[i], color='k', marker='.') - plt.scatter(t, measuredAcc[i], color=color, marker='.') - plt.xlabel('specific force ' + label) + ax = self.axes[3][i] + ax.scatter(t, actual[i], color='k', marker='.') + ax.scatter(t, measuredAcc[i], color=color, marker='.') + ax.set_xlabel('specific force ' + label) - def plotGroundTruthPose(self, t): + def plotGroundTruthPose(self, t, scale=0.3, time_interval=0.01): # plot ground truth pose, as well as prediction from integrated IMU measurements actualPose = self.scenario.pose(t) plot_pose3(POSES_FIG, actualPose, 0.3) @@ -117,11 +120,10 @@ class PreintegrationExample(object): ax.set_ylim3d(-self.maxDim, self.maxDim) ax.set_zlim3d(-self.maxDim, self.maxDim) - plt.pause(0.01) + plt.pause(time_interval) - def run(self): + def run(self, T=12): # simulate the loop - T = 12 for i, t in enumerate(np.arange(0, T, self.dt)): measuredOmega = self.runner.measuredAngularVelocity(t) measuredAcc = self.runner.measuredSpecificForce(t) From 858f5d42d3757372eaf5835f4d513ade436918fa Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Mon, 27 Jul 2020 21:00:24 -0500 Subject: [PATCH 278/869] add incremental plotting function --- python/gtsam_py/python/utils/plot.py | 38 ++++++++++++++++++++++++++++ 1 file changed, 38 insertions(+) diff --git a/python/gtsam_py/python/utils/plot.py b/python/gtsam_py/python/utils/plot.py index ce602f506..90f5fe5e7 100644 --- a/python/gtsam_py/python/utils/plot.py +++ b/python/gtsam_py/python/utils/plot.py @@ -366,3 +366,41 @@ def plot_trajectory(fignum, values, scale=1, marginals=None, fig.suptitle(title) fig.canvas.set_window_title(title.lower()) + + +def plot_incremental_trajectory(fignum, values, start=0, + scale=1, marginals=None, + time_interval=0.0): + """ + Incrementally plot a complete 3D trajectory using poses in `values`. + + Args: + fignum (int): Integer representing the figure number to use for plotting. + values (gtsam.Values): Values dict containing the poses. + start (int): Starting index to start plotting from. + scale (float): Value to scale the poses by. + marginals (gtsam.Marginals): Marginalized probability values of the estimation. + Used to plot uncertainty bounds. + time_interval (float): Time in seconds to pause between each rendering. + Used to create animation effect. + """ + fig = plt.figure(fignum) + axes = fig.gca(projection='3d') + + pose3Values = gtsam.utilities.allPose3s(values) + keys = gtsam.KeyVector(pose3Values.keys()) + + for i in range(start, len(keys)): + key = keys[i] + if values.exists(key): + pose_i = values.atPose3(keys[i]) + plot_pose3(fignum, pose_i, scale) + + # Update the plot space to encompass all plotted points + axes.autoscale() + + # Set the 3 axes equal + set_axes_equal(fignum) + + # Pause for a fixed amount of seconds + plt.pause(time_interval) \ No newline at end of file From 0b550b355fa040a3916605eb859efdf8dbbb7e7c Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Mon, 27 Jul 2020 21:00:44 -0500 Subject: [PATCH 279/869] update ImuFactorExample2.py --- .../python/examples/ImuFactorExample2.py | 117 +++++++++--------- 1 file changed, 57 insertions(+), 60 deletions(-) diff --git a/python/gtsam_py/python/examples/ImuFactorExample2.py b/python/gtsam_py/python/examples/ImuFactorExample2.py index d5be69f47..969d4fe6b 100644 --- a/python/gtsam_py/python/examples/ImuFactorExample2.py +++ b/python/gtsam_py/python/examples/ImuFactorExample2.py @@ -1,6 +1,6 @@ """ iSAM2 example with ImuFactor. -Author: Robert Truax (C++), Frank Dellaert (Python) +Author: Frank Dellaert, Varun Agrawal """ # pylint: disable=invalid-name, E1101 @@ -8,17 +8,18 @@ from __future__ import print_function import math -import gtsam -import gtsam.utils.plot as gtsam_plot import matplotlib.pyplot as plt +from mpl_toolkits.mplot3d import Axes3D # pylint: disable=W0611 import numpy as np + +import gtsam from gtsam import (ISAM2, BetweenFactorConstantBias, Cal3_S2, ConstantTwistScenario, ImuFactor, NonlinearFactorGraph, PinholeCameraCal3_S2, Point3, Pose3, PriorFactorConstantBias, PriorFactorPose3, PriorFactorVector, Rot3, Values) from gtsam.gtsam.symbol_shorthand import B, V, X -from mpl_toolkits.mplot3d import Axes3D # pylint: disable=W0611 +from gtsam.utils import plot def vector3(x, y, z): @@ -26,46 +27,45 @@ def vector3(x, y, z): return np.array([x, y, z], dtype=np.float) -def ISAM2_plot(values, fignum=0): - """Plot poses.""" - fig = plt.figure(fignum) - axes = fig.gca(projection='3d') - plt.cla() - - i = 0 - min_bounds = 0, 0, 0 - max_bounds = 0, 0, 0 - while values.exists(X(i)): - pose_i = values.atPose3(X(i)) - gtsam_plot.plot_pose3(fignum, pose_i, 10) - position = pose_i.translation() - min_bounds = [min(v1, v2) for (v1, v2) in zip(position, min_bounds)] - max_bounds = [max(v1, v2) for (v1, v2) in zip(position, max_bounds)] - # max_bounds = min(pose_i.x(), max_bounds[0]), 0, 0 - i += 1 - - # draw - axes.set_xlim3d(min_bounds[0]-1, max_bounds[0]+1) - axes.set_ylim3d(min_bounds[1]-1, max_bounds[1]+1) - axes.set_zlim3d(min_bounds[2]-1, max_bounds[2]+1) - plt.pause(1) - - -# IMU preintegration parameters -# Default Params for a Z-up navigation frame, such as ENU: gravity points along negative Z-axis g = 9.81 n_gravity = vector3(0, 0, -g) -PARAMS = gtsam.PreintegrationParams.MakeSharedU(g) -I = np.eye(3) -PARAMS.setAccelerometerCovariance(I * 0.1) -PARAMS.setGyroscopeCovariance(I * 0.1) -PARAMS.setIntegrationCovariance(I * 0.1) -PARAMS.setUse2ndOrderCoriolis(False) -PARAMS.setOmegaCoriolis(vector3(0, 0, 0)) -BIAS_COVARIANCE = gtsam.noiseModel.Isotropic.Variance(6, 0.1) -DELTA = Pose3(Rot3.Rodrigues(0, 0, 0), - Point3(0.05, -0.10, 0.20)) + +def preintegration_parameters(): + # IMU preintegration parameters + # Default Params for a Z-up navigation frame, such as ENU: gravity points along negative Z-axis + PARAMS = gtsam.PreintegrationParams.MakeSharedU(g) + I = np.eye(3) + PARAMS.setAccelerometerCovariance(I * 0.1) + PARAMS.setGyroscopeCovariance(I * 0.1) + PARAMS.setIntegrationCovariance(I * 0.1) + PARAMS.setUse2ndOrderCoriolis(False) + PARAMS.setOmegaCoriolis(vector3(0, 0, 0)) + + BIAS_COVARIANCE = gtsam.noiseModel.Isotropic.Variance(6, 0.1) + DELTA = Pose3(Rot3.Rodrigues(0, 0, 0), + Point3(0.05, -0.10, 0.20)) + + return PARAMS, BIAS_COVARIANCE, DELTA + + +def get_camera(radius): + up = Point3(0, 0, 1) + target = Point3(0, 0, 0) + position = Point3(radius, 0, 0) + camera = PinholeCameraCal3_S2.Lookat(position, target, up, Cal3_S2()) + return camera + + +def get_scenario(radius, pose_0, angular_velocity, delta_t): + """Create the set of ground-truth landmarks and poses""" + + angular_velocity_vector = vector3(0, -angular_velocity, 0) + linear_velocity_vector = vector3(radius * angular_velocity, 0, 0) + scenario = ConstantTwistScenario( + angular_velocity_vector, linear_velocity_vector, pose_0) + + return scenario def IMU_example(): @@ -73,23 +73,17 @@ def IMU_example(): # Start with a camera on x-axis looking at origin radius = 30 - up = Point3(0, 0, 1) - target = Point3(0, 0, 0) - position = Point3(radius, 0, 0) - camera = PinholeCameraCal3_S2.Lookat(position, target, up, Cal3_S2()) + camera = get_camera(radius) pose_0 = camera.pose() - # Create the set of ground-truth landmarks and poses - angular_velocity = math.radians(180) # rad/sec delta_t = 1.0/18 # makes for 10 degrees per step + angular_velocity = math.radians(180) # rad/sec + scenario = get_scenario(radius, pose_0, angular_velocity, delta_t) - angular_velocity_vector = vector3(0, -angular_velocity, 0) - linear_velocity_vector = vector3(radius * angular_velocity, 0, 0) - scenario = ConstantTwistScenario( - angular_velocity_vector, linear_velocity_vector, pose_0) + PARAMS, BIAS_COVARIANCE, DELTA = preintegration_parameters() # Create a factor graph - newgraph = NonlinearFactorGraph() + graph = NonlinearFactorGraph() # Create (incremental) ISAM2 solver isam = ISAM2() @@ -102,21 +96,21 @@ def IMU_example(): # 30cm std on x,y,z 0.1 rad on roll,pitch,yaw noise = gtsam.noiseModel.Diagonal.Sigmas( np.array([0.1, 0.1, 0.1, 0.3, 0.3, 0.3])) - newgraph.push_back(PriorFactorPose3(X(0), pose_0, noise)) + graph.push_back(PriorFactorPose3(X(0), pose_0, noise)) # Add imu priors biasKey = B(0) biasnoise = gtsam.noiseModel.Isotropic.Sigma(6, 0.1) biasprior = PriorFactorConstantBias(biasKey, gtsam.imuBias.ConstantBias(), biasnoise) - newgraph.push_back(biasprior) + graph.push_back(biasprior) initialEstimate.insert(biasKey, gtsam.imuBias.ConstantBias()) velnoise = gtsam.noiseModel.Isotropic.Sigma(3, 0.1) # Calculate with correct initial velocity n_velocity = vector3(0, angular_velocity * radius, 0) velprior = PriorFactorVector(V(0), n_velocity, velnoise) - newgraph.push_back(velprior) + graph.push_back(velprior) initialEstimate.insert(V(0), n_velocity) accum = gtsam.PreintegratedImuMeasurements(PARAMS) @@ -138,7 +132,7 @@ def IMU_example(): biasKey += 1 factor = BetweenFactorConstantBias( biasKey - 1, biasKey, gtsam.imuBias.ConstantBias(), BIAS_COVARIANCE) - newgraph.add(factor) + graph.add(factor) initialEstimate.insert(biasKey, gtsam.imuBias.ConstantBias()) # Predict acceleration and gyro measurements in (actual) body frame @@ -150,21 +144,24 @@ def IMU_example(): # Add Imu Factor imufac = ImuFactor(X(i - 1), V(i - 1), X(i), V(i), biasKey, accum) - newgraph.add(imufac) + graph.add(imufac) # insert new velocity, which is wrong initialEstimate.insert(V(i), n_velocity) accum.resetIntegration() # Incremental solution - isam.update(newgraph, initialEstimate) + isam.update(graph, initialEstimate) result = isam.calculateEstimate() - ISAM2_plot(result) + plot.plot_incremental_trajectory(0, result, + start=i, scale=3, time_interval=0.01) # reset - newgraph = NonlinearFactorGraph() + graph = NonlinearFactorGraph() initialEstimate.clear() + plt.show() + if __name__ == '__main__': IMU_example() From c8806dcb24f0aef8ed4c4712db1af323980fc535 Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Mon, 27 Jul 2020 21:01:38 -0500 Subject: [PATCH 280/869] rename ImuFactorExample2 to more descriptive name --- .../examples/{ImuFactorExample2.py => ImuFactorISAM2Example.py} | 0 1 file changed, 0 insertions(+), 0 deletions(-) rename python/gtsam_py/python/examples/{ImuFactorExample2.py => ImuFactorISAM2Example.py} (100%) diff --git a/python/gtsam_py/python/examples/ImuFactorExample2.py b/python/gtsam_py/python/examples/ImuFactorISAM2Example.py similarity index 100% rename from python/gtsam_py/python/examples/ImuFactorExample2.py rename to python/gtsam_py/python/examples/ImuFactorISAM2Example.py From e9c7e2cb4f21ff61b51616cf74ba1c19d952f0ba Mon Sep 17 00:00:00 2001 From: acxz <17132214+acxz@users.noreply.github.com> Date: Mon, 27 Jul 2020 22:11:50 -0400 Subject: [PATCH 281/869] add override keyword --- gtsam/navigation/MagFactor.h | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/gtsam/navigation/MagFactor.h b/gtsam/navigation/MagFactor.h index 97a4c70ce..74e9177d5 100644 --- a/gtsam/navigation/MagFactor.h +++ b/gtsam/navigation/MagFactor.h @@ -73,7 +73,7 @@ public: * @brief vector of errors */ Vector evaluateError(const Rot2& nRb, - boost::optional H = boost::none) const { + boost::optional H = boost::none) const override { // measured bM = nRb� * nM + b Point3 hx = unrotate(nRb, nM_, H) + bias_; return (hx - measured_); @@ -111,7 +111,7 @@ public: * @brief vector of errors */ Vector evaluateError(const Rot3& nRb, - boost::optional H = boost::none) const { + boost::optional H = boost::none) const override { // measured bM = nRb� * nM + b Point3 hx = nRb.unrotate(nM_, H, boost::none) + bias_; return (hx - measured_); @@ -150,7 +150,7 @@ public: */ Vector evaluateError(const Point3& nM, const Point3& bias, boost::optional H1 = boost::none, boost::optional H2 = - boost::none) const { + boost::none) const override { // measured bM = nRb� * nM + b, where b is unknown bias Point3 hx = bRn_.rotate(nM, boost::none, H1) + bias; if (H2) @@ -192,7 +192,7 @@ public: Vector evaluateError(const double& scale, const Unit3& direction, const Point3& bias, boost::optional H1 = boost::none, boost::optional H2 = boost::none, boost::optional H3 = - boost::none) const { + boost::none) const override { // measured bM = nRb� * nM + b, where b is unknown bias Unit3 rotated = bRn_.rotate(direction, boost::none, H2); Point3 hx = scale * rotated.point3() + bias; From 95d3582c2eddc8b477fd511b91c7d222d548b010 Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Mon, 27 Jul 2020 21:25:27 -0500 Subject: [PATCH 282/869] replaced SimpleCamera with PinholeCamera and updated tests --- cython/gtsam/examples/SFMExample.py | 2 +- .../python/tests/test_GaussianFactorGraph.py | 9 ++++---- .../python/tests/test_NonlinearOptimizer.py | 15 +++++++++++-- .../gtsam_py/python/tests/test_PriorFactor.py | 22 +++++++++++++++++++ .../gtsam_py/python/tests/test_SFMExample.py | 7 +++--- .../python/utils/visual_data_generator.py | 9 ++++---- 6 files changed, 50 insertions(+), 14 deletions(-) diff --git a/cython/gtsam/examples/SFMExample.py b/cython/gtsam/examples/SFMExample.py index e02def2f9..68053f862 100644 --- a/cython/gtsam/examples/SFMExample.py +++ b/cython/gtsam/examples/SFMExample.py @@ -20,7 +20,7 @@ from gtsam.gtsam import (Cal3_S2, DoglegOptimizer, GenericProjectionFactorCal3_S2, Marginals, NonlinearFactorGraph, PinholeCameraCal3_S2, Point3, Pose3, PriorFactorPoint3, PriorFactorPose3, Rot3, - SimpleCamera, Values) + PinholeCameraCal3_S2, Values) from gtsam.utils import plot diff --git a/python/gtsam_py/python/tests/test_GaussianFactorGraph.py b/python/gtsam_py/python/tests/test_GaussianFactorGraph.py index 759de0f3b..d520b0fa4 100644 --- a/python/gtsam_py/python/tests/test_GaussianFactorGraph.py +++ b/python/gtsam_py/python/tests/test_GaussianFactorGraph.py @@ -15,17 +15,18 @@ from __future__ import print_function import unittest import gtsam +import numpy as np +from gtsam.gtsam.symbol_shorthand import X from gtsam.utils.test_case import GtsamTestCase -import numpy as np def create_graph(): """Create a basic linear factor graph for testing""" graph = gtsam.GaussianFactorGraph() - x0 = gtsam.symbol('x', 0) - x1 = gtsam.symbol('x', 1) - x2 = gtsam.symbol('x', 2) + x0 = X(0) + x1 = X(1) + x2 = X(2) BETWEEN_NOISE = gtsam.noiseModel.Diagonal.Sigmas(np.ones(1)) PRIOR_NOISE = gtsam.noiseModel.Diagonal.Sigmas(np.ones(1)) diff --git a/python/gtsam_py/python/tests/test_NonlinearOptimizer.py b/python/gtsam_py/python/tests/test_NonlinearOptimizer.py index 3041e325c..e9234a43b 100644 --- a/python/gtsam_py/python/tests/test_NonlinearOptimizer.py +++ b/python/gtsam_py/python/tests/test_NonlinearOptimizer.py @@ -15,10 +15,11 @@ from __future__ import print_function import unittest import gtsam -from gtsam import (DoglegOptimizer, DoglegParams, GaussNewtonOptimizer, +from gtsam import (DoglegOptimizer, DoglegParams, + DummyPreconditionerParameters, GaussNewtonOptimizer, GaussNewtonParams, LevenbergMarquardtOptimizer, LevenbergMarquardtParams, NonlinearFactorGraph, Ordering, - Point2, PriorFactorPoint2, Values) + PCGSolverParameters, Point2, PriorFactorPoint2, Values) from gtsam.utils.test_case import GtsamTestCase KEY1 = 1 @@ -61,6 +62,16 @@ class TestScenario(GtsamTestCase): fg, initial_values, lmParams).optimize() self.assertAlmostEqual(0, fg.error(actual2)) + # Levenberg-Marquardt + lmParams = LevenbergMarquardtParams.CeresDefaults() + lmParams.setLinearSolverType("ITERATIVE") + cgParams = PCGSolverParameters() + cgParams.setPreconditionerParams(DummyPreconditionerParameters()) + lmParams.setIterativeParams(cgParams) + actual2 = LevenbergMarquardtOptimizer( + fg, initial_values, lmParams).optimize() + self.assertAlmostEqual(0, fg.error(actual2)) + # Dogleg dlParams = DoglegParams() dlParams.setOrdering(ordering) diff --git a/python/gtsam_py/python/tests/test_PriorFactor.py b/python/gtsam_py/python/tests/test_PriorFactor.py index da072d0bd..0582cf5d7 100644 --- a/python/gtsam_py/python/tests/test_PriorFactor.py +++ b/python/gtsam_py/python/tests/test_PriorFactor.py @@ -35,5 +35,27 @@ class TestPriorFactor(GtsamTestCase): values.insert(key, priorVector) self.assertEqual(factor.error(values), 0) + def test_AddPrior(self): + """ + Test adding prior factors directly to factor graph via the .addPrior method. + """ + # define factor graph + graph = gtsam.NonlinearFactorGraph() + + # define and add Pose3 prior + key = 5 + priorPose3 = gtsam.Pose3() + model = gtsam.noiseModel.Unit.Create(6) + graph.addPriorPose3(key, priorPose3, model) + self.assertEqual(graph.size(), 1) + + # define and add Vector prior + key = 3 + priorVector = np.array([0., 0., 0.]) + model = gtsam.noiseModel.Unit.Create(3) + graph.addPriorVector(key, priorVector, model) + self.assertEqual(graph.size(), 2) + + if __name__ == "__main__": unittest.main() diff --git a/python/gtsam_py/python/tests/test_SFMExample.py b/python/gtsam_py/python/tests/test_SFMExample.py index 8b5473ff0..1425902cf 100644 --- a/python/gtsam_py/python/tests/test_SFMExample.py +++ b/python/gtsam_py/python/tests/test_SFMExample.py @@ -15,6 +15,7 @@ import numpy as np import gtsam import gtsam.utils.visual_data_generator as generator from gtsam import symbol +from gtsam.gtsam.noiseModel improt Isotropic, Diagonal from gtsam.utils.test_case import GtsamTestCase @@ -34,7 +35,7 @@ class TestSFMExample(GtsamTestCase): graph = gtsam.NonlinearFactorGraph() # Add factors for all measurements - measurementNoise = gtsam.noiseModel.Isotropic.Sigma(2, measurementNoiseSigma) + measurementNoise = Isotropic.Sigma(2, measurementNoiseSigma) for i in range(len(data.Z)): for k in range(len(data.Z[i])): j = data.J[i][k] @@ -42,10 +43,10 @@ class TestSFMExample(GtsamTestCase): data.Z[i][k], measurementNoise, symbol('x', i), symbol('p', j), data.K)) - posePriorNoise = gtsam.noiseModel.Diagonal.Sigmas(poseNoiseSigmas) + posePriorNoise = Diagonal.Sigmas(poseNoiseSigmas) graph.add(gtsam.PriorFactorPose3(symbol('x', 0), truth.cameras[0].pose(), posePriorNoise)) - pointPriorNoise = gtsam.noiseModel.Isotropic.Sigma(3, pointNoiseSigma) + pointPriorNoise = Isotropic.Sigma(3, pointNoiseSigma) graph.add(gtsam.PriorFactorPoint3(symbol('p', 0), truth.points[0], pointPriorNoise)) diff --git a/python/gtsam_py/python/utils/visual_data_generator.py b/python/gtsam_py/python/utils/visual_data_generator.py index bc60dcd70..24404ca03 100644 --- a/python/gtsam_py/python/utils/visual_data_generator.py +++ b/python/gtsam_py/python/utils/visual_data_generator.py @@ -3,6 +3,7 @@ from __future__ import print_function import numpy as np from math import pi, cos, sin import gtsam +from gtsam import PinholeCameraCal3_S2 class Options: @@ -99,10 +100,10 @@ def generate_data(options): for i in range(options.nrCameras): theta = i * 2 * pi / options.nrCameras t = gtsam.Point3(r * cos(theta), r * sin(theta), height) - truth.cameras[i] = gtsam.SimpleCamera.Lookat(t, - gtsam.Point3(0, 0, 0), - gtsam.Point3(0, 0, 1), - truth.K) + truth.cameras[i] = PinholeCameraCal3_S2.Lookat(t, + gtsam.Point3(0, 0, 0), + gtsam.Point3(0, 0, 1), + truth.K) # Create measurements for j in range(nrPoints): # All landmarks seen in every frame From 95b77f76347a653536cec52507241f766c54edee Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Mon, 27 Jul 2020 21:25:44 -0500 Subject: [PATCH 283/869] sort imports in python examples --- .../python/examples/ImuFactorExample.py | 8 +++----- .../python/examples/ImuFactorISAM2Example.py | 7 +++---- .../python/examples/PreintegrationExample.py | 5 ++--- .../python/examples/VisualISAMExample.py | 20 +++++++++++-------- 4 files changed, 20 insertions(+), 20 deletions(-) diff --git a/python/gtsam_py/python/examples/ImuFactorExample.py b/python/gtsam_py/python/examples/ImuFactorExample.py index 03b16098d..f9ff44738 100644 --- a/python/gtsam_py/python/examples/ImuFactorExample.py +++ b/python/gtsam_py/python/examples/ImuFactorExample.py @@ -15,14 +15,12 @@ from __future__ import print_function import argparse import math -import matplotlib.pyplot as plt -from mpl_toolkits.mplot3d import Axes3D -import numpy as np - import gtsam +import matplotlib.pyplot as plt +import numpy as np from gtsam.gtsam.symbol_shorthand import B, V, X from gtsam.utils.plot import plot_pose3 - +from mpl_toolkits.mplot3d import Axes3D from PreintegrationExample import POSES_FIG, PreintegrationExample diff --git a/python/gtsam_py/python/examples/ImuFactorISAM2Example.py b/python/gtsam_py/python/examples/ImuFactorISAM2Example.py index 969d4fe6b..6556eb554 100644 --- a/python/gtsam_py/python/examples/ImuFactorISAM2Example.py +++ b/python/gtsam_py/python/examples/ImuFactorISAM2Example.py @@ -8,11 +8,9 @@ from __future__ import print_function import math -import matplotlib.pyplot as plt -from mpl_toolkits.mplot3d import Axes3D # pylint: disable=W0611 -import numpy as np - import gtsam +import matplotlib.pyplot as plt +import numpy as np from gtsam import (ISAM2, BetweenFactorConstantBias, Cal3_S2, ConstantTwistScenario, ImuFactor, NonlinearFactorGraph, PinholeCameraCal3_S2, Point3, Pose3, @@ -20,6 +18,7 @@ from gtsam import (ISAM2, BetweenFactorConstantBias, Cal3_S2, PriorFactorVector, Rot3, Values) from gtsam.gtsam.symbol_shorthand import B, V, X from gtsam.utils import plot +from mpl_toolkits.mplot3d import Axes3D # pylint: disable=W0611 def vector3(x, y, z): diff --git a/python/gtsam_py/python/examples/PreintegrationExample.py b/python/gtsam_py/python/examples/PreintegrationExample.py index e35722571..e308bc933 100644 --- a/python/gtsam_py/python/examples/PreintegrationExample.py +++ b/python/gtsam_py/python/examples/PreintegrationExample.py @@ -10,12 +10,11 @@ A script validating the Preintegration of IMU measurements import math +import gtsam import matplotlib.pyplot as plt import numpy as np -from mpl_toolkits.mplot3d import Axes3D - -import gtsam from gtsam.utils.plot import plot_pose3 +from mpl_toolkits.mplot3d import Axes3D IMU_FIG = 1 POSES_FIG = 2 diff --git a/python/gtsam_py/python/examples/VisualISAMExample.py b/python/gtsam_py/python/examples/VisualISAMExample.py index 2e90ce21b..7d562c9b4 100644 --- a/python/gtsam_py/python/examples/VisualISAMExample.py +++ b/python/gtsam_py/python/examples/VisualISAMExample.py @@ -16,9 +16,9 @@ import numpy as np import gtsam from gtsam.examples import SFMdata from gtsam import (Cal3_S2, GenericProjectionFactorCal3_S2, - NonlinearFactorGraph, NonlinearISAM, Pose3, - PriorFactorPoint3, PriorFactorPose3, Rot3, - SimpleCamera, Values, Point3) + NonlinearFactorGraph, NonlinearISAM, Pose3, + PriorFactorPoint3, PriorFactorPose3, Rot3, + PinholeCameraCal3_S2, Values, Point3) def symbol(name: str, index: int) -> int: @@ -37,7 +37,8 @@ def main(): K = Cal3_S2(50.0, 50.0, 0.0, 50.0, 50.0) # Define the camera observation noise model - camera_noise = gtsam.noiseModel.Isotropic.Sigma(2, 1.0) # one pixel in u and v + camera_noise = gtsam.noiseModel.Isotropic.Sigma( + 2, 1.0) # one pixel in u and v # Create the set of ground-truth landmarks points = SFMdata.createPoints() @@ -54,15 +55,17 @@ def main(): # Loop over the different poses, adding the observations to iSAM incrementally for i, pose in enumerate(poses): - camera = SimpleCamera(pose, K) + camera = PinholeCameraCal3_S2(pose, K) # Add factors for each landmark observation for j, point in enumerate(points): measurement = camera.project(point) - factor = GenericProjectionFactorCal3_S2(measurement, camera_noise, symbol('x', i), symbol('l', j), K) + factor = GenericProjectionFactorCal3_S2( + measurement, camera_noise, symbol('x', i), symbol('l', j), K) graph.push_back(factor) # Intentionally initialize the variables off from the ground truth - noise = Pose3(r=Rot3.Rodrigues(-0.1, 0.2, 0.25), t=Point3(0.05, -0.10, 0.20)) + noise = Pose3(r=Rot3.Rodrigues(-0.1, 0.2, 0.25), + t=Point3(0.05, -0.10, 0.20)) initial_xi = pose.compose(noise) # Add an initial guess for the current pose @@ -74,7 +77,8 @@ def main(): # adding it to iSAM. if i == 0: # Add a prior on pose x0, with 0.3 rad std on roll,pitch,yaw and 0.1m x,y,z - pose_noise = gtsam.noiseModel.Diagonal.Sigmas(np.array([0.3, 0.3, 0.3, 0.1, 0.1, 0.1])) + pose_noise = gtsam.noiseModel.Diagonal.Sigmas( + np.array([0.3, 0.3, 0.3, 0.1, 0.1, 0.1])) factor = PriorFactorPose3(symbol('x', 0), poses[0], pose_noise) graph.push_back(factor) From e0791f4e54ea7845b634a2f0c96f2a08f8f712de Mon Sep 17 00:00:00 2001 From: acxz <17132214+acxz@users.noreply.github.com> Date: Mon, 27 Jul 2020 23:43:35 -0400 Subject: [PATCH 284/869] workaround to dereferencing a nullptr --- gtsam/nonlinear/tests/testCallRecord.cpp | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/gtsam/nonlinear/tests/testCallRecord.cpp b/gtsam/nonlinear/tests/testCallRecord.cpp index c5ccc0f52..66c56e696 100644 --- a/gtsam/nonlinear/tests/testCallRecord.cpp +++ b/gtsam/nonlinear/tests/testCallRecord.cpp @@ -98,7 +98,8 @@ struct Record: public internal::CallRecordImplementor { friend struct internal::CallRecordImplementor; }; -internal::JacobianMap & NJM= *static_cast(nullptr); +internal::JacobianMap* NJM_ptr = static_cast(nullptr); +internal::JacobianMap & NJM = *NJM_ptr; /* ************************************************************************* */ typedef Eigen::Matrix DynRowMat; From c9fb0960022569f35080f4fe8b43757b4f367b80 Mon Sep 17 00:00:00 2001 From: Jose Luis Blanco Claraco Date: Tue, 28 Jul 2020 00:19:44 +0200 Subject: [PATCH 285/869] Add genericValue() helper --- gtsam/base/GenericValue.h | 8 ++++++++ 1 file changed, 8 insertions(+) diff --git a/gtsam/base/GenericValue.h b/gtsam/base/GenericValue.h index 98425adde..4b353e6de 100644 --- a/gtsam/base/GenericValue.h +++ b/gtsam/base/GenericValue.h @@ -198,4 +198,12 @@ const ValueType& Value::cast() const { return dynamic_cast&>(*this).value(); } +/** Functional constructor of GenericValue so T can be automatically deduced + */ +template +GenericValue genericValue(const T& v) { + return GenericValue(v); +} + + } /* namespace gtsam */ From 77c8c3bf0b095b37d84c41f7dc44a24156b90ae6 Mon Sep 17 00:00:00 2001 From: Jose Luis Blanco Claraco Date: Tue, 28 Jul 2020 00:22:09 +0200 Subject: [PATCH 286/869] Values initializer_list constructor --- gtsam/nonlinear/Values.cpp | 6 ++++++ gtsam/nonlinear/Values.h | 7 +++++++ gtsam/nonlinear/tests/testValues.cpp | 30 ++++++++++++++++++++++++++++ 3 files changed, 43 insertions(+) diff --git a/gtsam/nonlinear/Values.cpp b/gtsam/nonlinear/Values.cpp index 7e13a072a..13be88ce1 100644 --- a/gtsam/nonlinear/Values.cpp +++ b/gtsam/nonlinear/Values.cpp @@ -52,6 +52,12 @@ namespace gtsam { Values::Values(Values&& other) : values_(std::move(other.values_)) { } + /* ************************************************************************* */ + Values::Values(std::initializer_list init) { + for (const auto &kv : init) + insert(kv.key, kv.value); + } + /* ************************************************************************* */ Values::Values(const Values& other, const VectorValues& delta) { for (const_iterator key_value = other.begin(); key_value != other.end(); ++key_value) { diff --git a/gtsam/nonlinear/Values.h b/gtsam/nonlinear/Values.h index bc64f2612..aadbcf394 100644 --- a/gtsam/nonlinear/Values.h +++ b/gtsam/nonlinear/Values.h @@ -149,6 +149,13 @@ namespace gtsam { /** Move constructor */ Values(Values&& other); + + /** Constructor from initializer list. Example usage: + * \code + * Values v = {{k1, genericValue(pose1)}, {k2, genericValue(point2)}}; + * \endcode + */ + Values(std::initializer_list init); /** Construct from a Values and an update vector: identical to other.retract(delta) */ Values(const Values& other, const VectorValues& delta); diff --git a/gtsam/nonlinear/tests/testValues.cpp b/gtsam/nonlinear/tests/testValues.cpp index 2f624f527..388bcf568 100644 --- a/gtsam/nonlinear/tests/testValues.cpp +++ b/gtsam/nonlinear/tests/testValues.cpp @@ -606,6 +606,36 @@ TEST(Values, Demangle) { EXPECT(assert_equal(expected, actual)); } +/* ************************************************************************* */ +TEST(Values, brace_initializer) { + const Pose2 poseA(1.0, 2.0, 0.3), poseC(.0, .0, .0); + const Pose3 poseB(Pose2(0.1, 0.2, 0.3)); + + { + Values values; + EXPECT_LONGS_EQUAL(0, values.size()); + values = { {key1, genericValue(1.0)} }; + EXPECT_LONGS_EQUAL(1, values.size()); + CHECK(values.at(key1) == 1.0); + } + { + Values values = { {key1, genericValue(poseA)}, {key2, genericValue(poseB)} }; + EXPECT_LONGS_EQUAL(2, values.size()); + EXPECT(assert_equal(values.at(key1), poseA)); + EXPECT(assert_equal(values.at(key2), poseB)); + } + // Test exception: duplicated key: + { + Values values; + CHECK_EXCEPTION((values = { + {key1, genericValue(poseA)}, + {key2, genericValue(poseB)}, + {key1, genericValue(poseC)} + }), std::exception); + } +} + + /* ************************************************************************* */ int main() { TestResult tr; return TestRegistry::runAllTests(tr); } /* ************************************************************************* */ From 4756f7359d43e26ef935d6c8818a2def9407aef1 Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Tue, 28 Jul 2020 09:12:13 -0500 Subject: [PATCH 287/869] use \n instead of endl --- gtsam/base/GenericValue.h | 4 ++-- gtsam/nonlinear/Values.cpp | 4 ++-- 2 files changed, 4 insertions(+), 4 deletions(-) diff --git a/gtsam/base/GenericValue.h b/gtsam/base/GenericValue.h index cbd210b89..f4459243e 100644 --- a/gtsam/base/GenericValue.h +++ b/gtsam/base/GenericValue.h @@ -83,8 +83,8 @@ public: } /// Virtual print function, uses traits - virtual void print(const std::string& str) const { - std::cout << "(" << demangle(typeid(T).name()) << ") " << std::endl; + virtual void print(const std::string& str) const override { + std::cout << "(" << demangle(typeid(T).name()) << ")\n"; traits::Print(value_, str); } diff --git a/gtsam/nonlinear/Values.cpp b/gtsam/nonlinear/Values.cpp index c806ce12b..b672031ca 100644 --- a/gtsam/nonlinear/Values.cpp +++ b/gtsam/nonlinear/Values.cpp @@ -75,8 +75,8 @@ namespace gtsam { /* ************************************************************************* */ void Values::print(const string& str, const KeyFormatter& keyFormatter) const { - cout << str << endl; - cout << "Values with " << size() << " values:" << endl; + cout << str << (str == "" ? "" : "\n"); + cout << "Values with " << size() << " values:\n"; for(const_iterator key_value = begin(); key_value != end(); ++key_value) { cout << "Value " << keyFormatter(key_value->key) << ": "; key_value->value.print(""); From 8b1f3e174587c8d15126ecad0d007d939e64802b Mon Sep 17 00:00:00 2001 From: Jose Luis Blanco-Claraco Date: Mon, 27 Jul 2020 08:54:14 +0200 Subject: [PATCH 288/869] docs and missing traits --- gtsam/nonlinear/ExpressionFactor.h | 6 ++++++ 1 file changed, 6 insertions(+) diff --git a/gtsam/nonlinear/ExpressionFactor.h b/gtsam/nonlinear/ExpressionFactor.h index 4bb8da685..85527f6dc 100644 --- a/gtsam/nonlinear/ExpressionFactor.h +++ b/gtsam/nonlinear/ExpressionFactor.h @@ -34,6 +34,9 @@ namespace gtsam { * such instances, the user should declare derived classes from this template, * implementing expresion(), serialize(), clone(), print(), and defining the * corresponding `struct traits : public Testable {}`. + * + * \tparam T Type for measurements. + * */ template class ExpressionFactor: public NoiseModelFactor { @@ -279,6 +282,9 @@ class ExpressionFactor2 : public ExpressionFactor { "ExpressionFactor", boost::serialization::base_object >(*this)); } }; +/// traits +template +struct traits> : public Testable> {}; // ExpressionFactor2 }// \ namespace gtsam From 947479e9debc53ffe8800dc9711d9c1a410497b1 Mon Sep 17 00:00:00 2001 From: Jose Luis Blanco-Claraco Date: Mon, 27 Jul 2020 11:57:31 +0200 Subject: [PATCH 289/869] Add variadic-template N-ary ExpressionFactor --- gtsam/nonlinear/ExpressionFactor.h | 72 +++++++++++++++++++++- tests/testExpressionFactor.cpp | 97 ++++++++++++++++++++++++++++++ 2 files changed, 167 insertions(+), 2 deletions(-) diff --git a/gtsam/nonlinear/ExpressionFactor.h b/gtsam/nonlinear/ExpressionFactor.h index 85527f6dc..41eb1642e 100644 --- a/gtsam/nonlinear/ExpressionFactor.h +++ b/gtsam/nonlinear/ExpressionFactor.h @@ -19,9 +19,10 @@ #pragma once +#include +#include #include #include -#include #include namespace gtsam { @@ -287,4 +288,71 @@ template struct traits> : public Testable> {}; // ExpressionFactor2 -}// \ namespace gtsam +/** + * N-ary variadic template for ExpressionFactor meant as a base class for N-ary + * factors. Enforces an 'expression' method with N keys. + * Derived class (an N-factor!) needs to call 'initialize'. + * + * Does not provide backward compatible 'evaluateError'. + * + * \tparam T Type for measurements. The rest of template arguments are types + * for the N key-indexed Values. + * + */ +template +class ExpressionFactorN : public ExpressionFactor { +public: + static const std::size_t NARY_EXPRESSION_SIZE = sizeof...(Args); + using ArrayNKeys = std::array; + + /// Destructor + virtual ~ExpressionFactorN() = default; + + // Don't provide backward compatible evaluateVector(), due to its problematic + // variable length of optional Jacobian arguments. Vector evaluateError(const + // Args... args,...); + + /// Recreate expression from given keys_ and measured_, used in load + /// Needed to deserialize a derived factor + virtual Expression expression(const ArrayNKeys &keys) const { + throw std::runtime_error( + "ExpressionFactorN::expression not provided: cannot deserialize."); + } + +protected: + /// Default constructor, for serialization + ExpressionFactorN() = default; + + /// Constructor takes care of keys, but still need to call initialize + ExpressionFactorN(const ArrayNKeys &keys, const SharedNoiseModel &noiseModel, + const T &measurement) + : ExpressionFactor(noiseModel, measurement) { + for (const auto &key : keys) + Factor::keys_.push_back(key); + } + +private: + /// Return an expression that predicts the measurement given Values + Expression expression() const override { + ArrayNKeys keys; + int idx = 0; + for (const auto &key : Factor::keys_) + keys[idx++] = key; + return expression(keys); + } + + friend class boost::serialization::access; + template + void serialize(ARCHIVE &ar, const unsigned int /*version*/) { + ar &boost::serialization::make_nvp( + "ExpressionFactorN", + boost::serialization::base_object>(*this)); + } +}; +/// traits +template +struct traits> + : public Testable> {}; +// ExpressionFactorN + +} // namespace gtsam diff --git a/tests/testExpressionFactor.cpp b/tests/testExpressionFactor.cpp index d33c7ba1d..e3e37e7c7 100644 --- a/tests/testExpressionFactor.cpp +++ b/tests/testExpressionFactor.cpp @@ -630,6 +630,103 @@ TEST(ExpressionFactor, MultiplyWithInverseFunction) { EXPECT_CORRECT_FACTOR_JACOBIANS(factor, values, 1e-5, 1e-5); } + +/* ************************************************************************* */ +// Test N-ary variadic template +class TestNaryFactor + : public gtsam::ExpressionFactorN { +private: + using This = TestNaryFactor; + using Base = + gtsam::ExpressionFactorN; + +public: + /// default constructor + TestNaryFactor() = default; + ~TestNaryFactor() override = default; + + TestNaryFactor(gtsam::Key kR1, gtsam::Key kV1, gtsam::Key kR2, gtsam::Key kV2, + const gtsam::SharedNoiseModel &model, const gtsam::Point3& measured) + : Base({kR1, kV1, kR2, kV2}, model, measured) { + this->initialize(expression({kR1, kV1, kR2, kV2})); + } + + /// @return a deep copy of this factor + gtsam::NonlinearFactor::shared_ptr clone() const override { + return boost::static_pointer_cast( + gtsam::NonlinearFactor::shared_ptr(new This(*this))); + } + + // Return measurement expression + gtsam::Expression expression( + const std::array &keys) const override { + gtsam::Expression R1_(keys[0]); + gtsam::Expression V1_(keys[1]); + gtsam::Expression R2_(keys[2]); + gtsam::Expression V2_(keys[3]); + return {gtsam::rotate(R1_, V1_) - gtsam::rotate(R2_, V2_)}; + } + + /** print */ + void print(const std::string &s, + const gtsam::KeyFormatter &keyFormatter = + gtsam::DefaultKeyFormatter) const override { + std::cout << s << "TestNaryFactor(" + << keyFormatter(Factor::keys_[0]) << "," + << keyFormatter(Factor::keys_[1]) << "," + << keyFormatter(Factor::keys_[2]) << "," + << keyFormatter(Factor::keys_[3]) << ")\n"; + gtsam::traits::Print(measured_, " measured: "); + this->noiseModel_->print(" noise model: "); + } + + /** equals */ + bool equals(const gtsam::NonlinearFactor &expected, + double tol = 1e-9) const override { + const This *e = dynamic_cast(&expected); + return e != nullptr && Base::equals(*e, tol) && + gtsam::traits::Equals(measured_,e->measured_, tol); + } + +private: + /** Serialization function */ + friend class boost::serialization::access; + template + void serialize(ARCHIVE &ar, const unsigned int /*version*/) { + ar &boost::serialization::make_nvp( + "TestNaryFactor", + boost::serialization::base_object(*this)); + ar &BOOST_SERIALIZATION_NVP(measured_); + } +}; + +TEST(ExpressionFactor, variadicTemplate) { + using gtsam::symbol_shorthand::R; + using gtsam::symbol_shorthand::V; + + // Create factor + TestNaryFactor f(R(0),V(0), R(1), V(1), noiseModel::Unit::Create(3), Point3(0,0,0)); + + // Create some values + Values values; + values.insert(R(0), Rot3::Ypr(0.1, 0.2, 0.3)); + values.insert(V(0), Point3(1, 2, 3)); + values.insert(R(1), Rot3::Ypr(0.2, 0.5, 0.2)); + values.insert(V(1), Point3(5, 6, 7)); + + // Check unwhitenedError + std::vector H(4); + Vector actual = f.unwhitenedError(values, H); + EXPECT_LONGS_EQUAL(4, H.size()); + EXPECT(assert_equal(Eigen::Vector3d(-5.63578115, -4.85353243, -1.4801204), actual, 1e-5)); + + EXPECT_CORRECT_FACTOR_JACOBIANS(f, values, 1e-8, 1e-5); +} + + /* ************************************************************************* */ int main() { TestResult tr; From 90dc1ce3b51a6917a5cf47de2c4d5f636aade31d Mon Sep 17 00:00:00 2001 From: Jose Luis Blanco-Claraco Date: Mon, 27 Jul 2020 12:04:08 +0200 Subject: [PATCH 290/869] typo --- gtsam/nonlinear/ExpressionFactor.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/gtsam/nonlinear/ExpressionFactor.h b/gtsam/nonlinear/ExpressionFactor.h index 41eb1642e..8c4304318 100644 --- a/gtsam/nonlinear/ExpressionFactor.h +++ b/gtsam/nonlinear/ExpressionFactor.h @@ -351,7 +351,7 @@ private: }; /// traits template -struct traits> +struct traits> : public Testable> {}; // ExpressionFactorN From c9bd7ef8a70fbe63e519c0ac83754eb979fd5bf6 Mon Sep 17 00:00:00 2001 From: Jose Luis Blanco Claraco Date: Tue, 28 Jul 2020 00:20:16 +0200 Subject: [PATCH 291/869] Deprecate ExpressionFactor2 --- gtsam/nonlinear/ExpressionFactor.h | 117 ++++++++++++++--------------- 1 file changed, 55 insertions(+), 62 deletions(-) diff --git a/gtsam/nonlinear/ExpressionFactor.h b/gtsam/nonlinear/ExpressionFactor.h index 8c4304318..a690a62b3 100644 --- a/gtsam/nonlinear/ExpressionFactor.h +++ b/gtsam/nonlinear/ExpressionFactor.h @@ -20,6 +20,7 @@ #pragma once #include +#include #include #include #include @@ -226,68 +227,6 @@ private: template struct traits > : public Testable > {}; -/** - * Binary specialization of ExpressionFactor meant as a base class for binary - * factors. Enforces an 'expression' method with two keys, and provides 'evaluateError'. - * Derived class (a binary factor!) needs to call 'initialize'. - */ -template -class ExpressionFactor2 : public ExpressionFactor { - public: - /// Destructor - virtual ~ExpressionFactor2() {} - - /// Backwards compatible evaluateError, to make existing tests compile - Vector evaluateError(const A1& a1, const A2& a2, - boost::optional H1 = boost::none, - boost::optional H2 = boost::none) const { - Values values; - values.insert(this->keys_[0], a1); - values.insert(this->keys_[1], a2); - std::vector H(2); - Vector error = this->unwhitenedError(values, H); - if (H1) (*H1) = H[0]; - if (H2) (*H2) = H[1]; - return error; - } - - /// Recreate expression from given keys_ and measured_, used in load - /// Needed to deserialize a derived factor - virtual Expression expression(Key key1, Key key2) const { - throw std::runtime_error("ExpressionFactor2::expression not provided: cannot deserialize."); - } - - protected: - /// Default constructor, for serialization - ExpressionFactor2() {} - - /// Constructor takes care of keys, but still need to call initialize - ExpressionFactor2(Key key1, Key key2, - const SharedNoiseModel& noiseModel, - const T& measurement) - : ExpressionFactor(noiseModel, measurement) { - this->keys_.push_back(key1); - this->keys_.push_back(key2); - } - - private: - /// Return an expression that predicts the measurement given Values - Expression expression() const override { - return expression(this->keys_[0], this->keys_[1]); - } - - friend class boost::serialization::access; - template - void serialize(ARCHIVE& ar, const unsigned int /*version*/) { - ar& boost::serialization::make_nvp( - "ExpressionFactor", boost::serialization::base_object >(*this)); - } -}; -/// traits -template -struct traits> : public Testable> {}; -// ExpressionFactor2 - /** * N-ary variadic template for ExpressionFactor meant as a base class for N-ary * factors. Enforces an 'expression' method with N keys. @@ -355,4 +294,58 @@ struct traits> : public Testable> {}; // ExpressionFactorN + +#if defined(GTSAM_ALLOW_DEPRECATED_SINCE_V4) +/** + * Binary specialization of ExpressionFactor meant as a base class for binary + * factors. Enforces an 'expression' method with two keys, and provides + * 'evaluateError'. Derived class (a binary factor!) needs to call 'initialize'. + * + * \sa ExpressionFactorN + * \deprecated Prefer the more general ExpressionFactorN<>. + */ +template +class ExpressionFactor2 : public ExpressionFactorN { +public: + /// Destructor + ~ExpressionFactor2() override {} + + /// Backwards compatible evaluateError, to make existing tests compile + Vector evaluateError(const A1 &a1, const A2 &a2, + boost::optional H1 = boost::none, + boost::optional H2 = boost::none) const { + Values values; + values.insert(this->keys_[0], a1); + values.insert(this->keys_[1], a2); + std::vector H(2); + Vector error = ExpressionFactor::unwhitenedError(values, H); + if (H1) (*H1) = H[0]; + if (H2) (*H2) = H[1]; + return error; + } + + /// Recreate expression from given keys_ and measured_, used in load + /// Needed to deserialize a derived factor + virtual Expression expression(Key key1, Key key2) const { + throw std::runtime_error( + "ExpressionFactor2::expression not provided: cannot deserialize."); + } + virtual Expression + expression(const typename ExpressionFactorN::ArrayNKeys &keys) + const override { + return expression(keys[0], keys[1]); + } + +protected: + /// Default constructor, for serialization + ExpressionFactor2() {} + + /// Constructor takes care of keys, but still need to call initialize + ExpressionFactor2(Key key1, Key key2, const SharedNoiseModel &noiseModel, + const T &measurement) + : ExpressionFactorN({key1, key2}, noiseModel, measurement) {} +}; +// ExpressionFactor2 +#endif + } // namespace gtsam From 6b630effd09adfd632348a6e2a5973368c95d807 Mon Sep 17 00:00:00 2001 From: Jose Luis Blanco Claraco Date: Tue, 28 Jul 2020 01:01:37 +0200 Subject: [PATCH 292/869] port ExpressionFactor{2->N} --- gtsam/sam/BearingFactor.h | 14 +++---- gtsam/sam/BearingRangeFactor.h | 14 +++---- gtsam/sam/RangeFactor.h | 28 ++++++------- gtsam/sam/tests/testBearingFactor.cpp | 4 +- gtsam/sam/tests/testBearingRangeFactor.cpp | 4 +- gtsam/sam/tests/testRangeFactor.cpp | 48 ++++++++++++++-------- 6 files changed, 62 insertions(+), 50 deletions(-) diff --git a/gtsam/sam/BearingFactor.h b/gtsam/sam/BearingFactor.h index 530fcfdcd..ece26f3dc 100644 --- a/gtsam/sam/BearingFactor.h +++ b/gtsam/sam/BearingFactor.h @@ -34,8 +34,8 @@ struct Bearing; */ template ::result_type> -struct BearingFactor : public ExpressionFactor2 { - typedef ExpressionFactor2 Base; +struct BearingFactor : public ExpressionFactorN { + typedef ExpressionFactorN Base; /// default constructor BearingFactor() {} @@ -43,14 +43,14 @@ struct BearingFactor : public ExpressionFactor2 { /// primary constructor BearingFactor(Key key1, Key key2, const T& measured, const SharedNoiseModel& model) - : Base(key1, key2, model, measured) { - this->initialize(expression(key1, key2)); + : Base({key1, key2}, model, measured) { + this->initialize(expression({key1, key2})); } // Return measurement expression - Expression expression(Key key1, Key key2) const override { - Expression a1_(key1); - Expression a2_(key2); + Expression expression(const typename Base::ArrayNKeys &keys) const override { + Expression a1_(keys[0]); + Expression a2_(keys[1]); return Expression(Bearing(), a1_, a2_); } diff --git a/gtsam/sam/BearingRangeFactor.h b/gtsam/sam/BearingRangeFactor.h index be645ef94..2bd5fa11c 100644 --- a/gtsam/sam/BearingRangeFactor.h +++ b/gtsam/sam/BearingRangeFactor.h @@ -33,10 +33,10 @@ template ::result_type, typename R = typename Range::result_type> class BearingRangeFactor - : public ExpressionFactor2, A1, A2> { + : public ExpressionFactorN, A1, A2> { private: typedef BearingRange T; - typedef ExpressionFactor2 Base; + typedef ExpressionFactorN Base; typedef BearingRangeFactor This; public: @@ -48,8 +48,8 @@ class BearingRangeFactor /// primary constructor BearingRangeFactor(Key key1, Key key2, const B& measuredBearing, const R& measuredRange, const SharedNoiseModel& model) - : Base(key1, key2, model, T(measuredBearing, measuredRange)) { - this->initialize(expression(key1, key2)); + : Base({key1, key2}, model, T(measuredBearing, measuredRange)) { + this->initialize(expression({key1, key2})); } virtual ~BearingRangeFactor() {} @@ -61,9 +61,9 @@ class BearingRangeFactor } // Return measurement expression - Expression expression(Key key1, Key key2) const override { - return Expression(T::Measure, Expression(key1), - Expression(key2)); + Expression expression(const typename Base::ArrayNKeys& keys) const override { + return Expression(T::Measure, Expression(keys[0]), + Expression(keys[1])); } /// print diff --git a/gtsam/sam/RangeFactor.h b/gtsam/sam/RangeFactor.h index 80b02404e..abf11d179 100644 --- a/gtsam/sam/RangeFactor.h +++ b/gtsam/sam/RangeFactor.h @@ -32,18 +32,18 @@ struct Range; * @addtogroup SAM */ template -class RangeFactor : public ExpressionFactor2 { +class RangeFactor : public ExpressionFactorN { private: typedef RangeFactor This; - typedef ExpressionFactor2 Base; + typedef ExpressionFactorN Base; public: /// default constructor RangeFactor() {} RangeFactor(Key key1, Key key2, T measured, const SharedNoiseModel& model) - : Base(key1, key2, model, measured) { - this->initialize(expression(key1, key2)); + : Base({key1, key2}, model, measured) { + this->initialize(expression({key1, key2})); } /// @return a deep copy of this factor @@ -53,9 +53,9 @@ class RangeFactor : public ExpressionFactor2 { } // Return measurement expression - Expression expression(Key key1, Key key2) const override { - Expression a1_(key1); - Expression a2_(key2); + Expression expression(const typename Base::ArrayNKeys& keys) const override { + Expression a1_(keys[0]); + Expression a2_(keys[1]); return Expression(Range(), a1_, a2_); } @@ -86,10 +86,10 @@ struct traits > */ template ::result_type> -class RangeFactorWithTransform : public ExpressionFactor2 { +class RangeFactorWithTransform : public ExpressionFactorN { private: typedef RangeFactorWithTransform This; - typedef ExpressionFactor2 Base; + typedef ExpressionFactorN Base; A1 body_T_sensor_; ///< The pose of the sensor in the body frame @@ -100,8 +100,8 @@ class RangeFactorWithTransform : public ExpressionFactor2 { RangeFactorWithTransform(Key key1, Key key2, T measured, const SharedNoiseModel& model, const A1& body_T_sensor) - : Base(key1, key2, model, measured), body_T_sensor_(body_T_sensor) { - this->initialize(expression(key1, key2)); + : Base({key1, key2}, model, measured), body_T_sensor_(body_T_sensor) { + this->initialize(expression({key1, key2})); } virtual ~RangeFactorWithTransform() {} @@ -113,12 +113,12 @@ class RangeFactorWithTransform : public ExpressionFactor2 { } // Return measurement expression - Expression expression(Key key1, Key key2) const override { + Expression expression(const typename Base::ArrayNKeys& keys) const override { Expression body_T_sensor__(body_T_sensor_); - Expression nav_T_body_(key1); + Expression nav_T_body_(keys[0]); Expression nav_T_sensor_(traits::Compose, nav_T_body_, body_T_sensor__); - Expression a2_(key2); + Expression a2_(keys[1]); return Expression(Range(), nav_T_sensor_, a2_); } diff --git a/gtsam/sam/tests/testBearingFactor.cpp b/gtsam/sam/tests/testBearingFactor.cpp index 12635a7e5..17a049a1d 100644 --- a/gtsam/sam/tests/testBearingFactor.cpp +++ b/gtsam/sam/tests/testBearingFactor.cpp @@ -68,7 +68,7 @@ TEST(BearingFactor, 2D) { values.insert(poseKey, Pose2(1.0, 2.0, 0.57)); values.insert(pointKey, Point2(-4.0, 11.0)); - EXPECT_CORRECT_EXPRESSION_JACOBIANS(factor.expression(poseKey, pointKey), + EXPECT_CORRECT_EXPRESSION_JACOBIANS(factor.expression({poseKey, pointKey}), values, 1e-7, 1e-5); EXPECT_CORRECT_FACTOR_JACOBIANS(factor, values, 1e-7, 1e-5); } @@ -104,7 +104,7 @@ TEST(BearingFactor, Serialization3D) { // values.insert(poseKey, Pose3()); // values.insert(pointKey, Point3(1, 0, 0)); // -// EXPECT_CORRECT_EXPRESSION_JACOBIANS(factor.expression(poseKey, pointKey), +// EXPECT_CORRECT_EXPRESSION_JACOBIANS(factor.expression({poseKey, pointKey}), // values, 1e-7, 1e-5); // EXPECT_CORRECT_FACTOR_JACOBIANS(factor, values, 1e-7, 1e-5); //} diff --git a/gtsam/sam/tests/testBearingRangeFactor.cpp b/gtsam/sam/tests/testBearingRangeFactor.cpp index 4c7a9ab91..735358d89 100644 --- a/gtsam/sam/tests/testBearingRangeFactor.cpp +++ b/gtsam/sam/tests/testBearingRangeFactor.cpp @@ -67,7 +67,7 @@ TEST(BearingRangeFactor, 2D) { values.insert(poseKey, Pose2(1.0, 2.0, 0.57)); values.insert(pointKey, Point2(-4.0, 11.0)); - EXPECT_CORRECT_EXPRESSION_JACOBIANS(factor.expression(poseKey, pointKey), + EXPECT_CORRECT_EXPRESSION_JACOBIANS(factor.expression({poseKey, pointKey}), values, 1e-7, 1e-5); EXPECT_CORRECT_FACTOR_JACOBIANS(factor, values, 1e-7, 1e-5); } @@ -95,7 +95,7 @@ TEST(BearingRangeFactor, Serialization3D) { // values.insert(poseKey, Pose3()); // values.insert(pointKey, Point3(1, 0, 0)); // -// EXPECT_CORRECT_EXPRESSION_JACOBIANS(factor.expression(poseKey, pointKey), +// EXPECT_CORRECT_EXPRESSION_JACOBIANS(factor.expression({poseKey, pointKey}), // values, 1e-7, 1e-5); // EXPECT_CORRECT_FACTOR_JACOBIANS(factor, values, 1e-7, 1e-5); //} diff --git a/gtsam/sam/tests/testRangeFactor.cpp b/gtsam/sam/tests/testRangeFactor.cpp index 54d4a43c0..f10fb449d 100644 --- a/gtsam/sam/tests/testRangeFactor.cpp +++ b/gtsam/sam/tests/testRangeFactor.cpp @@ -47,25 +47,29 @@ double measurement(10.0); /* ************************************************************************* */ Vector factorError2D(const Pose2& pose, const Point2& point, const RangeFactor2D& factor) { - return factor.evaluateError(pose, point); + const auto &keys = factor.keys(); + return factor.unwhitenedError({{keys[0], genericValue(pose)}, {keys[1], genericValue(point)}}); } /* ************************************************************************* */ Vector factorError3D(const Pose3& pose, const Point3& point, const RangeFactor3D& factor) { - return factor.evaluateError(pose, point); + const auto &keys = factor.keys(); + return factor.unwhitenedError({{keys[0], genericValue(pose)}, {keys[1], genericValue(point)}}); } /* ************************************************************************* */ Vector factorErrorWithTransform2D(const Pose2& pose, const Point2& point, const RangeFactorWithTransform2D& factor) { - return factor.evaluateError(pose, point); + const auto &keys = factor.keys(); + return factor.unwhitenedError({{keys[0], genericValue(pose)}, {keys[1], genericValue(point)}}); } /* ************************************************************************* */ Vector factorErrorWithTransform3D(const Pose3& pose, const Point3& point, const RangeFactorWithTransform3D& factor) { - return factor.evaluateError(pose, point); + const auto &keys = factor.keys(); + return factor.unwhitenedError({{keys[0], genericValue(pose)}, {keys[1], genericValue(point)}}); } /* ************************************************************************* */ @@ -152,7 +156,7 @@ TEST( RangeFactor, Error2D ) { Point2 point(-4.0, 11.0); // Use the factor to calculate the error - Vector actualError(factor.evaluateError(pose, point)); + Vector actualError(factor.unwhitenedError({{poseKey, genericValue(pose)}, {pointKey, genericValue(point)}})); // The expected error is ||(5.0, 9.0)|| - 10.0 = 0.295630141 meter / UnitCovariance Vector expectedError = (Vector(1) << 0.295630141).finished(); @@ -175,7 +179,7 @@ TEST( RangeFactor, Error2DWithTransform ) { Point2 point(-4.0, 11.0); // Use the factor to calculate the error - Vector actualError(factor.evaluateError(pose, point)); + Vector actualError(factor.unwhitenedError({{poseKey, genericValue(pose)}, {pointKey, genericValue(point)}})); // The expected error is ||(5.0, 9.0)|| - 10.0 = 0.295630141 meter / UnitCovariance Vector expectedError = (Vector(1) << 0.295630141).finished(); @@ -194,7 +198,7 @@ TEST( RangeFactor, Error3D ) { Point3 point(-2.0, 11.0, 1.0); // Use the factor to calculate the error - Vector actualError(factor.evaluateError(pose, point)); + Vector actualError(factor.unwhitenedError({{poseKey, genericValue(pose)}, {pointKey, genericValue(point)}})); // The expected error is ||(3.0, 9.0, 4.0)|| - 10.0 = 0.295630141 meter / UnitCovariance Vector expectedError = (Vector(1) << 0.295630141).finished(); @@ -218,7 +222,7 @@ TEST( RangeFactor, Error3DWithTransform ) { Point3 point(-2.0, 11.0, 1.0); // Use the factor to calculate the error - Vector actualError(factor.evaluateError(pose, point)); + Vector actualError(factor.unwhitenedError({{poseKey, genericValue(pose)}, {pointKey, genericValue(point)}})); // The expected error is ||(3.0, 9.0, 4.0)|| - 10.0 = 0.295630141 meter / UnitCovariance Vector expectedError = (Vector(1) << 0.295630141).finished(); @@ -237,8 +241,10 @@ TEST( RangeFactor, Jacobian2D ) { Point2 point(-4.0, 11.0); // Use the factor to calculate the Jacobians - Matrix H1Actual, H2Actual; - factor.evaluateError(pose, point, H1Actual, H2Actual); + std::vector actualHs(2); + factor.unwhitenedError({{poseKey, genericValue(pose)}, {pointKey, genericValue(point)}}, actualHs); + const Matrix& H1Actual = actualHs.at(0); + const Matrix& H2Actual = actualHs.at(1); // Use numerical derivatives to calculate the Jacobians Matrix H1Expected, H2Expected; @@ -266,8 +272,10 @@ TEST( RangeFactor, Jacobian2DWithTransform ) { Point2 point(-4.0, 11.0); // Use the factor to calculate the Jacobians - Matrix H1Actual, H2Actual; - factor.evaluateError(pose, point, H1Actual, H2Actual); + std::vector actualHs(2); + factor.unwhitenedError({{poseKey, genericValue(pose)}, {pointKey, genericValue(point)}}, actualHs); + const Matrix& H1Actual = actualHs.at(0); + const Matrix& H2Actual = actualHs.at(1); // Use numerical derivatives to calculate the Jacobians Matrix H1Expected, H2Expected; @@ -291,8 +299,10 @@ TEST( RangeFactor, Jacobian3D ) { Point3 point(-2.0, 11.0, 1.0); // Use the factor to calculate the Jacobians - Matrix H1Actual, H2Actual; - factor.evaluateError(pose, point, H1Actual, H2Actual); + std::vector actualHs(2); + factor.unwhitenedError({{poseKey, genericValue(pose)}, {pointKey, genericValue(point)}}, actualHs); + const Matrix& H1Actual = actualHs.at(0); + const Matrix& H2Actual = actualHs.at(1); // Use numerical derivatives to calculate the Jacobians Matrix H1Expected, H2Expected; @@ -321,8 +331,10 @@ TEST( RangeFactor, Jacobian3DWithTransform ) { Point3 point(-2.0, 11.0, 1.0); // Use the factor to calculate the Jacobians - Matrix H1Actual, H2Actual; - factor.evaluateError(pose, point, H1Actual, H2Actual); + std::vector actualHs(2); + factor.unwhitenedError({{poseKey, genericValue(pose)}, {pointKey, genericValue(point)}}, actualHs); + const Matrix& H1Actual = actualHs.at(0); + const Matrix& H2Actual = actualHs.at(1); // Use numerical derivatives to calculate the Jacobians Matrix H1Expected, H2Expected; @@ -350,7 +362,7 @@ TEST(RangeFactor, Point3) { Vector expectedError = (Vector(1) << 0.295630141).finished(); // Verify we get the expected error - CHECK(assert_equal(expectedError, factor.evaluateError(pose, point), 1e-9)); + CHECK(assert_equal(expectedError, factor.unwhitenedError({{poseKey, genericValue(pose)}, {pointKey, genericValue(point)}}), 1e-9)); } /* ************************************************************************* */ @@ -393,7 +405,7 @@ TEST(RangeFactor, NonGTSAM) { Vector expectedError = (Vector(1) << 0.295630141).finished(); // Verify we get the expected error - CHECK(assert_equal(expectedError, factor.evaluateError(pose, point), 1e-9)); + CHECK(assert_equal(expectedError, factor.unwhitenedError({{poseKey, genericValue(pose)}, {pointKey, genericValue(point)}}), 1e-9)); } /* ************************************************************************* */ From 7b18d33c00db15353777cc28b2b9b991824cac05 Mon Sep 17 00:00:00 2001 From: Jose Luis Blanco-Claraco Date: Tue, 28 Jul 2020 12:03:54 +0200 Subject: [PATCH 293/869] Add unit test revealing deserialization error --- gtsam/sam/tests/testRangeFactor.cpp | 21 +++++++++++++++++++++ 1 file changed, 21 insertions(+) diff --git a/gtsam/sam/tests/testRangeFactor.cpp b/gtsam/sam/tests/testRangeFactor.cpp index f10fb449d..7ec8dc580 100644 --- a/gtsam/sam/tests/testRangeFactor.cpp +++ b/gtsam/sam/tests/testRangeFactor.cpp @@ -145,6 +145,27 @@ TEST( RangeFactor, EqualsWithTransform ) { body_P_sensor_3D); CHECK(assert_equal(factor3D_1, factor3D_2)); } +/* ************************************************************************* */ +TEST( RangeFactor, EqualsAfterDeserializing) { + // Check that the same results are obtained after deserializing: + Pose3 body_P_sensor_3D(Rot3::RzRyRx(-M_PI_2, 0.0, -M_PI_2), + Point3(0.25, -0.10, 1.0)); + + RangeFactorWithTransform3D factor3D_1(poseKey, pointKey, measurement, model, + body_P_sensor_3D), factor3D_2; + + // check with Equal() trait: + gtsam::serializationTestHelpers::roundtripXML(factor3D_1, factor3D_2); + CHECK(assert_equal(factor3D_1, factor3D_2)); + + const Pose3 pose(Rot3::RzRyRx(0.2, -0.3, 1.75), Point3(1.0, 2.0, -3.0)); + const Point3 point(-2.0, 11.0, 1.0); + const Values values = {{poseKey, genericValue(pose)}, {pointKey, genericValue(point)}}; + + const Vector error_1 = factor3D_1.unwhitenedError(values); + const Vector error_2 = factor3D_2.unwhitenedError(values); + CHECK(assert_equal(error_1, error_2)); +} /* ************************************************************************* */ TEST( RangeFactor, Error2D ) { From 4e34d644533167b0e9a747d6f185aacc6bd72822 Mon Sep 17 00:00:00 2001 From: Jose Luis Blanco-Claraco Date: Tue, 28 Jul 2020 12:05:41 +0200 Subject: [PATCH 294/869] Fix serialization bug in RangeFactor Closes #443 --- gtsam/sam/RangeFactor.h | 5 ++++- 1 file changed, 4 insertions(+), 1 deletion(-) diff --git a/gtsam/sam/RangeFactor.h b/gtsam/sam/RangeFactor.h index abf11d179..0bc997044 100644 --- a/gtsam/sam/RangeFactor.h +++ b/gtsam/sam/RangeFactor.h @@ -135,9 +135,12 @@ class RangeFactorWithTransform : public ExpressionFactorN { friend class boost::serialization::access; template void serialize(ARCHIVE& ar, const unsigned int /*version*/) { + // **IMPORTANT** We need to (de)serialize parameters before the base class, + // since it calls expression() and we need all parameters ready at that + // point. + ar& BOOST_SERIALIZATION_NVP(body_T_sensor_); ar& boost::serialization::make_nvp( "Base", boost::serialization::base_object(*this)); - ar& BOOST_SERIALIZATION_NVP(body_T_sensor_); } }; // \ RangeFactorWithTransform From b6ab778e96ff299d0853c4a4e89d834c3cca48b3 Mon Sep 17 00:00:00 2001 From: Fan Jiang Date: Tue, 28 Jul 2020 11:05:24 -0400 Subject: [PATCH 295/869] Fix import typo --- python/gtsam_py/python/tests/test_SFMExample.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/python/gtsam_py/python/tests/test_SFMExample.py b/python/gtsam_py/python/tests/test_SFMExample.py index 1425902cf..295bf0b5e 100644 --- a/python/gtsam_py/python/tests/test_SFMExample.py +++ b/python/gtsam_py/python/tests/test_SFMExample.py @@ -15,7 +15,7 @@ import numpy as np import gtsam import gtsam.utils.visual_data_generator as generator from gtsam import symbol -from gtsam.gtsam.noiseModel improt Isotropic, Diagonal +from gtsam.gtsam.noiseModel import Isotropic, Diagonal from gtsam.utils.test_case import GtsamTestCase From 08da0ab5a607086d605cc1470bff0344c5549542 Mon Sep 17 00:00:00 2001 From: Fan Jiang Date: Tue, 28 Jul 2020 11:16:58 -0400 Subject: [PATCH 296/869] Change to new KeyVector accessor --- .../python/examples/Pose3SLAMExample_initializePose3Chordal.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/python/gtsam_py/python/examples/Pose3SLAMExample_initializePose3Chordal.py b/python/gtsam_py/python/examples/Pose3SLAMExample_initializePose3Chordal.py index 140669c95..2b2c5f991 100644 --- a/python/gtsam_py/python/examples/Pose3SLAMExample_initializePose3Chordal.py +++ b/python/gtsam_py/python/examples/Pose3SLAMExample_initializePose3Chordal.py @@ -26,7 +26,7 @@ graph, initial = gtsam.readG2o(g2oFile, is3D) # Add prior on the first key. TODO: assumes first key ios z priorModel = gtsam.noiseModel.Diagonal.Variances( np.array([1e-6, 1e-6, 1e-6, 1e-4, 1e-4, 1e-4])) -firstKey = initial.keys().at(0) +firstKey = initial.keys()[0] graph.add(gtsam.PriorFactorPose3(0, gtsam.Pose3(), priorModel)) # Initializing Pose3 - chordal relaxation" From efed4237dc1e108ebf60d1944025ed2875a9bec4 Mon Sep 17 00:00:00 2001 From: Jose Luis Blanco Claraco Date: Tue, 28 Jul 2020 20:46:24 +0200 Subject: [PATCH 297/869] Deprecate ExpressionFactor2 for 4.1 --- gtsam/nonlinear/ExpressionFactor.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/gtsam/nonlinear/ExpressionFactor.h b/gtsam/nonlinear/ExpressionFactor.h index a690a62b3..6d6162825 100644 --- a/gtsam/nonlinear/ExpressionFactor.h +++ b/gtsam/nonlinear/ExpressionFactor.h @@ -295,7 +295,7 @@ struct traits> // ExpressionFactorN -#if defined(GTSAM_ALLOW_DEPRECATED_SINCE_V4) +#if defined(GTSAM_ALLOW_DEPRECATED_SINCE_V41) /** * Binary specialization of ExpressionFactor meant as a base class for binary * factors. Enforces an 'expression' method with two keys, and provides From 0ee5fc58f111507282bb5ecfeea5b8f6c5544ee7 Mon Sep 17 00:00:00 2001 From: Jose Luis Blanco Claraco Date: Tue, 28 Jul 2020 21:10:48 +0200 Subject: [PATCH 298/869] Recover the convenient evaluateError() method --- gtsam/sam/BearingFactor.h | 15 +++++++++++++++ gtsam/sam/BearingRangeFactor.h | 14 ++++++++++++++ gtsam/sam/RangeFactor.h | 14 ++++++++++++++ gtsam/sam/tests/testRangeFactor.cpp | 18 ++++++------------ 4 files changed, 49 insertions(+), 12 deletions(-) diff --git a/gtsam/sam/BearingFactor.h b/gtsam/sam/BearingFactor.h index ece26f3dc..7076708db 100644 --- a/gtsam/sam/BearingFactor.h +++ b/gtsam/sam/BearingFactor.h @@ -60,6 +60,21 @@ struct BearingFactor : public ExpressionFactorN { std::cout << s << "BearingFactor" << std::endl; Base::print(s, kf); } + + Vector evaluateError(const A1& a1, const A2& a2, + boost::optional H1 = boost::none, + boost::optional H2 = boost::none) const + { + std::vector Hs(2); + const auto &keys = Factor::keys(); + const Vector error = unwhitenedError( + {{keys[0], genericValue(a1)}, {keys[1], genericValue(a2)}}, + Hs); + if (H1) *H1 = Hs[0]; + if (H2) *H2 = Hs[1]; + return error; + } + private: friend class boost::serialization::access; diff --git a/gtsam/sam/BearingRangeFactor.h b/gtsam/sam/BearingRangeFactor.h index 2bd5fa11c..af7b47446 100644 --- a/gtsam/sam/BearingRangeFactor.h +++ b/gtsam/sam/BearingRangeFactor.h @@ -66,6 +66,20 @@ class BearingRangeFactor Expression(keys[1])); } + Vector evaluateError(const A1& a1, const A2& a2, + boost::optional H1 = boost::none, + boost::optional H2 = boost::none) const + { + std::vector Hs(2); + const auto &keys = Factor::keys(); + const Vector error = unwhitenedError( + {{keys[0], genericValue(a1)}, {keys[1], genericValue(a2)}}, + Hs); + if (H1) *H1 = Hs[0]; + if (H2) *H2 = Hs[1]; + return error; + } + /// print void print(const std::string& s = "", const KeyFormatter& kf = DefaultKeyFormatter) const override { diff --git a/gtsam/sam/RangeFactor.h b/gtsam/sam/RangeFactor.h index 0bc997044..0150505b2 100644 --- a/gtsam/sam/RangeFactor.h +++ b/gtsam/sam/RangeFactor.h @@ -58,6 +58,20 @@ class RangeFactor : public ExpressionFactorN { Expression a2_(keys[1]); return Expression(Range(), a1_, a2_); } + + Vector evaluateError(const A1& a1, const A2& a2, + boost::optional H1 = boost::none, + boost::optional H2 = boost::none) const + { + std::vector Hs(2); + const auto &keys = Factor::keys(); + const Vector error = unwhitenedError( + {{keys[0], genericValue(a1)}, {keys[1], genericValue(a2)}}, + Hs); + if (H1) *H1 = Hs[0]; + if (H2) *H2 = Hs[1]; + return error; + } /// print void print(const std::string& s = "", diff --git a/gtsam/sam/tests/testRangeFactor.cpp b/gtsam/sam/tests/testRangeFactor.cpp index 7ec8dc580..8ae3d818b 100644 --- a/gtsam/sam/tests/testRangeFactor.cpp +++ b/gtsam/sam/tests/testRangeFactor.cpp @@ -47,29 +47,25 @@ double measurement(10.0); /* ************************************************************************* */ Vector factorError2D(const Pose2& pose, const Point2& point, const RangeFactor2D& factor) { - const auto &keys = factor.keys(); - return factor.unwhitenedError({{keys[0], genericValue(pose)}, {keys[1], genericValue(point)}}); + return factor.evaluateError(pose, point); } /* ************************************************************************* */ Vector factorError3D(const Pose3& pose, const Point3& point, const RangeFactor3D& factor) { - const auto &keys = factor.keys(); - return factor.unwhitenedError({{keys[0], genericValue(pose)}, {keys[1], genericValue(point)}}); + return factor.evaluateError(pose, point); } /* ************************************************************************* */ Vector factorErrorWithTransform2D(const Pose2& pose, const Point2& point, const RangeFactorWithTransform2D& factor) { - const auto &keys = factor.keys(); - return factor.unwhitenedError({{keys[0], genericValue(pose)}, {keys[1], genericValue(point)}}); + return factor.evaluateError(pose, point); } /* ************************************************************************* */ Vector factorErrorWithTransform3D(const Pose3& pose, const Point3& point, const RangeFactorWithTransform3D& factor) { - const auto &keys = factor.keys(); - return factor.unwhitenedError({{keys[0], genericValue(pose)}, {keys[1], genericValue(point)}}); + return factor.evaluateError(pose, point); } /* ************************************************************************* */ @@ -262,10 +258,8 @@ TEST( RangeFactor, Jacobian2D ) { Point2 point(-4.0, 11.0); // Use the factor to calculate the Jacobians - std::vector actualHs(2); - factor.unwhitenedError({{poseKey, genericValue(pose)}, {pointKey, genericValue(point)}}, actualHs); - const Matrix& H1Actual = actualHs.at(0); - const Matrix& H2Actual = actualHs.at(1); + Matrix H1Actual, H2Actual; + factor.evaluateError(pose, point, H1Actual, H2Actual); // Use numerical derivatives to calculate the Jacobians Matrix H1Expected, H2Expected; From dcd9415ddf4dcd3cb23146477f0818bff5ad777b Mon Sep 17 00:00:00 2001 From: Jose Luis Blanco Claraco Date: Tue, 28 Jul 2020 21:37:02 +0200 Subject: [PATCH 299/869] fix evaluateError() methods --- gtsam/sam/RangeFactor.h | 16 +++++++++++++++- 1 file changed, 15 insertions(+), 1 deletion(-) diff --git a/gtsam/sam/RangeFactor.h b/gtsam/sam/RangeFactor.h index 0150505b2..d9890d2ef 100644 --- a/gtsam/sam/RangeFactor.h +++ b/gtsam/sam/RangeFactor.h @@ -65,7 +65,7 @@ class RangeFactor : public ExpressionFactorN { { std::vector Hs(2); const auto &keys = Factor::keys(); - const Vector error = unwhitenedError( + const Vector error = Base::unwhitenedError( {{keys[0], genericValue(a1)}, {keys[1], genericValue(a2)}}, Hs); if (H1) *H1 = Hs[0]; @@ -136,6 +136,20 @@ class RangeFactorWithTransform : public ExpressionFactorN { return Expression(Range(), nav_T_sensor_, a2_); } + Vector evaluateError(const A1& a1, const A2& a2, + boost::optional H1 = boost::none, + boost::optional H2 = boost::none) const + { + std::vector Hs(2); + const auto &keys = Factor::keys(); + const Vector error = Base::unwhitenedError( + {{keys[0], genericValue(a1)}, {keys[1], genericValue(a2)}}, + Hs); + if (H1) *H1 = Hs[0]; + if (H2) *H2 = Hs[1]; + return error; + } + /** print contents */ void print(const std::string& s = "", const KeyFormatter& keyFormatter = DefaultKeyFormatter) const override { From ca88ac568bde7d69648814ed80cdda07bb3dfd7a Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Tue, 28 Jul 2020 15:57:15 -0500 Subject: [PATCH 300/869] fixed tests --- gtsam/geometry/tests/testPose3.cpp | 13 ++++++++++--- gtsam/navigation/tests/testNavState.cpp | 9 ++++++++- gtsam/nonlinear/tests/testValues.cpp | 2 +- 3 files changed, 19 insertions(+), 5 deletions(-) diff --git a/gtsam/geometry/tests/testPose3.cpp b/gtsam/geometry/tests/testPose3.cpp index bb64192ef..003fc3f9c 100644 --- a/gtsam/geometry/tests/testPose3.cpp +++ b/gtsam/geometry/tests/testPose3.cpp @@ -862,7 +862,14 @@ TEST( Pose3, stream) Pose3 T; std::ostringstream os; os << T; - string expected = "R: [\n\t1, 0, 0;\n\t0, 1, 0;\n\t0, 0, 1\n]\nt: [0, 0, 0]'"; + + string expected; + #ifdef GTSAM_TYPEDEF_POINTS_TO_VECTORS + expected = "R: [\n\t1, 0, 0;\n\t0, 1, 0;\n\t0, 0, 1\n]\nt: 0\n0\n0";; +#else + expected = "R: [\n\t1, 0, 0;\n\t0, 1, 0;\n\t0, 0, 1\n]\nt: [0, 0, 0]'"; +#endif + EXPECT(os.str() == expected); } @@ -1037,9 +1044,9 @@ TEST(Pose3, print) { expected << "R: [\n\t1, 0, 0;\n\t0, 1, 0;\n\t0, 0, 1\n]\n"; #ifdef GTSAM_TYPEDEF_POINTS_TO_VECTORS - expected << "1\n" + expected << "t: 1\n" "2\n" - "3;\n"; + "3\n"; #else expected << "t: [" << translation.x() << ", " << translation.y() << ", " << translation.z() << "]'\n"; #endif diff --git a/gtsam/navigation/tests/testNavState.cpp b/gtsam/navigation/tests/testNavState.cpp index 57945020c..0c649017a 100644 --- a/gtsam/navigation/tests/testNavState.cpp +++ b/gtsam/navigation/tests/testNavState.cpp @@ -244,7 +244,14 @@ TEST(NavState, Stream) std::ostringstream os; os << state; - string expected = "R: [\n\t1, 0, 0;\n\t0, 1, 0;\n\t0, 0, 1\n]\np: [0, 0, 0]'\nv: [0, 0, 0]'"; + + string expected; +#ifdef GTSAM_TYPEDEF_POINTS_TO_VECTORS + expected = "R: [\n\t1, 0, 0;\n\t0, 1, 0;\n\t0, 0, 1\n]\np: 0\n0\n0\nv: 0\n0\n0"; +#else + expected = "R: [\n\t1, 0, 0;\n\t0, 1, 0;\n\t0, 0, 1\n]\np: [0, 0, 0]'\nv: [0, 0, 0]'"; +#endif + EXPECT(os.str() == expected); } diff --git a/gtsam/nonlinear/tests/testValues.cpp b/gtsam/nonlinear/tests/testValues.cpp index 388bcf568..09b358efb 100644 --- a/gtsam/nonlinear/tests/testValues.cpp +++ b/gtsam/nonlinear/tests/testValues.cpp @@ -593,7 +593,7 @@ TEST(Values, Demangle) { Values values; Matrix13 v; v << 5.0, 6.0, 7.0; values.insert(key1, v); - string expected = "Values with 1 values:\nValue v1: (Eigen::Matrix) [\n 5, 6, 7\n]\n\n"; + string expected = "Values with 1 values:\nValue v1: (Eigen::Matrix)\n[\n 5, 6, 7\n]\n\n"; stringstream buffer; streambuf * old = cout.rdbuf(buffer.rdbuf()); From ce0f21930e2590f2e9c8f8f61161d955369176bf Mon Sep 17 00:00:00 2001 From: acxz <17132214+acxz@users.noreply.github.com> Date: Tue, 28 Jul 2020 17:10:23 -0400 Subject: [PATCH 301/869] remove empty smart folder --- gtsam/smart/CMakeLists.txt | 6 ------ gtsam/smart/tests/CMakeLists.txt | 1 - 2 files changed, 7 deletions(-) delete mode 100644 gtsam/smart/CMakeLists.txt delete mode 100644 gtsam/smart/tests/CMakeLists.txt diff --git a/gtsam/smart/CMakeLists.txt b/gtsam/smart/CMakeLists.txt deleted file mode 100644 index 53c18fe96..000000000 --- a/gtsam/smart/CMakeLists.txt +++ /dev/null @@ -1,6 +0,0 @@ -# Install headers -file(GLOB smart_headers "*.h") -install(FILES ${smart_headers} DESTINATION include/gtsam/smart) - -# Build tests -add_subdirectory(tests) diff --git a/gtsam/smart/tests/CMakeLists.txt b/gtsam/smart/tests/CMakeLists.txt deleted file mode 100644 index caa3164fa..000000000 --- a/gtsam/smart/tests/CMakeLists.txt +++ /dev/null @@ -1 +0,0 @@ -gtsamAddTestsGlob(smart "test*.cpp" "" "gtsam") From e069bd5301ae8b203ee070bf89fccf1c58878861 Mon Sep 17 00:00:00 2001 From: acxz <17132214+acxz@users.noreply.github.com> Date: Tue, 28 Jul 2020 19:24:25 -0400 Subject: [PATCH 302/869] remove smart from cmake --- gtsam/CMakeLists.txt | 1 - 1 file changed, 1 deletion(-) diff --git a/gtsam/CMakeLists.txt b/gtsam/CMakeLists.txt index 16dca6736..49b8bc19b 100644 --- a/gtsam/CMakeLists.txt +++ b/gtsam/CMakeLists.txt @@ -14,7 +14,6 @@ set (gtsam_subdirs sam sfm slam - smart navigation ) From 08df535cba26123ac360a83cab1f6f7d831a0cc0 Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Wed, 29 Jul 2020 11:35:02 -0500 Subject: [PATCH 303/869] fix indentation of macro guard --- gtsam/geometry/tests/testPose3.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/gtsam/geometry/tests/testPose3.cpp b/gtsam/geometry/tests/testPose3.cpp index 003fc3f9c..596fa8957 100644 --- a/gtsam/geometry/tests/testPose3.cpp +++ b/gtsam/geometry/tests/testPose3.cpp @@ -864,7 +864,7 @@ TEST( Pose3, stream) os << T; string expected; - #ifdef GTSAM_TYPEDEF_POINTS_TO_VECTORS +#ifdef GTSAM_TYPEDEF_POINTS_TO_VECTORS expected = "R: [\n\t1, 0, 0;\n\t0, 1, 0;\n\t0, 0, 1\n]\nt: 0\n0\n0";; #else expected = "R: [\n\t1, 0, 0;\n\t0, 1, 0;\n\t0, 0, 1\n]\nt: [0, 0, 0]'"; From e9deca590ae3809b824e226a23af6bf1a7332058 Mon Sep 17 00:00:00 2001 From: Fan Jiang Date: Wed, 29 Jul 2020 13:54:49 -0400 Subject: [PATCH 304/869] Sync with varun's pr --- python/gtsam_py/python/__init__.py | 24 +++++++++++++++++++----- 1 file changed, 19 insertions(+), 5 deletions(-) diff --git a/python/gtsam_py/python/__init__.py b/python/gtsam_py/python/__init__.py index 9e3e19187..ee00905cf 100644 --- a/python/gtsam_py/python/__init__.py +++ b/python/gtsam_py/python/__init__.py @@ -1,9 +1,23 @@ from .gtsam import * -def Point2(x=0, y=0): - import numpy as np - return np.array([x, y], dtype=float) -def Point3(x=0, y=0, z=0): +def _init(): import numpy as np - return np.array([x, y, z], dtype=float) + + global Point2 # export function + + def Point2(x=0, y=0): + return np.array([x, y], dtype=float) + + global Point3 # export function + + def Point3(x=0, y=0, z=0): + return np.array([x, y, z], dtype=float) + + # for interactive debugging + if __name__ == "__main__": + # we want all definitions accessible + globals().update(locals()) + + +_init() From 851d4a4af4732ef6ebbca0583b592ad393e8006c Mon Sep 17 00:00:00 2001 From: akrishnan86 Date: Thu, 30 Jul 2020 00:12:13 -0700 Subject: [PATCH 305/869] add binary measurement class --- gtsam/sfm/BinaryMeasurement.h | 92 +++++++++++++++++++++++ gtsam/sfm/TranslationFactor.h | 2 + gtsam/sfm/TranslationRecovery.cpp | 28 +++---- gtsam/sfm/TranslationRecovery.h | 13 ++-- gtsam/sfm/tests/testBinaryMeasurement.cpp | 61 +++++++++++++++ 5 files changed, 174 insertions(+), 22 deletions(-) create mode 100644 gtsam/sfm/BinaryMeasurement.h create mode 100644 gtsam/sfm/tests/testBinaryMeasurement.cpp diff --git a/gtsam/sfm/BinaryMeasurement.h b/gtsam/sfm/BinaryMeasurement.h new file mode 100644 index 000000000..41ffa38d6 --- /dev/null +++ b/gtsam/sfm/BinaryMeasurement.h @@ -0,0 +1,92 @@ +/* ---------------------------------------------------------------------------- + + * GTSAM Copyright 2010-2020, Georgia Tech Research Corporation, + * Atlanta, Georgia 30332-0415 + * All Rights Reserved + * Authors: Frank Dellaert, et al. (see THANKS for the full author list) + + * See LICENSE for the license information + + * -------------------------------------------------------------------------- */ + +#pragma once + +/** + * @file BinaryMeasurement.h + * @author Akshay Krishnan + * @date July 2020 + * @brief Binary measurement for representing edges in the epipolar graph + */ + +#include +#include + +namespace gtsam { + +template +class BinaryMeasurement { + // Check that VALUE type is testable + BOOST_CONCEPT_ASSERT((IsTestable)); + +public: + typedef VALUE T; + + // shorthand for a smart pointer to a measurement + typedef typename boost::shared_ptr shared_ptr; + +private: + Key key1_, key2_; /** Keys */ + + VALUE measured_; /** The measurement */ + + SharedNoiseModel noiseModel_; /** Noise model */ + +public: + /** default constructor - only use for serialization */ + BinaryMeasurement() {} + + /** Constructor */ + BinaryMeasurement(Key key1, Key key2, const VALUE& measured, + const SharedNoiseModel& model = nullptr) : + key1_(key1), key2_(key2), measured_(measured), noiseModel_(model) { + } + + virtual ~BinaryMeasurement() {} + + Key key1() const { return key1_; } + + Key key2() const { return key2_; } + + const SharedNoiseModel& noiseModel() const { return noiseModel_; } + + /** implement functions needed for Testable */ + + /** print */ + void print(const std::string& s, const KeyFormatter& keyFormatter = DefaultKeyFormatter) const { + std::cout << s << "BinaryMeasurement(" + << keyFormatter(this->key1()) << "," + << keyFormatter(this->key2()) << ")\n"; + traits::Print(measured_, " measured: "); + this->noiseModel_->print(" noise model: "); + } + + /** equals */ + bool equals(const BetweenMeasurement& expected, double tol=1e-9) const { + const BetweenMeasurement *e = dynamic_cast*> (&expected); + return e != nullptr && key1_ == expected.key1() && + key2_ == expected.key2() + && traits::Equals(this->measured_, e->measured_, tol) && + noiseModel_.equals(expected.noiseModel()); + } + + /** return the measured */ + const VALUE& measured() const { + return measured_; + } + + /** number of variables attached to this measurement */ + std::size_t size() const { + return 2; + } + }; // \class BetweenMeasurement +} \ No newline at end of file diff --git a/gtsam/sfm/TranslationFactor.h b/gtsam/sfm/TranslationFactor.h index d63633d7e..d1f85cf01 100644 --- a/gtsam/sfm/TranslationFactor.h +++ b/gtsam/sfm/TranslationFactor.h @@ -36,6 +36,8 @@ namespace gtsam { * normalized(Tb - Ta) - w_aZb.point3() * * @addtogroup SFM + * + * */ class TranslationFactor : public NoiseModelFactor2 { private: diff --git a/gtsam/sfm/TranslationRecovery.cpp b/gtsam/sfm/TranslationRecovery.cpp index aeeae688f..c3be003ba 100644 --- a/gtsam/sfm/TranslationRecovery.cpp +++ b/gtsam/sfm/TranslationRecovery.cpp @@ -33,15 +33,12 @@ using namespace gtsam; using namespace std; NonlinearFactorGraph TranslationRecovery::buildGraph() const { - auto noiseModel = noiseModel::Isotropic::Sigma(3, 0.01); NonlinearFactorGraph graph; // Add all relative translation edges for (auto edge : relativeTranslations_) { - Key a, b; - tie(a, b) = edge.first; - const Unit3 w_aZb = edge.second; - graph.emplace_shared(a, b, w_aZb, noiseModel); + graph.emplace_shared(edge.key1(), edge.key2(), + edge.measured(), edge.noiseModel()); } return graph; @@ -49,14 +46,12 @@ NonlinearFactorGraph TranslationRecovery::buildGraph() const { void TranslationRecovery::addPrior(const double scale, NonlinearFactorGraph* graph) const { - auto noiseModel = noiseModel::Isotropic::Sigma(3, 0.01); + //TODO(akshay-krishnan): make this an input argument + auto priorNoiseModel = noiseModel::Isotropic::Sigma(3, 0.01); auto edge = relativeTranslations_.begin(); - Key a, b; - tie(a, b) = edge->first; - const Unit3 w_aZb = edge->second; - graph->emplace_shared >(a, Point3(0, 0, 0), noiseModel); - graph->emplace_shared >(b, scale * w_aZb.point3(), - noiseModel); + graph->emplace_shared >(edge->key1(), Point3(0, 0, 0), priorNoiseModel); + graph->emplace_shared >(edge->key2(), scale * edge->measured().point3(), + edge->noiseModel()); } Values TranslationRecovery::initalizeRandomly() const { @@ -71,10 +66,8 @@ Values TranslationRecovery::initalizeRandomly() const { // Loop over measurements and add a random translation for (auto edge : relativeTranslations_) { - Key a, b; - tie(a, b) = edge.first; - insert(a); - insert(b); + insert(edge.key1()); + insert(edge.key2()); } return initial; } @@ -90,6 +83,7 @@ Values TranslationRecovery::run(const double scale) const { TranslationRecovery::TranslationEdges TranslationRecovery::SimulateMeasurements( const Values& poses, const vector& edges) { + auto edgeNoiseModel = noiseModel::Isotropic::Sigma(3, 0.01); TranslationEdges relativeTranslations; for (auto edge : edges) { Key a, b; @@ -97,7 +91,7 @@ TranslationRecovery::TranslationEdges TranslationRecovery::SimulateMeasurements( const Pose3 wTa = poses.at(a), wTb = poses.at(b); const Point3 Ta = wTa.translation(), Tb = wTb.translation(); const Unit3 w_aZb(Tb - Ta); - relativeTranslations[edge] = w_aZb; + relativeTranslations.emplace_back(a, b, w_aZb, edgeNoiseModel); } return relativeTranslations; } diff --git a/gtsam/sfm/TranslationRecovery.h b/gtsam/sfm/TranslationRecovery.h index bb3c3cdb1..1392817b2 100644 --- a/gtsam/sfm/TranslationRecovery.h +++ b/gtsam/sfm/TranslationRecovery.h @@ -19,9 +19,10 @@ #include #include #include +#include -#include #include +#include namespace gtsam { @@ -48,7 +49,7 @@ namespace gtsam { class TranslationRecovery { public: using KeyPair = std::pair; - using TranslationEdges = std::map; + using TranslationEdges = std::vector>; private: TranslationEdges relativeTranslations_; @@ -59,7 +60,8 @@ class TranslationRecovery { * @brief Construct a new Translation Recovery object * * @param relativeTranslations the relative translations, in world coordinate - * frames, indexed in a map by a pair of Pose keys. + * frames, vector of BinaryMeasurements of Unit3, where each key of a measurement + * is a point in 3D. * @param lmParams (optional) gtsam::LavenbergMarquardtParams that can be * used to modify the parameters for the LM optimizer. By default, uses the * default LM parameters. @@ -105,8 +107,9 @@ class TranslationRecovery { * * @param poses SE(3) ground truth poses stored as Values * @param edges pairs (a,b) for which a measurement w_aZb will be generated. - * @return TranslationEdges map from a KeyPair to the simulated Unit3 - * translation direction measurement between the cameras in KeyPair. + * @return TranslationEdges vector of binary measurements where the keys are + * the cameras and the measurement is the simulated Unit3 translation + * direction between the cameras. */ static TranslationEdges SimulateMeasurements( const Values& poses, const std::vector& edges); diff --git a/gtsam/sfm/tests/testBinaryMeasurement.cpp b/gtsam/sfm/tests/testBinaryMeasurement.cpp new file mode 100644 index 000000000..ae3ba23e5 --- /dev/null +++ b/gtsam/sfm/tests/testBinaryMeasurement.cpp @@ -0,0 +1,61 @@ +/* ---------------------------------------------------------------------------- + + * GTSAM Copyright 2010-2020, Georgia Tech Research Corporation, + * Atlanta, Georgia 30332-0415 + * All Rights Reserved + * Authors: Frank Dellaert, et al. (see THANKS for the full author list) + + * See LICENSE for the license information + + * -------------------------------------------------------------------------- */ + +/** + * @file testBinaryMeasurement.cpp + * @brief Unit tests for BinaryMeasurement class + * @author Akshay Krishnan + * @date July 2020 + */ + +#include + +#include +#include +#include + +#include + +using namespace std; +using namespace gtsam; + +// Keys are deliberately *not* in sorted order to test that case. +static const Key kKey1(2), kKey2(1); + +// Create noise models for unit3 and rot3 +static SharedNoiseModel unit3_model(noiseModel::Isotropic::Sigma(2, 0.05)); +static SharedNoiseModel rot3_model(noiseModel::Isotropic::Sigma(3, 0.05)); + +const Unit3 unit3Measured(Vector3(1, 1, 1)); +const Rot3 rot3Measured; + +TEST(BinaryMeasurement, Unit3) { + BinaryMeasurement unit3Measurement(kKey1, kKey2, unit3Measured, + unit3_model); + EXPECT_LONGS_EQUAL(unit3Measurement.key1(), kKey1); + EXPECT_LONGS_EQUAL(unit3Measurement.key2(), kKey2); + EXPECT(unit3Measurement.measured().equals(unit3Measured)); +} + +TEST(BinaryMeasurement, Rot3) { + BinaryMeasurement rot3Measurement(kKey1, kKey2, rot3Measured, + rot3_model); + EXPECT_LONGS_EQUAL(rot3Measurement.key1(), kKey1); + EXPECT_LONGS_EQUAL(rot3Measurement.key2(), kKey2); + EXPECT(rot3Measurement.measured().equals(rot3Measured)); +} + +/* ************************************************************************* */ +int main() { + TestResult tr; + return TestRegistry::runAllTests(tr); +} +/* ************************************************************************* */ From 82849112ec844ebe94bdbc6e7e0725e4ec695d43 Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Thu, 30 Jul 2020 20:52:07 -0500 Subject: [PATCH 306/869] wrap preintegrated function --- gtsam.h | 1 + 1 file changed, 1 insertion(+) diff --git a/gtsam.h b/gtsam.h index 2cd30be42..b9133e49c 100644 --- a/gtsam.h +++ b/gtsam.h @@ -2996,6 +2996,7 @@ class PreintegratedImuMeasurements { void resetIntegrationAndSetBias(const gtsam::imuBias::ConstantBias& biasHat); Matrix preintMeasCov() const; + Vector preintegrated() const; double deltaTij() const; gtsam::Rot3 deltaRij() const; Vector deltaPij() const; From 3d4a8e16a26907df941af55ad9da0c3173be6bf2 Mon Sep 17 00:00:00 2001 From: Fan Jiang Date: Fri, 31 Jul 2020 11:49:31 -0400 Subject: [PATCH 307/869] Moved python files --- python/{gtsam_py/python => gtsam}/__init__.py | 0 .../{gtsam_py/python => gtsam}/examples/DogLegOptimizerExample.py | 0 python/{gtsam_py/python => gtsam}/examples/GPSFactorExample.py | 0 python/{gtsam_py/python => gtsam}/examples/ImuFactorExample.py | 0 .../{gtsam_py/python => gtsam}/examples/ImuFactorISAM2Example.py | 0 python/{gtsam_py/python => gtsam}/examples/OdometryExample.py | 0 .../python => gtsam}/examples/PlanarManipulatorExample.py | 0 python/{gtsam_py/python => gtsam}/examples/PlanarSLAMExample.py | 0 python/{gtsam_py/python => gtsam}/examples/Pose2SLAMExample.py | 0 .../{gtsam_py/python => gtsam}/examples/Pose2SLAMExample_g2o.py | 0 .../{gtsam_py/python => gtsam}/examples/Pose3SLAMExample_g2o.py | 0 .../examples/Pose3SLAMExample_initializePose3Chordal.py | 0 .../{gtsam_py/python => gtsam}/examples/PreintegrationExample.py | 0 python/{gtsam_py/python => gtsam}/examples/README.md | 0 python/{gtsam_py/python => gtsam}/examples/SFMExample.py | 0 python/{gtsam_py/python => gtsam}/examples/SFMdata.py | 0 python/{gtsam_py/python => gtsam}/examples/SimpleRotation.py | 0 python/{gtsam_py/python => gtsam}/examples/VisualISAM2Example.py | 0 python/{gtsam_py/python => gtsam}/examples/VisualISAMExample.py | 0 python/{gtsam_py/python => gtsam}/examples/__init__.py | 0 python/{gtsam_py/python => gtsam}/tests/testScenarioRunner.py | 0 python/{gtsam_py/python => gtsam}/tests/test_Cal3Unified.py | 0 python/{gtsam_py/python => gtsam}/tests/test_FrobeniusFactor.py | 0 .../{gtsam_py/python => gtsam}/tests/test_GaussianFactorGraph.py | 0 python/{gtsam_py/python => gtsam}/tests/test_JacobianFactor.py | 0 python/{gtsam_py/python => gtsam}/tests/test_KalmanFilter.py | 0 python/{gtsam_py/python => gtsam}/tests/test_KarcherMeanFactor.py | 0 .../{gtsam_py/python => gtsam}/tests/test_LocalizationExample.py | 0 .../{gtsam_py/python => gtsam}/tests/test_NonlinearOptimizer.py | 0 python/{gtsam_py/python => gtsam}/tests/test_OdometryExample.py | 0 python/{gtsam_py/python => gtsam}/tests/test_PlanarSLAMExample.py | 0 python/{gtsam_py/python => gtsam}/tests/test_Pose2.py | 0 python/{gtsam_py/python => gtsam}/tests/test_Pose2SLAMExample.py | 0 python/{gtsam_py/python => gtsam}/tests/test_Pose3.py | 0 python/{gtsam_py/python => gtsam}/tests/test_Pose3SLAMExample.py | 0 python/{gtsam_py/python => gtsam}/tests/test_PriorFactor.py | 0 python/{gtsam_py/python => gtsam}/tests/test_SFMExample.py | 0 python/{gtsam_py/python => gtsam}/tests/test_SO4.py | 0 python/{gtsam_py/python => gtsam}/tests/test_SOn.py | 0 python/{gtsam_py/python => gtsam}/tests/test_Scenario.py | 0 python/{gtsam_py/python => gtsam}/tests/test_SimpleCamera.py | 0 python/{gtsam_py/python => gtsam}/tests/test_StereoVOExample.py | 0 python/{gtsam_py/python => gtsam}/tests/test_Triangulation.py | 0 python/{gtsam_py/python => gtsam}/tests/test_Values.py | 0 python/{gtsam_py/python => gtsam}/tests/test_VisualISAMExample.py | 0 python/{gtsam_py/python => gtsam}/tests/test_dataset.py | 0 python/{gtsam_py/python => gtsam}/tests/test_dsf_map.py | 0 python/{gtsam_py/python => gtsam}/tests/test_initialize_pose3.py | 0 python/{gtsam_py/python => gtsam}/tests/test_logging_optimizer.py | 0 python/{gtsam_py/python => gtsam}/utils/__init__.py | 0 python/{gtsam_py/python => gtsam}/utils/circlePose3.py | 0 python/{gtsam_py/python => gtsam}/utils/logging_optimizer.py | 0 python/{gtsam_py/python => gtsam}/utils/plot.py | 0 python/{gtsam_py/python => gtsam}/utils/test_case.py | 0 python/{gtsam_py/python => gtsam}/utils/visual_data_generator.py | 0 python/{gtsam_py/python => gtsam}/utils/visual_isam.py | 0 python/{gtsam_unstable_py/python => gtsam_unstable}/__init__.py | 0 .../python => gtsam_unstable}/examples/FixedLagSmootherExample.py | 0 .../python => gtsam_unstable}/examples/TimeOfArrivalExample.py | 0 .../python => gtsam_unstable}/examples/__init__.py | 0 .../python => gtsam_unstable}/tests/__init__.py | 0 .../tests/test_FixedLagSmootherExample.py | 0 62 files changed, 0 insertions(+), 0 deletions(-) rename python/{gtsam_py/python => gtsam}/__init__.py (100%) rename python/{gtsam_py/python => gtsam}/examples/DogLegOptimizerExample.py (100%) rename python/{gtsam_py/python => gtsam}/examples/GPSFactorExample.py (100%) rename python/{gtsam_py/python => gtsam}/examples/ImuFactorExample.py (100%) rename python/{gtsam_py/python => gtsam}/examples/ImuFactorISAM2Example.py (100%) rename python/{gtsam_py/python => gtsam}/examples/OdometryExample.py (100%) rename python/{gtsam_py/python => gtsam}/examples/PlanarManipulatorExample.py (100%) rename python/{gtsam_py/python => gtsam}/examples/PlanarSLAMExample.py (100%) rename python/{gtsam_py/python => gtsam}/examples/Pose2SLAMExample.py (100%) rename python/{gtsam_py/python => gtsam}/examples/Pose2SLAMExample_g2o.py (100%) rename python/{gtsam_py/python => gtsam}/examples/Pose3SLAMExample_g2o.py (100%) rename python/{gtsam_py/python => gtsam}/examples/Pose3SLAMExample_initializePose3Chordal.py (100%) rename python/{gtsam_py/python => gtsam}/examples/PreintegrationExample.py (100%) rename python/{gtsam_py/python => gtsam}/examples/README.md (100%) rename python/{gtsam_py/python => gtsam}/examples/SFMExample.py (100%) rename python/{gtsam_py/python => gtsam}/examples/SFMdata.py (100%) rename python/{gtsam_py/python => gtsam}/examples/SimpleRotation.py (100%) rename python/{gtsam_py/python => gtsam}/examples/VisualISAM2Example.py (100%) rename python/{gtsam_py/python => gtsam}/examples/VisualISAMExample.py (100%) rename python/{gtsam_py/python => gtsam}/examples/__init__.py (100%) rename python/{gtsam_py/python => gtsam}/tests/testScenarioRunner.py (100%) rename python/{gtsam_py/python => gtsam}/tests/test_Cal3Unified.py (100%) rename python/{gtsam_py/python => gtsam}/tests/test_FrobeniusFactor.py (100%) rename python/{gtsam_py/python => gtsam}/tests/test_GaussianFactorGraph.py (100%) rename python/{gtsam_py/python => gtsam}/tests/test_JacobianFactor.py (100%) rename python/{gtsam_py/python => gtsam}/tests/test_KalmanFilter.py (100%) rename python/{gtsam_py/python => gtsam}/tests/test_KarcherMeanFactor.py (100%) rename python/{gtsam_py/python => gtsam}/tests/test_LocalizationExample.py (100%) rename python/{gtsam_py/python => gtsam}/tests/test_NonlinearOptimizer.py (100%) rename python/{gtsam_py/python => gtsam}/tests/test_OdometryExample.py (100%) rename python/{gtsam_py/python => gtsam}/tests/test_PlanarSLAMExample.py (100%) rename python/{gtsam_py/python => gtsam}/tests/test_Pose2.py (100%) rename python/{gtsam_py/python => gtsam}/tests/test_Pose2SLAMExample.py (100%) rename python/{gtsam_py/python => gtsam}/tests/test_Pose3.py (100%) rename python/{gtsam_py/python => gtsam}/tests/test_Pose3SLAMExample.py (100%) rename python/{gtsam_py/python => gtsam}/tests/test_PriorFactor.py (100%) rename python/{gtsam_py/python => gtsam}/tests/test_SFMExample.py (100%) rename python/{gtsam_py/python => gtsam}/tests/test_SO4.py (100%) rename python/{gtsam_py/python => gtsam}/tests/test_SOn.py (100%) rename python/{gtsam_py/python => gtsam}/tests/test_Scenario.py (100%) rename python/{gtsam_py/python => gtsam}/tests/test_SimpleCamera.py (100%) rename python/{gtsam_py/python => gtsam}/tests/test_StereoVOExample.py (100%) rename python/{gtsam_py/python => gtsam}/tests/test_Triangulation.py (100%) rename python/{gtsam_py/python => gtsam}/tests/test_Values.py (100%) rename python/{gtsam_py/python => gtsam}/tests/test_VisualISAMExample.py (100%) rename python/{gtsam_py/python => gtsam}/tests/test_dataset.py (100%) rename python/{gtsam_py/python => gtsam}/tests/test_dsf_map.py (100%) rename python/{gtsam_py/python => gtsam}/tests/test_initialize_pose3.py (100%) rename python/{gtsam_py/python => gtsam}/tests/test_logging_optimizer.py (100%) rename python/{gtsam_py/python => gtsam}/utils/__init__.py (100%) rename python/{gtsam_py/python => gtsam}/utils/circlePose3.py (100%) rename python/{gtsam_py/python => gtsam}/utils/logging_optimizer.py (100%) rename python/{gtsam_py/python => gtsam}/utils/plot.py (100%) rename python/{gtsam_py/python => gtsam}/utils/test_case.py (100%) rename python/{gtsam_py/python => gtsam}/utils/visual_data_generator.py (100%) rename python/{gtsam_py/python => gtsam}/utils/visual_isam.py (100%) rename python/{gtsam_unstable_py/python => gtsam_unstable}/__init__.py (100%) rename python/{gtsam_unstable_py/python => gtsam_unstable}/examples/FixedLagSmootherExample.py (100%) rename python/{gtsam_unstable_py/python => gtsam_unstable}/examples/TimeOfArrivalExample.py (100%) rename python/{gtsam_unstable_py/python => gtsam_unstable}/examples/__init__.py (100%) rename python/{gtsam_unstable_py/python => gtsam_unstable}/tests/__init__.py (100%) rename python/{gtsam_unstable_py/python => gtsam_unstable}/tests/test_FixedLagSmootherExample.py (100%) diff --git a/python/gtsam_py/python/__init__.py b/python/gtsam/__init__.py similarity index 100% rename from python/gtsam_py/python/__init__.py rename to python/gtsam/__init__.py diff --git a/python/gtsam_py/python/examples/DogLegOptimizerExample.py b/python/gtsam/examples/DogLegOptimizerExample.py similarity index 100% rename from python/gtsam_py/python/examples/DogLegOptimizerExample.py rename to python/gtsam/examples/DogLegOptimizerExample.py diff --git a/python/gtsam_py/python/examples/GPSFactorExample.py b/python/gtsam/examples/GPSFactorExample.py similarity index 100% rename from python/gtsam_py/python/examples/GPSFactorExample.py rename to python/gtsam/examples/GPSFactorExample.py diff --git a/python/gtsam_py/python/examples/ImuFactorExample.py b/python/gtsam/examples/ImuFactorExample.py similarity index 100% rename from python/gtsam_py/python/examples/ImuFactorExample.py rename to python/gtsam/examples/ImuFactorExample.py diff --git a/python/gtsam_py/python/examples/ImuFactorISAM2Example.py b/python/gtsam/examples/ImuFactorISAM2Example.py similarity index 100% rename from python/gtsam_py/python/examples/ImuFactorISAM2Example.py rename to python/gtsam/examples/ImuFactorISAM2Example.py diff --git a/python/gtsam_py/python/examples/OdometryExample.py b/python/gtsam/examples/OdometryExample.py similarity index 100% rename from python/gtsam_py/python/examples/OdometryExample.py rename to python/gtsam/examples/OdometryExample.py diff --git a/python/gtsam_py/python/examples/PlanarManipulatorExample.py b/python/gtsam/examples/PlanarManipulatorExample.py similarity index 100% rename from python/gtsam_py/python/examples/PlanarManipulatorExample.py rename to python/gtsam/examples/PlanarManipulatorExample.py diff --git a/python/gtsam_py/python/examples/PlanarSLAMExample.py b/python/gtsam/examples/PlanarSLAMExample.py similarity index 100% rename from python/gtsam_py/python/examples/PlanarSLAMExample.py rename to python/gtsam/examples/PlanarSLAMExample.py diff --git a/python/gtsam_py/python/examples/Pose2SLAMExample.py b/python/gtsam/examples/Pose2SLAMExample.py similarity index 100% rename from python/gtsam_py/python/examples/Pose2SLAMExample.py rename to python/gtsam/examples/Pose2SLAMExample.py diff --git a/python/gtsam_py/python/examples/Pose2SLAMExample_g2o.py b/python/gtsam/examples/Pose2SLAMExample_g2o.py similarity index 100% rename from python/gtsam_py/python/examples/Pose2SLAMExample_g2o.py rename to python/gtsam/examples/Pose2SLAMExample_g2o.py diff --git a/python/gtsam_py/python/examples/Pose3SLAMExample_g2o.py b/python/gtsam/examples/Pose3SLAMExample_g2o.py similarity index 100% rename from python/gtsam_py/python/examples/Pose3SLAMExample_g2o.py rename to python/gtsam/examples/Pose3SLAMExample_g2o.py diff --git a/python/gtsam_py/python/examples/Pose3SLAMExample_initializePose3Chordal.py b/python/gtsam/examples/Pose3SLAMExample_initializePose3Chordal.py similarity index 100% rename from python/gtsam_py/python/examples/Pose3SLAMExample_initializePose3Chordal.py rename to python/gtsam/examples/Pose3SLAMExample_initializePose3Chordal.py diff --git a/python/gtsam_py/python/examples/PreintegrationExample.py b/python/gtsam/examples/PreintegrationExample.py similarity index 100% rename from python/gtsam_py/python/examples/PreintegrationExample.py rename to python/gtsam/examples/PreintegrationExample.py diff --git a/python/gtsam_py/python/examples/README.md b/python/gtsam/examples/README.md similarity index 100% rename from python/gtsam_py/python/examples/README.md rename to python/gtsam/examples/README.md diff --git a/python/gtsam_py/python/examples/SFMExample.py b/python/gtsam/examples/SFMExample.py similarity index 100% rename from python/gtsam_py/python/examples/SFMExample.py rename to python/gtsam/examples/SFMExample.py diff --git a/python/gtsam_py/python/examples/SFMdata.py b/python/gtsam/examples/SFMdata.py similarity index 100% rename from python/gtsam_py/python/examples/SFMdata.py rename to python/gtsam/examples/SFMdata.py diff --git a/python/gtsam_py/python/examples/SimpleRotation.py b/python/gtsam/examples/SimpleRotation.py similarity index 100% rename from python/gtsam_py/python/examples/SimpleRotation.py rename to python/gtsam/examples/SimpleRotation.py diff --git a/python/gtsam_py/python/examples/VisualISAM2Example.py b/python/gtsam/examples/VisualISAM2Example.py similarity index 100% rename from python/gtsam_py/python/examples/VisualISAM2Example.py rename to python/gtsam/examples/VisualISAM2Example.py diff --git a/python/gtsam_py/python/examples/VisualISAMExample.py b/python/gtsam/examples/VisualISAMExample.py similarity index 100% rename from python/gtsam_py/python/examples/VisualISAMExample.py rename to python/gtsam/examples/VisualISAMExample.py diff --git a/python/gtsam_py/python/examples/__init__.py b/python/gtsam/examples/__init__.py similarity index 100% rename from python/gtsam_py/python/examples/__init__.py rename to python/gtsam/examples/__init__.py diff --git a/python/gtsam_py/python/tests/testScenarioRunner.py b/python/gtsam/tests/testScenarioRunner.py similarity index 100% rename from python/gtsam_py/python/tests/testScenarioRunner.py rename to python/gtsam/tests/testScenarioRunner.py diff --git a/python/gtsam_py/python/tests/test_Cal3Unified.py b/python/gtsam/tests/test_Cal3Unified.py similarity index 100% rename from python/gtsam_py/python/tests/test_Cal3Unified.py rename to python/gtsam/tests/test_Cal3Unified.py diff --git a/python/gtsam_py/python/tests/test_FrobeniusFactor.py b/python/gtsam/tests/test_FrobeniusFactor.py similarity index 100% rename from python/gtsam_py/python/tests/test_FrobeniusFactor.py rename to python/gtsam/tests/test_FrobeniusFactor.py diff --git a/python/gtsam_py/python/tests/test_GaussianFactorGraph.py b/python/gtsam/tests/test_GaussianFactorGraph.py similarity index 100% rename from python/gtsam_py/python/tests/test_GaussianFactorGraph.py rename to python/gtsam/tests/test_GaussianFactorGraph.py diff --git a/python/gtsam_py/python/tests/test_JacobianFactor.py b/python/gtsam/tests/test_JacobianFactor.py similarity index 100% rename from python/gtsam_py/python/tests/test_JacobianFactor.py rename to python/gtsam/tests/test_JacobianFactor.py diff --git a/python/gtsam_py/python/tests/test_KalmanFilter.py b/python/gtsam/tests/test_KalmanFilter.py similarity index 100% rename from python/gtsam_py/python/tests/test_KalmanFilter.py rename to python/gtsam/tests/test_KalmanFilter.py diff --git a/python/gtsam_py/python/tests/test_KarcherMeanFactor.py b/python/gtsam/tests/test_KarcherMeanFactor.py similarity index 100% rename from python/gtsam_py/python/tests/test_KarcherMeanFactor.py rename to python/gtsam/tests/test_KarcherMeanFactor.py diff --git a/python/gtsam_py/python/tests/test_LocalizationExample.py b/python/gtsam/tests/test_LocalizationExample.py similarity index 100% rename from python/gtsam_py/python/tests/test_LocalizationExample.py rename to python/gtsam/tests/test_LocalizationExample.py diff --git a/python/gtsam_py/python/tests/test_NonlinearOptimizer.py b/python/gtsam/tests/test_NonlinearOptimizer.py similarity index 100% rename from python/gtsam_py/python/tests/test_NonlinearOptimizer.py rename to python/gtsam/tests/test_NonlinearOptimizer.py diff --git a/python/gtsam_py/python/tests/test_OdometryExample.py b/python/gtsam/tests/test_OdometryExample.py similarity index 100% rename from python/gtsam_py/python/tests/test_OdometryExample.py rename to python/gtsam/tests/test_OdometryExample.py diff --git a/python/gtsam_py/python/tests/test_PlanarSLAMExample.py b/python/gtsam/tests/test_PlanarSLAMExample.py similarity index 100% rename from python/gtsam_py/python/tests/test_PlanarSLAMExample.py rename to python/gtsam/tests/test_PlanarSLAMExample.py diff --git a/python/gtsam_py/python/tests/test_Pose2.py b/python/gtsam/tests/test_Pose2.py similarity index 100% rename from python/gtsam_py/python/tests/test_Pose2.py rename to python/gtsam/tests/test_Pose2.py diff --git a/python/gtsam_py/python/tests/test_Pose2SLAMExample.py b/python/gtsam/tests/test_Pose2SLAMExample.py similarity index 100% rename from python/gtsam_py/python/tests/test_Pose2SLAMExample.py rename to python/gtsam/tests/test_Pose2SLAMExample.py diff --git a/python/gtsam_py/python/tests/test_Pose3.py b/python/gtsam/tests/test_Pose3.py similarity index 100% rename from python/gtsam_py/python/tests/test_Pose3.py rename to python/gtsam/tests/test_Pose3.py diff --git a/python/gtsam_py/python/tests/test_Pose3SLAMExample.py b/python/gtsam/tests/test_Pose3SLAMExample.py similarity index 100% rename from python/gtsam_py/python/tests/test_Pose3SLAMExample.py rename to python/gtsam/tests/test_Pose3SLAMExample.py diff --git a/python/gtsam_py/python/tests/test_PriorFactor.py b/python/gtsam/tests/test_PriorFactor.py similarity index 100% rename from python/gtsam_py/python/tests/test_PriorFactor.py rename to python/gtsam/tests/test_PriorFactor.py diff --git a/python/gtsam_py/python/tests/test_SFMExample.py b/python/gtsam/tests/test_SFMExample.py similarity index 100% rename from python/gtsam_py/python/tests/test_SFMExample.py rename to python/gtsam/tests/test_SFMExample.py diff --git a/python/gtsam_py/python/tests/test_SO4.py b/python/gtsam/tests/test_SO4.py similarity index 100% rename from python/gtsam_py/python/tests/test_SO4.py rename to python/gtsam/tests/test_SO4.py diff --git a/python/gtsam_py/python/tests/test_SOn.py b/python/gtsam/tests/test_SOn.py similarity index 100% rename from python/gtsam_py/python/tests/test_SOn.py rename to python/gtsam/tests/test_SOn.py diff --git a/python/gtsam_py/python/tests/test_Scenario.py b/python/gtsam/tests/test_Scenario.py similarity index 100% rename from python/gtsam_py/python/tests/test_Scenario.py rename to python/gtsam/tests/test_Scenario.py diff --git a/python/gtsam_py/python/tests/test_SimpleCamera.py b/python/gtsam/tests/test_SimpleCamera.py similarity index 100% rename from python/gtsam_py/python/tests/test_SimpleCamera.py rename to python/gtsam/tests/test_SimpleCamera.py diff --git a/python/gtsam_py/python/tests/test_StereoVOExample.py b/python/gtsam/tests/test_StereoVOExample.py similarity index 100% rename from python/gtsam_py/python/tests/test_StereoVOExample.py rename to python/gtsam/tests/test_StereoVOExample.py diff --git a/python/gtsam_py/python/tests/test_Triangulation.py b/python/gtsam/tests/test_Triangulation.py similarity index 100% rename from python/gtsam_py/python/tests/test_Triangulation.py rename to python/gtsam/tests/test_Triangulation.py diff --git a/python/gtsam_py/python/tests/test_Values.py b/python/gtsam/tests/test_Values.py similarity index 100% rename from python/gtsam_py/python/tests/test_Values.py rename to python/gtsam/tests/test_Values.py diff --git a/python/gtsam_py/python/tests/test_VisualISAMExample.py b/python/gtsam/tests/test_VisualISAMExample.py similarity index 100% rename from python/gtsam_py/python/tests/test_VisualISAMExample.py rename to python/gtsam/tests/test_VisualISAMExample.py diff --git a/python/gtsam_py/python/tests/test_dataset.py b/python/gtsam/tests/test_dataset.py similarity index 100% rename from python/gtsam_py/python/tests/test_dataset.py rename to python/gtsam/tests/test_dataset.py diff --git a/python/gtsam_py/python/tests/test_dsf_map.py b/python/gtsam/tests/test_dsf_map.py similarity index 100% rename from python/gtsam_py/python/tests/test_dsf_map.py rename to python/gtsam/tests/test_dsf_map.py diff --git a/python/gtsam_py/python/tests/test_initialize_pose3.py b/python/gtsam/tests/test_initialize_pose3.py similarity index 100% rename from python/gtsam_py/python/tests/test_initialize_pose3.py rename to python/gtsam/tests/test_initialize_pose3.py diff --git a/python/gtsam_py/python/tests/test_logging_optimizer.py b/python/gtsam/tests/test_logging_optimizer.py similarity index 100% rename from python/gtsam_py/python/tests/test_logging_optimizer.py rename to python/gtsam/tests/test_logging_optimizer.py diff --git a/python/gtsam_py/python/utils/__init__.py b/python/gtsam/utils/__init__.py similarity index 100% rename from python/gtsam_py/python/utils/__init__.py rename to python/gtsam/utils/__init__.py diff --git a/python/gtsam_py/python/utils/circlePose3.py b/python/gtsam/utils/circlePose3.py similarity index 100% rename from python/gtsam_py/python/utils/circlePose3.py rename to python/gtsam/utils/circlePose3.py diff --git a/python/gtsam_py/python/utils/logging_optimizer.py b/python/gtsam/utils/logging_optimizer.py similarity index 100% rename from python/gtsam_py/python/utils/logging_optimizer.py rename to python/gtsam/utils/logging_optimizer.py diff --git a/python/gtsam_py/python/utils/plot.py b/python/gtsam/utils/plot.py similarity index 100% rename from python/gtsam_py/python/utils/plot.py rename to python/gtsam/utils/plot.py diff --git a/python/gtsam_py/python/utils/test_case.py b/python/gtsam/utils/test_case.py similarity index 100% rename from python/gtsam_py/python/utils/test_case.py rename to python/gtsam/utils/test_case.py diff --git a/python/gtsam_py/python/utils/visual_data_generator.py b/python/gtsam/utils/visual_data_generator.py similarity index 100% rename from python/gtsam_py/python/utils/visual_data_generator.py rename to python/gtsam/utils/visual_data_generator.py diff --git a/python/gtsam_py/python/utils/visual_isam.py b/python/gtsam/utils/visual_isam.py similarity index 100% rename from python/gtsam_py/python/utils/visual_isam.py rename to python/gtsam/utils/visual_isam.py diff --git a/python/gtsam_unstable_py/python/__init__.py b/python/gtsam_unstable/__init__.py similarity index 100% rename from python/gtsam_unstable_py/python/__init__.py rename to python/gtsam_unstable/__init__.py diff --git a/python/gtsam_unstable_py/python/examples/FixedLagSmootherExample.py b/python/gtsam_unstable/examples/FixedLagSmootherExample.py similarity index 100% rename from python/gtsam_unstable_py/python/examples/FixedLagSmootherExample.py rename to python/gtsam_unstable/examples/FixedLagSmootherExample.py diff --git a/python/gtsam_unstable_py/python/examples/TimeOfArrivalExample.py b/python/gtsam_unstable/examples/TimeOfArrivalExample.py similarity index 100% rename from python/gtsam_unstable_py/python/examples/TimeOfArrivalExample.py rename to python/gtsam_unstable/examples/TimeOfArrivalExample.py diff --git a/python/gtsam_unstable_py/python/examples/__init__.py b/python/gtsam_unstable/examples/__init__.py similarity index 100% rename from python/gtsam_unstable_py/python/examples/__init__.py rename to python/gtsam_unstable/examples/__init__.py diff --git a/python/gtsam_unstable_py/python/tests/__init__.py b/python/gtsam_unstable/tests/__init__.py similarity index 100% rename from python/gtsam_unstable_py/python/tests/__init__.py rename to python/gtsam_unstable/tests/__init__.py diff --git a/python/gtsam_unstable_py/python/tests/test_FixedLagSmootherExample.py b/python/gtsam_unstable/tests/test_FixedLagSmootherExample.py similarity index 100% rename from python/gtsam_unstable_py/python/tests/test_FixedLagSmootherExample.py rename to python/gtsam_unstable/tests/test_FixedLagSmootherExample.py From fda79057e4e764e3d5028202c1af0571bc2ddaae Mon Sep 17 00:00:00 2001 From: Fan Jiang Date: Fri, 31 Jul 2020 12:16:25 -0400 Subject: [PATCH 308/869] import from is working --- python/gtsam/__init__.py | 1 - python/gtsam/examples/ImuFactorExample.py | 2 +- python/gtsam/examples/ImuFactorISAM2Example.py | 2 +- python/gtsam/examples/PlanarSLAMExample.py | 2 +- python/gtsam/examples/Pose2SLAMExample.py | 1 - python/gtsam/examples/SimpleRotation.py | 2 +- python/gtsam/examples/VisualISAM2Example.py | 2 +- python/gtsam/imuBias.py | 1 + python/gtsam/noiseModel.py | 1 + python/gtsam/symbol_shorthand.py | 1 + python/gtsam/tests/test_GaussianFactorGraph.py | 2 +- python/gtsam/tests/test_SFMExample.py | 2 +- 12 files changed, 10 insertions(+), 9 deletions(-) create mode 100644 python/gtsam/imuBias.py create mode 100644 python/gtsam/noiseModel.py create mode 100644 python/gtsam/symbol_shorthand.py diff --git a/python/gtsam/__init__.py b/python/gtsam/__init__.py index ee00905cf..555808d5a 100644 --- a/python/gtsam/__init__.py +++ b/python/gtsam/__init__.py @@ -1,6 +1,5 @@ from .gtsam import * - def _init(): import numpy as np diff --git a/python/gtsam/examples/ImuFactorExample.py b/python/gtsam/examples/ImuFactorExample.py index f9ff44738..eec7c5ebd 100644 --- a/python/gtsam/examples/ImuFactorExample.py +++ b/python/gtsam/examples/ImuFactorExample.py @@ -18,7 +18,7 @@ import math import gtsam import matplotlib.pyplot as plt import numpy as np -from gtsam.gtsam.symbol_shorthand import B, V, X +from gtsam.symbol_shorthand import B, V, X from gtsam.utils.plot import plot_pose3 from mpl_toolkits.mplot3d import Axes3D diff --git a/python/gtsam/examples/ImuFactorISAM2Example.py b/python/gtsam/examples/ImuFactorISAM2Example.py index 6556eb554..e0999b25b 100644 --- a/python/gtsam/examples/ImuFactorISAM2Example.py +++ b/python/gtsam/examples/ImuFactorISAM2Example.py @@ -16,7 +16,7 @@ from gtsam import (ISAM2, BetweenFactorConstantBias, Cal3_S2, PinholeCameraCal3_S2, Point3, Pose3, PriorFactorConstantBias, PriorFactorPose3, PriorFactorVector, Rot3, Values) -from gtsam.gtsam.symbol_shorthand import B, V, X +from gtsam.symbol_shorthand import B, V, X from gtsam.utils import plot from mpl_toolkits.mplot3d import Axes3D # pylint: disable=W0611 diff --git a/python/gtsam/examples/PlanarSLAMExample.py b/python/gtsam/examples/PlanarSLAMExample.py index ba0529479..5ffdf048d 100644 --- a/python/gtsam/examples/PlanarSLAMExample.py +++ b/python/gtsam/examples/PlanarSLAMExample.py @@ -16,7 +16,7 @@ from __future__ import print_function import numpy as np import gtsam -from gtsam.gtsam.symbol_shorthand import X, L +from gtsam.symbol_shorthand import X, L # Create noise models PRIOR_NOISE = gtsam.noiseModel.Diagonal.Sigmas(np.array([0.3, 0.3, 0.1])) diff --git a/python/gtsam/examples/Pose2SLAMExample.py b/python/gtsam/examples/Pose2SLAMExample.py index 686da4db3..2569f0953 100644 --- a/python/gtsam/examples/Pose2SLAMExample.py +++ b/python/gtsam/examples/Pose2SLAMExample.py @@ -27,7 +27,6 @@ def vector3(x, y, z): """Create 3d double numpy array.""" return np.array([x, y, z], dtype=np.float) - # Create noise models PRIOR_NOISE = gtsam.noiseModel.Diagonal.Sigmas(vector3(0.3, 0.3, 0.1)) ODOMETRY_NOISE = gtsam.noiseModel.Diagonal.Sigmas(vector3(0.2, 0.2, 0.1)) diff --git a/python/gtsam/examples/SimpleRotation.py b/python/gtsam/examples/SimpleRotation.py index de8ab07c3..0fef261f8 100644 --- a/python/gtsam/examples/SimpleRotation.py +++ b/python/gtsam/examples/SimpleRotation.py @@ -12,7 +12,7 @@ a single variable with a single factor. import numpy as np import gtsam -from gtsam.gtsam.symbol_shorthand import X +from gtsam.symbol_shorthand import X def main(): """ diff --git a/python/gtsam/examples/VisualISAM2Example.py b/python/gtsam/examples/VisualISAM2Example.py index e4c0c8b8d..bacf510ec 100644 --- a/python/gtsam/examples/VisualISAM2Example.py +++ b/python/gtsam/examples/VisualISAM2Example.py @@ -17,7 +17,7 @@ import gtsam import gtsam.utils.plot as gtsam_plot import matplotlib.pyplot as plt import numpy as np -from gtsam.gtsam.symbol_shorthand import L, X +from gtsam.symbol_shorthand import L, X from gtsam.examples import SFMdata from mpl_toolkits.mplot3d import Axes3D # pylint: disable=W0611 diff --git a/python/gtsam/imuBias.py b/python/gtsam/imuBias.py new file mode 100644 index 000000000..1cb367b9f --- /dev/null +++ b/python/gtsam/imuBias.py @@ -0,0 +1 @@ +from .gtsam.imuBias import * diff --git a/python/gtsam/noiseModel.py b/python/gtsam/noiseModel.py new file mode 100644 index 000000000..9b1929a8e --- /dev/null +++ b/python/gtsam/noiseModel.py @@ -0,0 +1 @@ +from .gtsam.noiseModel import * \ No newline at end of file diff --git a/python/gtsam/symbol_shorthand.py b/python/gtsam/symbol_shorthand.py new file mode 100644 index 000000000..956ed693a --- /dev/null +++ b/python/gtsam/symbol_shorthand.py @@ -0,0 +1 @@ +from .gtsam.symbol_shorthand import * \ No newline at end of file diff --git a/python/gtsam/tests/test_GaussianFactorGraph.py b/python/gtsam/tests/test_GaussianFactorGraph.py index d520b0fa4..a29b0f263 100644 --- a/python/gtsam/tests/test_GaussianFactorGraph.py +++ b/python/gtsam/tests/test_GaussianFactorGraph.py @@ -16,7 +16,7 @@ import unittest import gtsam import numpy as np -from gtsam.gtsam.symbol_shorthand import X +from gtsam.symbol_shorthand import X from gtsam.utils.test_case import GtsamTestCase diff --git a/python/gtsam/tests/test_SFMExample.py b/python/gtsam/tests/test_SFMExample.py index 295bf0b5e..5e787f5ae 100644 --- a/python/gtsam/tests/test_SFMExample.py +++ b/python/gtsam/tests/test_SFMExample.py @@ -15,7 +15,7 @@ import numpy as np import gtsam import gtsam.utils.visual_data_generator as generator from gtsam import symbol -from gtsam.gtsam.noiseModel import Isotropic, Diagonal +from gtsam.noiseModel import Isotropic, Diagonal from gtsam.utils.test_case import GtsamTestCase From 1cabd2000fcd580625395d02f926e0a216f95f39 Mon Sep 17 00:00:00 2001 From: Fan Jiang Date: Fri, 31 Jul 2020 12:39:04 -0400 Subject: [PATCH 309/869] Sync with new_wrapper develop branch --- python/gtsam/__init__.py | 5 ++++ .../gtsam/examples/ImuFactorISAM2Example.py | 2 +- python/gtsam/examples/README.md | 12 +++++----- python/gtsam/examples/VisualISAMExample.py | 17 +++++--------- python/gtsam/tests/test_SFMExample.py | 20 ++++++++-------- python/gtsam/utils/plot.py | 23 ++++++++----------- 6 files changed, 37 insertions(+), 42 deletions(-) diff --git a/python/gtsam/__init__.py b/python/gtsam/__init__.py index 555808d5a..e6fd8c9c8 100644 --- a/python/gtsam/__init__.py +++ b/python/gtsam/__init__.py @@ -1,16 +1,21 @@ from .gtsam import * + def _init(): + """This function is to add shims for the long-gone Point2 and Point3 types""" + import numpy as np global Point2 # export function def Point2(x=0, y=0): + """Shim for the deleted Point2 type.""" return np.array([x, y], dtype=float) global Point3 # export function def Point3(x=0, y=0, z=0): + """Shim for the deleted Point3 type.""" return np.array([x, y, z], dtype=float) # for interactive debugging diff --git a/python/gtsam/examples/ImuFactorISAM2Example.py b/python/gtsam/examples/ImuFactorISAM2Example.py index e0999b25b..98f6218ea 100644 --- a/python/gtsam/examples/ImuFactorISAM2Example.py +++ b/python/gtsam/examples/ImuFactorISAM2Example.py @@ -1,6 +1,6 @@ """ iSAM2 example with ImuFactor. -Author: Frank Dellaert, Varun Agrawal +Author: Robert Truax (C++), Frank Dellaert, Varun Agrawal """ # pylint: disable=invalid-name, E1101 diff --git a/python/gtsam/examples/README.md b/python/gtsam/examples/README.md index 46b87f079..e998e4dcd 100644 --- a/python/gtsam/examples/README.md +++ b/python/gtsam/examples/README.md @@ -5,8 +5,8 @@ | CameraResectioning | | | CreateSFMExampleData | | | DiscreteBayesNet_FG | none of the required discrete functionality is exposed through Python | -| easyPoint2KalmanFilter | ExtendedKalmanFilter not exposed through Python | -| elaboratePoint2KalmanFilter | GaussianSequentialSolver not exposed through Python | +| easyPoint2KalmanFilter | ExtendedKalmanFilter not yet exposed through Python | +| elaboratePoint2KalmanFilter | GaussianSequentialSolver not yet exposed through Python | | ImuFactorExample2 | X | | ImuFactorsExample | | | ISAM2Example_SmartFactor | | @@ -20,7 +20,7 @@ | Pose2SLAMExample_g2o | X | | Pose2SLAMExample_graph | | | Pose2SLAMExample_graphviz | | -| Pose2SLAMExample_lago | lago not exposed through Python | +| Pose2SLAMExample_lago | lago not yet exposed through Python | | Pose2SLAMStressTest | | | Pose2SLAMwSPCG | | | Pose3SLAMExample_changeKeys | | @@ -42,11 +42,11 @@ | StereoVOExample | | | StereoVOExample_large | | | TimeTBB | | -| UGM_chain | discrete functionality not exposed | -| UGM_small | discrete functionality not exposed | +| UGM_chain | discrete functionality not yet exposed | +| UGM_small | discrete functionality not yet exposed | | VisualISAM2Example | X | | VisualISAMExample | X | Extra Examples (with no C++ equivalent) - PlanarManipulatorExample -- SFMData +- SFMData \ No newline at end of file diff --git a/python/gtsam/examples/VisualISAMExample.py b/python/gtsam/examples/VisualISAMExample.py index 7d562c9b4..f99d3f3e6 100644 --- a/python/gtsam/examples/VisualISAMExample.py +++ b/python/gtsam/examples/VisualISAMExample.py @@ -19,12 +19,7 @@ from gtsam import (Cal3_S2, GenericProjectionFactorCal3_S2, NonlinearFactorGraph, NonlinearISAM, Pose3, PriorFactorPoint3, PriorFactorPose3, Rot3, PinholeCameraCal3_S2, Values, Point3) - - -def symbol(name: str, index: int) -> int: - """ helper for creating a symbol without explicitly casting 'name' from str to int """ - return gtsam.symbol(name, index) - +from gtsam.symbol_shorthand import X, L def main(): """ @@ -60,7 +55,7 @@ def main(): for j, point in enumerate(points): measurement = camera.project(point) factor = GenericProjectionFactorCal3_S2( - measurement, camera_noise, symbol('x', i), symbol('l', j), K) + measurement, camera_noise, X(i), L(j), K) graph.push_back(factor) # Intentionally initialize the variables off from the ground truth @@ -69,7 +64,7 @@ def main(): initial_xi = pose.compose(noise) # Add an initial guess for the current pose - initial_estimate.insert(symbol('x', i), initial_xi) + initial_estimate.insert(X(i), initial_xi) # If this is the first iteration, add a prior on the first pose to set the coordinate frame # and a prior on the first landmark to set the scale @@ -79,12 +74,12 @@ def main(): # Add a prior on pose x0, with 0.3 rad std on roll,pitch,yaw and 0.1m x,y,z pose_noise = gtsam.noiseModel.Diagonal.Sigmas( np.array([0.3, 0.3, 0.3, 0.1, 0.1, 0.1])) - factor = PriorFactorPose3(symbol('x', 0), poses[0], pose_noise) + factor = PriorFactorPose3(X(0), poses[0], pose_noise) graph.push_back(factor) # Add a prior on landmark l0 point_noise = gtsam.noiseModel.Isotropic.Sigma(3, 0.1) - factor = PriorFactorPoint3(symbol('l', 0), points[0], point_noise) + factor = PriorFactorPoint3(L(0), points[0], point_noise) graph.push_back(factor) # Add initial guesses to all observed landmarks @@ -92,7 +87,7 @@ def main(): for j, point in enumerate(points): # Intentionally initialize the variables off from the ground truth initial_lj = points[j] + noise - initial_estimate.insert(symbol('l', j), initial_lj) + initial_estimate.insert(L(j), initial_lj) else: # Update iSAM with the new factors isam.update(graph, initial_estimate) diff --git a/python/gtsam/tests/test_SFMExample.py b/python/gtsam/tests/test_SFMExample.py index 5e787f5ae..47a3cbe3e 100644 --- a/python/gtsam/tests/test_SFMExample.py +++ b/python/gtsam/tests/test_SFMExample.py @@ -17,7 +17,7 @@ import gtsam.utils.visual_data_generator as generator from gtsam import symbol from gtsam.noiseModel import Isotropic, Diagonal from gtsam.utils.test_case import GtsamTestCase - +from gtsam.symbol_shorthand import X, P class TestSFMExample(GtsamTestCase): @@ -41,23 +41,23 @@ class TestSFMExample(GtsamTestCase): j = data.J[i][k] graph.add(gtsam.GenericProjectionFactorCal3_S2( data.Z[i][k], measurementNoise, - symbol('x', i), symbol('p', j), data.K)) + X(i), P(j), data.K)) posePriorNoise = Diagonal.Sigmas(poseNoiseSigmas) - graph.add(gtsam.PriorFactorPose3(symbol('x', 0), + graph.add(gtsam.PriorFactorPose3(X(0), truth.cameras[0].pose(), posePriorNoise)) pointPriorNoise = Isotropic.Sigma(3, pointNoiseSigma) - graph.add(gtsam.PriorFactorPoint3(symbol('p', 0), + graph.add(gtsam.PriorFactorPoint3(P(0), truth.points[0], pointPriorNoise)) # Initial estimate initialEstimate = gtsam.Values() for i in range(len(truth.cameras)): pose_i = truth.cameras[i].pose() - initialEstimate.insert(symbol('x', i), pose_i) + initialEstimate.insert(X(i), pose_i) for j in range(len(truth.points)): point_j = truth.points[j] - initialEstimate.insert(symbol('p', j), point_j) + initialEstimate.insert(P(j), point_j) # Optimization optimizer = gtsam.LevenbergMarquardtOptimizer(graph, initialEstimate) @@ -67,16 +67,16 @@ class TestSFMExample(GtsamTestCase): # Marginalization marginals = gtsam.Marginals(graph, result) - marginals.marginalCovariance(symbol('p', 0)) - marginals.marginalCovariance(symbol('x', 0)) + marginals.marginalCovariance(P(0)) + marginals.marginalCovariance(X(0)) # Check optimized results, should be equal to ground truth for i in range(len(truth.cameras)): - pose_i = result.atPose3(symbol('x', i)) + pose_i = result.atPose3(X(i)) self.gtsamAssertEquals(pose_i, truth.cameras[i].pose(), 1e-5) for j in range(len(truth.points)): - point_j = result.atPoint3(symbol('p', j)) + point_j = result.atPoint3(P(j)) self.gtsamAssertEquals(point_j, truth.points[j], 1e-5) if __name__ == "__main__": diff --git a/python/gtsam/utils/plot.py b/python/gtsam/utils/plot.py index 90f5fe5e7..8b34ad2bf 100644 --- a/python/gtsam/utils/plot.py +++ b/python/gtsam/utils/plot.py @@ -109,7 +109,7 @@ def plot_pose2_on_axes(axes, pose, axis_length=0.1, covariance=None): # get rotation and translation (center) gRp = pose.rotation().matrix() # rotation from pose to global t = pose.translation() - origin = np.array(t) + origin = t # draw the camera axes x_axis = origin + gRp[:, 0] * axis_length @@ -221,9 +221,8 @@ def plot_3d_points(fignum, values, linespec="g*", marginals=None, keys = values.keys() # Plot points and covariance matrices - for i in range(len(keys)): + for key in keys: try: - key = keys[i] point = values.atPoint3(key) if marginals is not None: covariance = marginals.marginalCovariance(key) @@ -321,17 +320,15 @@ def plot_trajectory(fignum, values, scale=1, marginals=None, """ pose3Values = gtsam.utilities.allPose3s(values) keys = gtsam.KeyVector(pose3Values.keys()) - lastIndex = None + lastKey = None - for i in range(len(keys)): - key = keys[i] + for key in keys: try: pose = pose3Values.atPose3(key) except: print("Warning: no Pose3 at key: {0}".format(key)) - if lastIndex is not None: - lastKey = keys[lastIndex] + if lastKey is not None: try: lastPose = pose3Values.atPose3(lastKey) except: @@ -346,11 +343,10 @@ def plot_trajectory(fignum, values, scale=1, marginals=None, fig = plot_pose3(fignum, lastPose, P=covariance, axis_length=scale, axis_labels=axis_labels) - lastIndex = i + lastKey = key # Draw final pose - if lastIndex is not None: - lastKey = keys[lastIndex] + if lastKey is not None: try: lastPose = pose3Values.atPose3(lastKey) if marginals: @@ -390,10 +386,9 @@ def plot_incremental_trajectory(fignum, values, start=0, pose3Values = gtsam.utilities.allPose3s(values) keys = gtsam.KeyVector(pose3Values.keys()) - for i in range(start, len(keys)): - key = keys[i] + for key in keys[start:]: if values.exists(key): - pose_i = values.atPose3(keys[i]) + pose_i = values.atPose3(key) plot_pose3(fignum, pose_i, scale) # Update the plot space to encompass all plotted points From b02cc3f7e3aba926392d29e4b734e05ef2d4c6ee Mon Sep 17 00:00:00 2001 From: Fan Jiang Date: Fri, 31 Jul 2020 12:42:09 -0400 Subject: [PATCH 310/869] remove function import --- python/gtsam/utils/circlePose3.py | 5 +++-- python/gtsam/utils/visual_data_generator.py | 7 ++++--- 2 files changed, 7 insertions(+), 5 deletions(-) diff --git a/python/gtsam/utils/circlePose3.py b/python/gtsam/utils/circlePose3.py index 37e7c5568..e1def9427 100644 --- a/python/gtsam/utils/circlePose3.py +++ b/python/gtsam/utils/circlePose3.py @@ -1,6 +1,7 @@ import gtsam +import math import numpy as np -from math import pi, cos, sin +from math import pi def circlePose3(numPoses=8, radius=1.0, symbolChar='\0'): @@ -25,7 +26,7 @@ def circlePose3(numPoses=8, radius=1.0, symbolChar='\0'): np.array([[0., 1., 0.], [1., 0., 0.], [0., 0., -1.]], order='F')) for i in range(numPoses): key = gtsam.symbol(symbolChar, i) - gti = gtsam.Point3(radius * cos(theta), radius * sin(theta), 0) + gti = gtsam.Point3(radius * math.cos(theta), radius * math.sin(theta), 0) oRi = gtsam.Rot3.Yaw( -theta) # negative yaw goes counterclockwise, with Z down ! gTi = gtsam.Pose3(gRo.compose(oRi), gti) diff --git a/python/gtsam/utils/visual_data_generator.py b/python/gtsam/utils/visual_data_generator.py index 24404ca03..c6e5b8c63 100644 --- a/python/gtsam/utils/visual_data_generator.py +++ b/python/gtsam/utils/visual_data_generator.py @@ -1,7 +1,8 @@ from __future__ import print_function import numpy as np -from math import pi, cos, sin +import math +from math import pi import gtsam from gtsam import PinholeCameraCal3_S2 @@ -85,7 +86,7 @@ def generate_data(options): r = 10 for j in range(len(truth.points)): theta = j * 2 * pi / nrPoints - truth.points[j] = gtsam.Point3(r * cos(theta), r * sin(theta), 0) + truth.points[j] = gtsam.Point3(r * math.cos(theta), r * math.sin(theta), 0) else: # 3D landmarks as vertices of a cube truth.points = [ gtsam.Point3(10, 10, 10), gtsam.Point3(-10, 10, 10), @@ -99,7 +100,7 @@ def generate_data(options): r = 40 for i in range(options.nrCameras): theta = i * 2 * pi / options.nrCameras - t = gtsam.Point3(r * cos(theta), r * sin(theta), height) + t = gtsam.Point3(r * math.cos(theta), r * math.sin(theta), height) truth.cameras[i] = PinholeCameraCal3_S2.Lookat(t, gtsam.Point3(0, 0, 0), gtsam.Point3(0, 0, 1), From c0486d39a0d7ef05e421f787a77008248b2d64ff Mon Sep 17 00:00:00 2001 From: Fan Jiang Date: Fri, 31 Jul 2020 12:47:08 -0400 Subject: [PATCH 311/869] Import classes used more than once --- python/gtsam/utils/visual_data_generator.py | 32 ++++++++++----------- 1 file changed, 16 insertions(+), 16 deletions(-) diff --git a/python/gtsam/utils/visual_data_generator.py b/python/gtsam/utils/visual_data_generator.py index c6e5b8c63..32ccbc8fa 100644 --- a/python/gtsam/utils/visual_data_generator.py +++ b/python/gtsam/utils/visual_data_generator.py @@ -4,7 +4,7 @@ import numpy as np import math from math import pi import gtsam -from gtsam import PinholeCameraCal3_S2 +from gtsam import Point3, Pose3, PinholeCameraCal3_S2, Cal3_S2 class Options: @@ -12,7 +12,7 @@ class Options: Options to generate test scenario """ - def __init__(self, triangle=False, nrCameras=3, K=gtsam.Cal3_S2()): + def __init__(self, triangle=False, nrCameras=3, K=Cal3_S2()): """ Options to generate test scenario @param triangle: generate a triangle scene with 3 points if True, otherwise @@ -29,10 +29,10 @@ class GroundTruth: Object holding generated ground-truth data """ - def __init__(self, K=gtsam.Cal3_S2(), nrCameras=3, nrPoints=4): + def __init__(self, K=Cal3_S2(), nrCameras=3, nrPoints=4): self.K = K - self.cameras = [gtsam.Pose3()] * nrCameras - self.points = [gtsam.Point3(0, 0, 0)] * nrPoints + self.cameras = [Pose3()] * nrCameras + self.points = [Point3(0, 0, 0)] * nrPoints def print_(self, s=""): print(s) @@ -54,11 +54,11 @@ class Data: class NoiseModels: pass - def __init__(self, K=gtsam.Cal3_S2(), nrCameras=3, nrPoints=4): + def __init__(self, K=Cal3_S2(), nrCameras=3, nrPoints=4): self.K = K self.Z = [x[:] for x in [[gtsam.Point2()] * nrPoints] * nrCameras] self.J = [x[:] for x in [[0] * nrPoints] * nrCameras] - self.odometry = [gtsam.Pose3()] * nrCameras + self.odometry = [Pose3()] * nrCameras # Set Noise parameters self.noiseModels = Data.NoiseModels() @@ -75,7 +75,7 @@ class Data: def generate_data(options): """ Generate ground-truth and measurement data. """ - K = gtsam.Cal3_S2(500, 500, 0, 640. / 2., 480. / 2.) + K = Cal3_S2(500, 500, 0, 640. / 2., 480. / 2.) nrPoints = 3 if options.triangle else 8 truth = GroundTruth(K=K, nrCameras=options.nrCameras, nrPoints=nrPoints) @@ -86,13 +86,13 @@ def generate_data(options): r = 10 for j in range(len(truth.points)): theta = j * 2 * pi / nrPoints - truth.points[j] = gtsam.Point3(r * math.cos(theta), r * math.sin(theta), 0) + truth.points[j] = Point3(r * math.cos(theta), r * math.sin(theta), 0) else: # 3D landmarks as vertices of a cube truth.points = [ - gtsam.Point3(10, 10, 10), gtsam.Point3(-10, 10, 10), - gtsam.Point3(-10, -10, 10), gtsam.Point3(10, -10, 10), - gtsam.Point3(10, 10, -10), gtsam.Point3(-10, 10, -10), - gtsam.Point3(-10, -10, -10), gtsam.Point3(10, -10, -10) + Point3(10, 10, 10), Point3(-10, 10, 10), + Point3(-10, -10, 10), Point3(10, -10, 10), + Point3(10, 10, -10), Point3(-10, 10, -10), + Point3(-10, -10, -10), Point3(10, -10, -10) ] # Create camera cameras on a circle around the triangle @@ -100,10 +100,10 @@ def generate_data(options): r = 40 for i in range(options.nrCameras): theta = i * 2 * pi / options.nrCameras - t = gtsam.Point3(r * math.cos(theta), r * math.sin(theta), height) + t = Point3(r * math.cos(theta), r * math.sin(theta), height) truth.cameras[i] = PinholeCameraCal3_S2.Lookat(t, - gtsam.Point3(0, 0, 0), - gtsam.Point3(0, 0, 1), + Point3(0, 0, 0), + Point3(0, 0, 1), truth.K) # Create measurements for j in range(nrPoints): From fa97bc23727c63a42810629b6235e5c1cf250ae8 Mon Sep 17 00:00:00 2001 From: Fan Jiang Date: Fri, 31 Jul 2020 12:48:50 -0400 Subject: [PATCH 312/869] Newline --- python/gtsam/utils/plot.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/python/gtsam/utils/plot.py b/python/gtsam/utils/plot.py index 8b34ad2bf..0267da8c3 100644 --- a/python/gtsam/utils/plot.py +++ b/python/gtsam/utils/plot.py @@ -398,4 +398,4 @@ def plot_incremental_trajectory(fignum, values, start=0, set_axes_equal(fignum) # Pause for a fixed amount of seconds - plt.pause(time_interval) \ No newline at end of file + plt.pause(time_interval) From b6f979fd0dd9398361bcd58a7b30cf060027c3a1 Mon Sep 17 00:00:00 2001 From: Stephanie McCormick Date: Fri, 31 Jul 2020 16:29:11 -0400 Subject: [PATCH 313/869] change from const Params back to non-const Params --- gtsam/navigation/AHRSFactor.h | 2 +- gtsam/navigation/CombinedImuFactor.h | 4 ++-- gtsam/navigation/PreintegrationBase.cpp | 2 +- gtsam/navigation/PreintegrationBase.h | 8 ++++---- gtsam/navigation/TangentPreintegration.cpp | 2 +- gtsam/navigation/TangentPreintegration.h | 2 +- 6 files changed, 10 insertions(+), 10 deletions(-) diff --git a/gtsam/navigation/AHRSFactor.h b/gtsam/navigation/AHRSFactor.h index 1418ab687..8a10e90e1 100644 --- a/gtsam/navigation/AHRSFactor.h +++ b/gtsam/navigation/AHRSFactor.h @@ -75,7 +75,7 @@ class GTSAM_EXPORT PreintegratedAhrsMeasurements : public PreintegratedRotation biasHat_(bias_hat), preintMeasCov_(preint_meas_cov) {} - const Params& p() const { return *boost::static_pointer_cast(p_);} + Params& p() const { return *boost::static_pointer_cast(p_);} const Vector3& biasHat() const { return biasHat_; } const Matrix3& preintMeasCov() const { return preintMeasCov_; } diff --git a/gtsam/navigation/CombinedImuFactor.h b/gtsam/navigation/CombinedImuFactor.h index 42180ca04..e1a38bc91 100644 --- a/gtsam/navigation/CombinedImuFactor.h +++ b/gtsam/navigation/CombinedImuFactor.h @@ -156,7 +156,7 @@ public: * @param biasHat Current estimate of acceleration and rotation rate biases */ PreintegratedCombinedMeasurements( - const boost::shared_ptr& p, + const boost::shared_ptr& p, const imuBias::ConstantBias& biasHat = imuBias::ConstantBias()) : PreintegrationType(p, biasHat) { preintMeasCov_.setZero(); @@ -184,7 +184,7 @@ public: void resetIntegration() override; /// const reference to params, shadows definition in base class - const Params& p() const { return *boost::static_pointer_cast(this->p_); } + Params& p() const { return *boost::static_pointer_cast(this->p_); } /// @} /// @name Access instance variables diff --git a/gtsam/navigation/PreintegrationBase.cpp b/gtsam/navigation/PreintegrationBase.cpp index 1c8fdd760..45560f34d 100644 --- a/gtsam/navigation/PreintegrationBase.cpp +++ b/gtsam/navigation/PreintegrationBase.cpp @@ -28,7 +28,7 @@ using namespace std; namespace gtsam { //------------------------------------------------------------------------------ -PreintegrationBase::PreintegrationBase(const boost::shared_ptr& p, +PreintegrationBase::PreintegrationBase(const boost::shared_ptr& p, const Bias& biasHat) : p_(p), biasHat_(biasHat), deltaTij_(0.0) { } diff --git a/gtsam/navigation/PreintegrationBase.h b/gtsam/navigation/PreintegrationBase.h index e4edbe562..2f02a95b8 100644 --- a/gtsam/navigation/PreintegrationBase.h +++ b/gtsam/navigation/PreintegrationBase.h @@ -44,7 +44,7 @@ class GTSAM_EXPORT PreintegrationBase { typedef PreintegrationParams Params; protected: - boost::shared_ptr p_; + boost::shared_ptr p_; /// Acceleration and gyro bias used for preintegration Bias biasHat_; @@ -67,7 +67,7 @@ class GTSAM_EXPORT PreintegrationBase { * @param p Parameters, typically fixed in a single application * @param bias Current estimate of acceleration and rotation rate biases */ - PreintegrationBase(const boost::shared_ptr& p, + PreintegrationBase(const boost::shared_ptr& p, const imuBias::ConstantBias& biasHat = imuBias::ConstantBias()); /// @} @@ -88,12 +88,12 @@ class GTSAM_EXPORT PreintegrationBase { } /// shared pointer to params - const boost::shared_ptr& params() const { + const boost::shared_ptr& params() const { return p_; } /// const reference to params - const Params& p() const { + Params& p() const { return *p_; } diff --git a/gtsam/navigation/TangentPreintegration.cpp b/gtsam/navigation/TangentPreintegration.cpp index 0d39242b7..56d7aa6d3 100644 --- a/gtsam/navigation/TangentPreintegration.cpp +++ b/gtsam/navigation/TangentPreintegration.cpp @@ -24,7 +24,7 @@ using namespace std; namespace gtsam { //------------------------------------------------------------------------------ -TangentPreintegration::TangentPreintegration(const boost::shared_ptr& p, +TangentPreintegration::TangentPreintegration(const boost::shared_ptr& p, const Bias& biasHat) : PreintegrationBase(p, biasHat) { resetIntegration(); diff --git a/gtsam/navigation/TangentPreintegration.h b/gtsam/navigation/TangentPreintegration.h index 183c7262e..1b51b4e1e 100644 --- a/gtsam/navigation/TangentPreintegration.h +++ b/gtsam/navigation/TangentPreintegration.h @@ -50,7 +50,7 @@ public: * @param p Parameters, typically fixed in a single application * @param bias Current estimate of acceleration and rotation rate biases */ - TangentPreintegration(const boost::shared_ptr& p, + TangentPreintegration(const boost::shared_ptr& p, const imuBias::ConstantBias& biasHat = imuBias::ConstantBias()); /// Virtual destructor From 720a313a9d51135b31ed4433d789b61bf358da20 Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Fri, 31 Jul 2020 19:37:02 -0500 Subject: [PATCH 314/869] remove virtual --- gtsam/base/GenericValue.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/gtsam/base/GenericValue.h b/gtsam/base/GenericValue.h index f4459243e..dc205b47f 100644 --- a/gtsam/base/GenericValue.h +++ b/gtsam/base/GenericValue.h @@ -83,7 +83,7 @@ public: } /// Virtual print function, uses traits - virtual void print(const std::string& str) const override { + void print(const std::string& str) const override { std::cout << "(" << demangle(typeid(T).name()) << ")\n"; traits::Print(value_, str); } From 94f744ecaeafd7e7862c24b3f86df5d2c45d60d0 Mon Sep 17 00:00:00 2001 From: Frank Dellaert Date: Sat, 1 Aug 2020 15:40:50 -0400 Subject: [PATCH 315/869] Allow graph to be queried --- gtsam.h | 1 + gtsam/nonlinear/NonlinearOptimizer.h | 11 +++++++---- 2 files changed, 8 insertions(+), 4 deletions(-) diff --git a/gtsam.h b/gtsam.h index b9133e49c..1b4fc6e34 100644 --- a/gtsam.h +++ b/gtsam.h @@ -2369,6 +2369,7 @@ virtual class NonlinearOptimizer { double error() const; int iterations() const; gtsam::Values values() const; + gtsam::NonlinearFactorGraph graph() const; gtsam::GaussianFactorGraph* iterate() const; }; diff --git a/gtsam/nonlinear/NonlinearOptimizer.h b/gtsam/nonlinear/NonlinearOptimizer.h index 103c231be..9935f44ce 100644 --- a/gtsam/nonlinear/NonlinearOptimizer.h +++ b/gtsam/nonlinear/NonlinearOptimizer.h @@ -105,14 +105,17 @@ public: */ const Values& optimizeSafely(); - /// return error + /// return error in current optimizer state double error() const; - /// return number of iterations + /// return number of iterations in current optimizer state size_t iterations() const; - /// return values - const Values& values() const; + /// return values in current optimizer state + const Values &values() const; + + /// return the graph with nonlinear factors + const NonlinearFactorGraph &graph() const { return graph_; } /// @} From 458a33dadeb79f1f36cb5be9e4bc34a032833156 Mon Sep 17 00:00:00 2001 From: Frank Dellaert Date: Sat, 1 Aug 2020 15:41:19 -0400 Subject: [PATCH 316/869] VectorizedGenerators --- gtsam/geometry/SOn-inl.h | 10 +++------- gtsam/geometry/SOn.h | 31 ++++++++++++++++++++++++++++++- 2 files changed, 33 insertions(+), 8 deletions(-) diff --git a/gtsam/geometry/SOn-inl.h b/gtsam/geometry/SOn-inl.h index 0d7f3e108..9edce8336 100644 --- a/gtsam/geometry/SOn-inl.h +++ b/gtsam/geometry/SOn-inl.h @@ -26,13 +26,13 @@ using namespace std; namespace gtsam { -// Implementation for N>5 just uses dynamic version +// Implementation for N>=5 just uses dynamic version template typename SO::MatrixNN SO::Hat(const TangentVector& xi) { return SOn::Hat(xi); } -// Implementation for N>5 just uses dynamic version +// Implementation for N>=5 just uses dynamic version template typename SO::TangentVector SO::Vee(const MatrixNN& X) { return SOn::Vee(X); @@ -99,12 +99,8 @@ typename SO::VectorN2 SO::vec( if (H) { // Calculate P matrix of vectorized generators // TODO(duy): Should we refactor this as the jacobian of Hat? + Matrix P = VectorizedGenerators(n); const size_t d = dim(); - Matrix P(n2, d); - for (size_t j = 0; j < d; j++) { - const auto X = Hat(Eigen::VectorXd::Unit(d, j)); - P.col(j) = Eigen::Map(X.data(), n2, 1); - } H->resize(n2, d); for (size_t i = 0; i < n; i++) { H->block(i * n, 0, n, d) = matrix_ * P.block(i * n, 0, n, d); diff --git a/gtsam/geometry/SOn.h b/gtsam/geometry/SOn.h index a6392c2f9..004569416 100644 --- a/gtsam/geometry/SOn.h +++ b/gtsam/geometry/SOn.h @@ -290,7 +290,34 @@ class SO : public LieGroup, internal::DimensionSO(N)> { * */ VectorN2 vec(OptionalJacobian H = boost::none) const; - /// @} + + /// Calculate N^2 x dim matrix of vectorized Lie algebra generators for SO(N) + template > + static Matrix VectorizedGenerators() { + constexpr size_t N2 = static_cast(N * N); + Matrix G(N2, dimension); + for (size_t j = 0; j < dimension; j++) { + const auto X = Hat(Vector::Unit(dimension, j)); + G.col(j) = Eigen::Map(X.data(), N2, 1); + } + return G; + } + + /// Calculate n^2 x dim matrix of vectorized Lie algebra generators for SO(n) + template > + static Matrix VectorizedGenerators(size_t n = 0) { + const size_t n2 = n * n, dim = Dimension(n); + Matrix G(n2, dim); + for (size_t j = 0; j < dim; j++) { + const auto X = Hat(Vector::Unit(dim, j)); + G.col(j) = Eigen::Map(X.data(), n2, 1); + } + return G; + } + + /// @{ + /// @name Serialization + /// @{ template friend void save(Archive&, SO&, const unsigned int); @@ -300,6 +327,8 @@ class SO : public LieGroup, internal::DimensionSO(N)> { friend void serialize(Archive&, SO&, const unsigned int); friend class boost::serialization::access; friend class Rot3; // for serialize + + /// @} }; using SOn = SO; From e22c24eff5e43b7769185e0e15b408321486ffdf Mon Sep 17 00:00:00 2001 From: Frank Dellaert Date: Sat, 1 Aug 2020 15:43:21 -0400 Subject: [PATCH 317/869] Removed superfluous size, added doxygen partitions --- gtsam/nonlinear/NonlinearFactor.h | 37 +++++++++++++------ gtsam/slam/BetweenFactor.h | 26 +++++++------ gtsam/slam/EssentialMatrixConstraint.h | 5 --- gtsam_unstable/slam/BetweenFactorEM.h | 5 --- .../slam/TransformBtwRobotsUnaryFactor.h | 5 --- .../slam/TransformBtwRobotsUnaryFactorEM.h | 5 --- 6 files changed, 41 insertions(+), 42 deletions(-) diff --git a/gtsam/nonlinear/NonlinearFactor.h b/gtsam/nonlinear/NonlinearFactor.h index 7bbd51236..f7d821c13 100644 --- a/gtsam/nonlinear/NonlinearFactor.h +++ b/gtsam/nonlinear/NonlinearFactor.h @@ -296,6 +296,8 @@ protected: typedef NoiseModelFactor1 This; public: + /// @name Constructors + /// @{ /** Default constructor for I/O only */ NoiseModelFactor1() {} @@ -309,16 +311,23 @@ public: * @param noiseModel shared pointer to noise model * @param key1 by which to look up X value in Values */ - NoiseModelFactor1(const SharedNoiseModel& noiseModel, Key key1) : - Base(noiseModel, cref_list_of<1>(key1)) {} + NoiseModelFactor1(const SharedNoiseModel &noiseModel, Key key1) + : Base(noiseModel, cref_list_of<1>(key1)) {} - /** Calls the 1-key specific version of evaluateError, which is pure virtual - * so must be implemented in the derived class. + /// @} + /// @name NoiseModelFactor methods + /// @{ + + /** + * Calls the 1-key specific version of evaluateError below, which is pure + * virtual so must be implemented in the derived class. */ - Vector unwhitenedError(const Values& x, boost::optional&> H = boost::none) const override { - if(this->active(x)) { - const X& x1 = x.at(keys_[0]); - if(H) { + Vector unwhitenedError( + const Values &x, + boost::optional &> H = boost::none) const override { + if (this->active(x)) { + const X &x1 = x.at(keys_[0]); + if (H) { return evaluateError(x1, (*H)[0]); } else { return evaluateError(x1); @@ -328,16 +337,22 @@ public: } } + /// @} + /// @name Virtual methods + /// @{ + /** * Override this method to finish implementing a unary factor. * If the optional Matrix reference argument is specified, it should compute * both the function evaluation and its derivative in X. */ - virtual Vector evaluateError(const X& x, boost::optional H = - boost::none) const = 0; + virtual Vector + evaluateError(const X &x, + boost::optional H = boost::none) const = 0; + + /// @} private: - /** Serialization function */ friend class boost::serialization::access; template diff --git a/gtsam/slam/BetweenFactor.h b/gtsam/slam/BetweenFactor.h index 0f5aa6a4c..9afc2f72b 100644 --- a/gtsam/slam/BetweenFactor.h +++ b/gtsam/slam/BetweenFactor.h @@ -67,9 +67,11 @@ namespace gtsam { return boost::static_pointer_cast( gtsam::NonlinearFactor::shared_ptr(new This(*this))); } - /** implement functions needed for Testable */ + /// @} + /// @name Testable + /// @{ - /** print */ + /// print with optional string void print(const std::string& s, const KeyFormatter& keyFormatter = DefaultKeyFormatter) const override { std::cout << s << "BetweenFactor(" << keyFormatter(this->key1()) << "," @@ -78,15 +80,17 @@ namespace gtsam { this->noiseModel_->print(" noise model: "); } - /** equals */ + /// assert equality up to a tolerance bool equals(const NonlinearFactor& expected, double tol=1e-9) const override { const This *e = dynamic_cast (&expected); return e != nullptr && Base::equals(*e, tol) && traits::Equals(this->measured_, e->measured_, tol); } - /** implement functions needed to derive from Factor */ + /// @} + /// @name NoiseModelFactor2 methods + /// @{ - /** vector of errors */ + /// evaluate error, returns vector of errors size of tangent space Vector evaluateError(const T& p1, const T& p2, boost::optional H1 = boost::none, boost::optional H2 = boost::none) const override { T hx = traits::Between(p1, p2, H1, H2); // h(x) @@ -102,15 +106,15 @@ namespace gtsam { #endif } - /** return the measured */ + /// @} + /// @name Standard interface + /// @{ + + /// return the measurement const VALUE& measured() const { return measured_; } - - /** number of variables attached to this factor */ - std::size_t size() const { - return 2; - } + /// @} private: diff --git a/gtsam/slam/EssentialMatrixConstraint.h b/gtsam/slam/EssentialMatrixConstraint.h index 943db7207..d21ead31f 100644 --- a/gtsam/slam/EssentialMatrixConstraint.h +++ b/gtsam/slam/EssentialMatrixConstraint.h @@ -87,11 +87,6 @@ public: return measuredE_; } - /** number of variables attached to this factor */ - std::size_t size() const { - return 2; - } - private: /** Serialization function */ diff --git a/gtsam_unstable/slam/BetweenFactorEM.h b/gtsam_unstable/slam/BetweenFactorEM.h index 4104ba653..d551209c9 100644 --- a/gtsam_unstable/slam/BetweenFactorEM.h +++ b/gtsam_unstable/slam/BetweenFactorEM.h @@ -403,11 +403,6 @@ public: return measured_; } - /** number of variables attached to this factor */ - std::size_t size() const { - return 2; - } - size_t dim() const override { return model_inlier_->R().rows() + model_inlier_->R().cols(); } diff --git a/gtsam_unstable/slam/TransformBtwRobotsUnaryFactor.h b/gtsam_unstable/slam/TransformBtwRobotsUnaryFactor.h index 35080bd42..a17e07f9c 100644 --- a/gtsam_unstable/slam/TransformBtwRobotsUnaryFactor.h +++ b/gtsam_unstable/slam/TransformBtwRobotsUnaryFactor.h @@ -203,11 +203,6 @@ namespace gtsam { /* ************************************************************************* */ - /** number of variables attached to this factor */ - std::size_t size() const { - return 1; - } - size_t dim() const override { return model_->R().rows() + model_->R().cols(); } diff --git a/gtsam_unstable/slam/TransformBtwRobotsUnaryFactorEM.h b/gtsam_unstable/slam/TransformBtwRobotsUnaryFactorEM.h index 2db2844ae..8a56a5d02 100644 --- a/gtsam_unstable/slam/TransformBtwRobotsUnaryFactorEM.h +++ b/gtsam_unstable/slam/TransformBtwRobotsUnaryFactorEM.h @@ -401,11 +401,6 @@ namespace gtsam { /* ************************************************************************* */ - /** number of variables attached to this factor */ - std::size_t size() const { - return 1; - } - size_t dim() const override { return model_inlier_->R().rows() + model_inlier_->R().cols(); } From a4590a2fe34f6f3719afc340a47f8c94f9c7a2b5 Mon Sep 17 00:00:00 2001 From: Frank Dellaert Date: Sat, 1 Aug 2020 15:43:55 -0400 Subject: [PATCH 318/869] Allow to pass in pre-computed generators. Should save some energy. --- gtsam/slam/FrobeniusFactor.cpp | 51 +++++++++++++++-------- gtsam/slam/FrobeniusFactor.h | 74 +++++++++++++++++++++++++++++----- timing/timeFrobeniusFactor.cpp | 19 ++++----- 3 files changed, 107 insertions(+), 37 deletions(-) diff --git a/gtsam/slam/FrobeniusFactor.cpp b/gtsam/slam/FrobeniusFactor.cpp index 904addb03..6981a6a1c 100644 --- a/gtsam/slam/FrobeniusFactor.cpp +++ b/gtsam/slam/FrobeniusFactor.cpp @@ -52,23 +52,40 @@ boost::shared_ptr ConvertPose3NoiseModel( } //****************************************************************************** -FrobeniusWormholeFactor::FrobeniusWormholeFactor(Key j1, Key j2, const Rot3& R12, - size_t p, - const SharedNoiseModel& model) +FrobeniusWormholeFactor::FrobeniusWormholeFactor( + Key j1, Key j2, const Rot3 &R12, size_t p, const SharedNoiseModel &model, + const boost::shared_ptr &G) : NoiseModelFactor2(ConvertPose3NoiseModel(model, p * 3), j1, j2), - M_(R12.matrix()), // 3*3 in all cases - p_(p), // 4 for SO(4) - pp_(p * p), // 16 for SO(4) - dimension_(SOn::Dimension(p)), // 6 for SO(4) - G_(pp_, dimension_) // 16*6 for SO(4) -{ - // Calculate G matrix of vectorized generators - Matrix Z = Matrix::Zero(p, p); - for (size_t j = 0; j < dimension_; j++) { - const auto X = SOn::Hat(Eigen::VectorXd::Unit(dimension_, j)); - G_.col(j) = Eigen::Map(X.data(), pp_, 1); + M_(R12.matrix()), // 3*3 in all cases + p_(p), // 4 for SO(4) + pp_(p * p), // 16 for SO(4) + G_(G) { + if (noiseModel()->dim() != 3 * p_) + throw std::invalid_argument( + "FrobeniusWormholeFactor: model with incorrect dimension."); + if (!G) { + G_ = boost::make_shared(); + *G_ = SOn::VectorizedGenerators(p); // expensive! } - assert(noiseModel()->dim() == 3 * p_); + if (G_->rows() != pp_ || G_->cols() != SOn::Dimension(p)) + throw std::invalid_argument("FrobeniusWormholeFactor: passed in generators " + "of incorrect dimension."); +} + +//****************************************************************************** +void FrobeniusWormholeFactor::print(const std::string &s, const KeyFormatter &keyFormatter) const { + std::cout << s << "FrobeniusWormholeFactor<" << p_ << ">(" << keyFormatter(key1()) << "," + << keyFormatter(key2()) << ")\n"; + traits::Print(M_, " M: "); + noiseModel_->print(" noise model: "); +} + +//****************************************************************************** +bool FrobeniusWormholeFactor::equals(const NonlinearFactor &expected, + double tol) const { + auto e = dynamic_cast(&expected); + return e != nullptr && NoiseModelFactor2::equals(*e, tol) && + p_ == e->p_ && M_ == e->M_; } //****************************************************************************** @@ -98,7 +115,7 @@ Vector FrobeniusWormholeFactor::evaluateError( RPxQ.block(0, 0, p_, dim) << M1 * M_(0, 0), M1 * M_(1, 0), M1 * M_(2, 0); RPxQ.block(p_, 0, p_, dim) << M1 * M_(0, 1), M1 * M_(1, 1), M1 * M_(2, 1); RPxQ.block(p2, 0, p_, dim) << M1 * M_(0, 2), M1 * M_(1, 2), M1 * M_(2, 2); - *H1 = -RPxQ * G_; + *H1 = -RPxQ * (*G_); } if (H2) { const size_t p2 = 2 * p_; @@ -106,7 +123,7 @@ Vector FrobeniusWormholeFactor::evaluateError( PxQ.block(0, 0, p_, p_) = M2; PxQ.block(p_, p_, p_, p_) = M2; PxQ.block(p2, p2, p_, p_) = M2; - *H2 = PxQ * G_; + *H2 = PxQ * (*G_); } return fQ2 - hQ1; diff --git a/gtsam/slam/FrobeniusFactor.h b/gtsam/slam/FrobeniusFactor.h index 6b2ef67fc..f254b4b81 100644 --- a/gtsam/slam/FrobeniusFactor.h +++ b/gtsam/slam/FrobeniusFactor.h @@ -92,14 +92,17 @@ class FrobeniusFactor : public NoiseModelFactor2 { * and in fact only SO3 and SO4 really work, as we need SO::AdjointMap. */ template -class FrobeniusBetweenFactor : public NoiseModelFactor2 { +GTSAM_EXPORT class FrobeniusBetweenFactor : public NoiseModelFactor2 { Rot R12_; ///< measured rotation between R1 and R2 Eigen::Matrix R2hat_H_R1_; ///< fixed derivative of R2hat wrpt R1 enum { Dim = Rot::VectorN2::RowsAtCompileTime }; public: - /// Constructor + /// @name Constructor + /// @{ + + /// Construct from two keys and measured rotation FrobeniusBetweenFactor(Key j1, Key j2, const Rot& R12, const SharedNoiseModel& model = nullptr) : NoiseModelFactor2( @@ -107,6 +110,33 @@ class FrobeniusBetweenFactor : public NoiseModelFactor2 { R12_(R12), R2hat_H_R1_(R12.inverse().AdjointMap()) {} + /// @} + /// @name Testable + /// @{ + + /// print with optional string + void + print(const std::string &s, + const KeyFormatter &keyFormatter = DefaultKeyFormatter) const override { + std::cout << s << "FrobeniusBetweenFactor<" << demangle(typeid(Rot).name()) + << ">(" << keyFormatter(this->key1()) << "," + << keyFormatter(this->key2()) << ")\n"; + traits::Print(R12_, " R12: "); + this->noiseModel_->print(" noise model: "); + } + + /// assert equality up to a tolerance + bool equals(const NonlinearFactor &expected, + double tol = 1e-9) const override { + auto e = dynamic_cast(&expected); + return e != nullptr && NoiseModelFactor2::equals(*e, tol) && + traits::Equals(this->R12_, e->R12_, tol); + } + + /// @} + /// @name NoiseModelFactor2 methods + /// @{ + /// Error is Frobenius norm between R1*R12 and R2. Vector evaluateError(const Rot& R1, const Rot& R2, boost::optional H1 = boost::none, @@ -117,6 +147,7 @@ class FrobeniusBetweenFactor : public NoiseModelFactor2 { if (H1) *H1 = -vec_H_R2hat * R2hat_H_R1_; return error; } + /// @} }; /** @@ -125,21 +156,46 @@ class FrobeniusBetweenFactor : public NoiseModelFactor2 { * the SO(p) matrices down to a Stiefel manifold of p*d matrices. * TODO(frank): template on D=2 or 3 */ -class GTSAM_EXPORT FrobeniusWormholeFactor : public NoiseModelFactor2 { - Matrix M_; ///< measured rotation between R1 and R2 - size_t p_, pp_, dimension_; ///< dimensionality constants - Matrix G_; ///< matrix of vectorized generators +class GTSAM_EXPORT FrobeniusWormholeFactor + : public NoiseModelFactor2 { + Matrix M_; ///< measured rotation between R1 and R2 + size_t p_, pp_; ///< dimensionality constants + boost::shared_ptr G_; ///< matrix of vectorized generators + +public: + /// @name Constructor + /// @{ - public: /// Constructor. Note we convert to 3*p-dimensional noise model. - FrobeniusWormholeFactor(Key j1, Key j2, const Rot3& R12, size_t p = 4, - const SharedNoiseModel& model = nullptr); + /// To save memory and mallocs, pass in the vectorized Lie algebra generators: + /// G = boost::make_shared(SOn::VectorizedGenerators(p)); + FrobeniusWormholeFactor(Key j1, Key j2, const Rot3 &R12, size_t p = 4, + const SharedNoiseModel &model = nullptr, + const boost::shared_ptr &G = nullptr); + + /// @} + /// @name Testable + /// @{ + + /// print with optional string + void + print(const std::string &s, + const KeyFormatter &keyFormatter = DefaultKeyFormatter) const override; + + /// assert equality up to a tolerance + bool equals(const NonlinearFactor &expected, + double tol = 1e-9) const override; + + /// @} + /// @name NoiseModelFactor2 methods + /// @{ /// Error is Frobenius norm between Q1*P*R12 and Q2*P, where P=[I_3x3;0] /// projects down from SO(p) to the Stiefel manifold of px3 matrices. Vector evaluateError(const SOn& Q1, const SOn& Q2, boost::optional H1 = boost::none, boost::optional H2 = boost::none) const override; + /// @} }; } // namespace gtsam diff --git a/timing/timeFrobeniusFactor.cpp b/timing/timeFrobeniusFactor.cpp index 8bd754de6..8bdda968f 100644 --- a/timing/timeFrobeniusFactor.cpp +++ b/timing/timeFrobeniusFactor.cpp @@ -13,12 +13,11 @@ * @file timeFrobeniusFactor.cpp * @brief time FrobeniusFactor with BAL file * @author Frank Dellaert - * @date June 6, 2015 + * @date 2019 */ #include #include -#include #include #include #include @@ -51,10 +50,7 @@ int main(int argc, char* argv[]) { if (argc > 1) g2oFile = argv[argc - 1]; else - g2oFile = - "/Users/dellaert/git/2019c-notes-shonanrotationaveraging/matlabCode/" - "datasets/randomTorus3D.g2o"; - // g2oFile = findExampleDataFile("sphere_smallnoise.graph"); + g2oFile = findExampleDataFile("sphere_smallnoise.graph"); } catch (const exception& e) { cerr << e.what() << '\n'; exit(1); @@ -66,15 +62,16 @@ int main(int argc, char* argv[]) { // Build graph NonlinearFactorGraph graph; - // graph.add(NonlinearEquality(0, SO4())); + // graph.add(NonlinearEquality(0, SOn::identity(4))); auto priorModel = noiseModel::Isotropic::Sigma(6, 10000); - graph.add(PriorFactor(0, SO4(), priorModel)); + graph.add(PriorFactor(0, SOn::identity(4), priorModel)); + auto G = boost::make_shared(SOn::VectorizedGenerators(4)); for (const auto& factor : factors) { const auto& keys = factor->keys(); const auto& Tij = factor->measured(); const auto& model = factor->noiseModel(); graph.emplace_shared( - keys[0], keys[1], Rot3(Tij.rotation().matrix()), 4, model); + keys[0], keys[1], Rot3(Tij.rotation().matrix()), 4, model, G); } std::mt19937 rng(42); @@ -95,9 +92,9 @@ int main(int argc, char* argv[]) { for (size_t i = 0; i < 100; i++) { gttic_(optimize); Values initial; - initial.insert(0, SO4()); + initial.insert(0, SOn::identity(4)); for (size_t j = 1; j < poses.size(); j++) { - initial.insert(j, SO4::Random(rng)); + initial.insert(j, SOn::Random(rng, 4)); } LevenbergMarquardtOptimizer lm(graph, initial, params); Values result = lm.optimize(); From 9326bc1ce63e1ae34c3bb3808f16dd443593bf04 Mon Sep 17 00:00:00 2001 From: Frank Dellaert Date: Sun, 2 Aug 2020 16:23:50 -0400 Subject: [PATCH 319/869] Update README.md --- README.md | 2 ++ 1 file changed, 2 insertions(+) diff --git a/README.md b/README.md index 0b3ecb11d..015d65e3d 100644 --- a/README.md +++ b/README.md @@ -1,5 +1,7 @@ # README - Georgia Tech Smoothing and Mapping Library +**As of August 1, develop is officially in "Pre 4.1" mode, and features deprecated in 4.0 were removed. Use the last 4.0.3 release if you need those features. However, most are easily converted and can be tracked down (in 4.0.3) by disabling the cmake flag GTSAM_ALLOW_DEPRECATED_SINCE_V4** + ## What is GTSAM? GTSAM is a C++ library that implements smoothing and From 00a95642993be561421dec2a50add5be53e04d2c Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Sun, 2 Aug 2020 20:55:50 -0500 Subject: [PATCH 320/869] fix warning in FrobeniusWormholeFactor --- gtsam/slam/FrobeniusFactor.cpp | 33 ++++++++++++++++++--------------- 1 file changed, 18 insertions(+), 15 deletions(-) diff --git a/gtsam/slam/FrobeniusFactor.cpp b/gtsam/slam/FrobeniusFactor.cpp index 6981a6a1c..6d73a73d3 100644 --- a/gtsam/slam/FrobeniusFactor.cpp +++ b/gtsam/slam/FrobeniusFactor.cpp @@ -32,7 +32,7 @@ namespace gtsam { //****************************************************************************** boost::shared_ptr ConvertPose3NoiseModel( - const SharedNoiseModel& model, size_t d, bool defaultToUnit) { + const SharedNoiseModel &model, size_t d, bool defaultToUnit) { double sigma = 1.0; if (model != nullptr) { if (model->dim() != 6) { @@ -56,26 +56,29 @@ FrobeniusWormholeFactor::FrobeniusWormholeFactor( Key j1, Key j2, const Rot3 &R12, size_t p, const SharedNoiseModel &model, const boost::shared_ptr &G) : NoiseModelFactor2(ConvertPose3NoiseModel(model, p * 3), j1, j2), - M_(R12.matrix()), // 3*3 in all cases - p_(p), // 4 for SO(4) - pp_(p * p), // 16 for SO(4) + M_(R12.matrix()), // 3*3 in all cases + p_(p), // 4 for SO(4) + pp_(p * p), // 16 for SO(4) G_(G) { if (noiseModel()->dim() != 3 * p_) throw std::invalid_argument( "FrobeniusWormholeFactor: model with incorrect dimension."); if (!G) { G_ = boost::make_shared(); - *G_ = SOn::VectorizedGenerators(p); // expensive! + *G_ = SOn::VectorizedGenerators(p); // expensive! } - if (G_->rows() != pp_ || G_->cols() != SOn::Dimension(p)) - throw std::invalid_argument("FrobeniusWormholeFactor: passed in generators " - "of incorrect dimension."); + if (static_cast(G_->rows()) != pp_ || + static_cast(G_->cols()) != SOn::Dimension(p)) + throw std::invalid_argument( + "FrobeniusWormholeFactor: passed in generators " + "of incorrect dimension."); } //****************************************************************************** -void FrobeniusWormholeFactor::print(const std::string &s, const KeyFormatter &keyFormatter) const { - std::cout << s << "FrobeniusWormholeFactor<" << p_ << ">(" << keyFormatter(key1()) << "," - << keyFormatter(key2()) << ")\n"; +void FrobeniusWormholeFactor::print(const std::string &s, + const KeyFormatter &keyFormatter) const { + std::cout << s << "FrobeniusWormholeFactor<" << p_ << ">(" + << keyFormatter(key1()) << "," << keyFormatter(key2()) << ")\n"; traits::Print(M_, " M: "); noiseModel_->print(" noise model: "); } @@ -90,12 +93,12 @@ bool FrobeniusWormholeFactor::equals(const NonlinearFactor &expected, //****************************************************************************** Vector FrobeniusWormholeFactor::evaluateError( - const SOn& Q1, const SOn& Q2, boost::optional H1, - boost::optional H2) const { + const SOn &Q1, const SOn &Q2, boost::optional H1, + boost::optional H2) const { gttic(FrobeniusWormholeFactorP_evaluateError); - const Matrix& M1 = Q1.matrix(); - const Matrix& M2 = Q2.matrix(); + const Matrix &M1 = Q1.matrix(); + const Matrix &M2 = Q2.matrix(); assert(M1.rows() == p_ && M2.rows() == p_); const size_t dim = 3 * p_; // Stiefel manifold dimension From ae5956bd10edd2d0e1b92f5778f12b4ac6ff0dd7 Mon Sep 17 00:00:00 2001 From: akrishnan86 Date: Wed, 5 Aug 2020 00:18:42 -0700 Subject: [PATCH 321/869] changes with passing unit tests --- gtsam/sfm/BinaryMeasurement.h | 24 +++++++++++++----------- tests/testTranslationRecovery.cpp | 28 +++++++++++++++++----------- 2 files changed, 30 insertions(+), 22 deletions(-) diff --git a/gtsam/sfm/BinaryMeasurement.h b/gtsam/sfm/BinaryMeasurement.h index 41ffa38d6..99f0e6882 100644 --- a/gtsam/sfm/BinaryMeasurement.h +++ b/gtsam/sfm/BinaryMeasurement.h @@ -18,6 +18,13 @@ * @brief Binary measurement for representing edges in the epipolar graph */ +#include + + +#include +#include +#include + #include #include @@ -71,22 +78,17 @@ public: } /** equals */ - bool equals(const BetweenMeasurement& expected, double tol=1e-9) const { - const BetweenMeasurement *e = dynamic_cast*> (&expected); - return e != nullptr && key1_ == expected.key1() && - key2_ == expected.key2() + bool equals(const BinaryMeasurement& expected, double tol=1e-9) const { + const BinaryMeasurement *e = dynamic_cast*> (&expected); + return e != nullptr && key1_ == e->key1_ && + key2_ == e->key2_ && traits::Equals(this->measured_, e->measured_, tol) && - noiseModel_.equals(expected.noiseModel()); + noiseModel_->equals(expected.noiseModel()); } /** return the measured */ - const VALUE& measured() const { + VALUE measured() const { return measured_; } - - /** number of variables attached to this measurement */ - std::size_t size() const { - return 2; - } }; // \class BetweenMeasurement } \ No newline at end of file diff --git a/tests/testTranslationRecovery.cpp b/tests/testTranslationRecovery.cpp index 5a98c3bf5..eb34ba803 100644 --- a/tests/testTranslationRecovery.cpp +++ b/tests/testTranslationRecovery.cpp @@ -49,15 +49,17 @@ TEST(TranslationRecovery, BAL) { poses, {{0, 1}, {0, 2}, {1, 2}}); // Check - const Pose3 wTa = poses.at(0), wTb = poses.at(1), - wTc = poses.at(2); - const Point3 Ta = wTa.translation(), Tb = wTb.translation(), - Tc = wTc.translation(); - const Rot3 aRw = wTa.rotation().inverse(); - const Unit3 w_aZb = relativeTranslations.at({0, 1}); - EXPECT(assert_equal(Unit3(Tb - Ta), w_aZb)); - const Unit3 w_aZc = relativeTranslations.at({0, 2}); - EXPECT(assert_equal(Unit3(Tc - Ta), w_aZc)); + Unit3 w_aZb_stored; // measurement between 0 and 1 stored for next unit test + for(auto& unitTranslation : relativeTranslations) { + const Pose3 wTa = poses.at(unitTranslation.key1()), + wTb = poses.at(unitTranslation.key2()); + const Point3 Ta = wTa.translation(), Tb = wTb.translation(); + const Unit3 w_aZb = unitTranslation.measured(); + EXPECT(assert_equal(Unit3(Tb - Ta), w_aZb)); + if(unitTranslation.key1() == 0 && unitTranslation.key2() == 1) { + w_aZb_stored = unitTranslation.measured(); + } + } TranslationRecovery algorithm(relativeTranslations); const auto graph = algorithm.buildGraph(); @@ -69,10 +71,14 @@ TEST(TranslationRecovery, BAL) { // Check result for first two translations, determined by prior EXPECT(assert_equal(Point3(0, 0, 0), result.at(0))); - EXPECT(assert_equal(Point3(2 * w_aZb.point3()), result.at(1))); + EXPECT(assert_equal(Point3(2 * w_aZb_stored.point3()), result.at(1))); // Check that the third translations is correct - Point3 expected = (Tc - Ta) * (scale / (Tb - Ta).norm()); + Point3 Ta = poses.at(0).translation(); + Point3 Tb = poses.at(1).translation(); + Point3 Tc = poses.at(2).translation(); + Point3 expected = + (Tc - Ta) * (scale / (Tb - Ta).norm()); EXPECT(assert_equal(expected, result.at(2), 1e-4)); // TODO(frank): how to get stats back? From 68671427e67d29ca51e988a32c192a3299057a64 Mon Sep 17 00:00:00 2001 From: mawallace Date: Wed, 5 Aug 2020 22:15:10 -0400 Subject: [PATCH 322/869] Remove set_zlabel from plot_pose2 --- cython/gtsam/utils/plot.py | 1 - 1 file changed, 1 deletion(-) diff --git a/cython/gtsam/utils/plot.py b/cython/gtsam/utils/plot.py index 1e976a69e..77031eec4 100644 --- a/cython/gtsam/utils/plot.py +++ b/cython/gtsam/utils/plot.py @@ -155,7 +155,6 @@ def plot_pose2(fignum, pose, axis_length=0.1, covariance=None, axes.set_xlabel(axis_labels[0]) axes.set_ylabel(axis_labels[1]) - axes.set_zlabel(axis_labels[2]) return fig From 667fb9a4b956f04baf619126a4e33d4a4869f207 Mon Sep 17 00:00:00 2001 From: akrishnan86 Date: Thu, 6 Aug 2020 06:28:34 -0700 Subject: [PATCH 323/869] binary measurement wrap --- gtsam.h | 44 +++++++++++++++++++++++++++++++---- gtsam/sfm/BinaryMeasurement.h | 3 +++ 2 files changed, 43 insertions(+), 4 deletions(-) diff --git a/gtsam.h b/gtsam.h index 2cd30be42..80fbddec7 100644 --- a/gtsam.h +++ b/gtsam.h @@ -2568,10 +2568,12 @@ virtual class BetweenFactor : gtsam::NoiseModelFactor { void serialize() const; }; - - #include -template +template virtual class NonlinearEquality : gtsam::NoiseModelFactor { // Constructor - forces exact evaluation NonlinearEquality(size_t j, const T& feasible); @@ -2582,7 +2584,6 @@ virtual class NonlinearEquality : gtsam::NoiseModelFactor { void serialize() const; }; - #include template virtual class RangeFactor : gtsam::NoiseModelFactor { @@ -2880,6 +2881,41 @@ virtual class FrobeniusWormholeFactor : gtsam::NoiseModelFactor { Vector evaluateError(const gtsam::SOn& Q1, const gtsam::SOn& Q2); }; +#include +template +class BinaryMeasurement { + BinaryMeasurement(size_t key1, size_t key2, const T& measured, + const gtsam::noiseModel::Base* model); + size_t key1() const; + size_t key2() const; + T measured() const; +}; + +typedef gtsam::BinaryMeasurement BinaryMeasurementUnit3; +typedef gtsam::BinaryMeasurement BinaryMeasurementRot3; + +// std::vector::shared_ptr> +class BinaryMeasurementUnit3s +{ + BinaryMeasurementUnit3s(); + size_t size() const; + gtsam::BinaryMeasurementUnit3* at(size_t i) const; + void push_back(const gtsam::BinaryMeasurementUnit3* measurement); +}; + +// std::vector::shared_ptr> +class BinaryMeasurementRot3s +{ + BinaryMeasurementRot3s(); + size_t size() const; + gtsam::BinaryMeasurementRot3* at(size_t i) const; + void push_back(const gtsam::BinaryMeasurementRot3* measurement); +}; + +#include +class TranslationRecovery { + TranslationRecovery() +} //************************************************************************* // Navigation //************************************************************************* diff --git a/gtsam/sfm/BinaryMeasurement.h b/gtsam/sfm/BinaryMeasurement.h index 99f0e6882..c5bb9c625 100644 --- a/gtsam/sfm/BinaryMeasurement.h +++ b/gtsam/sfm/BinaryMeasurement.h @@ -91,4 +91,7 @@ public: return measured_; } }; // \class BetweenMeasurement + + using BinaryMeasurementUnit3s = std::vector::shared_ptr>; + using BinaryMeasurementRot3s = std::vector::shared_ptr>; } \ No newline at end of file From ccdd1471ed148aa0df051c59b4a9f043ce7aa459 Mon Sep 17 00:00:00 2001 From: ss Date: Thu, 6 Aug 2020 14:26:22 -0400 Subject: [PATCH 324/869] Fix pose2 align bug. --- gtsam/geometry/Pose2.cpp | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/gtsam/geometry/Pose2.cpp b/gtsam/geometry/Pose2.cpp index 9c41a76c8..71df0f753 100644 --- a/gtsam/geometry/Pose2.cpp +++ b/gtsam/geometry/Pose2.cpp @@ -322,10 +322,10 @@ boost::optional align(const vector& pairs) { // calculate cos and sin double c=0,s=0; for(const Point2Pair& pair: pairs) { - Point2 dq = pair.first - cp; - Point2 dp = pair.second - cq; - c += dp.x() * dq.x() + dp.y() * dq.y(); - s += dp.y() * dq.x() - dp.x() * dq.y(); // this works but is negative from formula above !! :-( + Point2 dp = pair.first - cp; + Point2 dq = pair.second - cq; + c += dp.x() * dq.x() + dp.y() * dq.y(); + s += -dp.y() * dq.x() + dp.x() * dq.y(); } // calculate angle and translation From 87499699776e6cea7e9a08b02ac78ea1a93e0d9c Mon Sep 17 00:00:00 2001 From: Sam Bateman Date: Thu, 6 Aug 2020 16:59:57 -0700 Subject: [PATCH 325/869] added mutex to BayesTreeCliqueBase for access to cached variable and added copy/copy assignment constructors to allow for full previous functionality while adding thread safety to marginalCovariance. --- gtsam/inference/BayesTreeCliqueBase-inst.h | 4 +++ gtsam/inference/BayesTreeCliqueBase.h | 30 +++++++++++++++++++--- 2 files changed, 31 insertions(+), 3 deletions(-) diff --git a/gtsam/inference/BayesTreeCliqueBase-inst.h b/gtsam/inference/BayesTreeCliqueBase-inst.h index a02fe274e..df775557c 100644 --- a/gtsam/inference/BayesTreeCliqueBase-inst.h +++ b/gtsam/inference/BayesTreeCliqueBase-inst.h @@ -91,6 +91,7 @@ namespace gtsam { template size_t BayesTreeCliqueBase::numCachedSeparatorMarginals() const { + std::lock_guard marginalLock(cachedSeparatorMarginalMutex_); if (!cachedSeparatorMarginal_) return 0; @@ -144,6 +145,7 @@ namespace gtsam { typename BayesTreeCliqueBase::FactorGraphType BayesTreeCliqueBase::separatorMarginal( Eliminate function) const { + std::lock_guard marginalLock(cachedSeparatorMarginalMutex_); gttic(BayesTreeCliqueBase_separatorMarginal); // Check if the Separator marginal was already calculated if (!cachedSeparatorMarginal_) { @@ -206,6 +208,8 @@ namespace gtsam { // When a shortcut is requested, all of the shortcuts between it and the // root are also generated. So, if this clique's cached shortcut is set, // recursively call over all child cliques. Otherwise, it is unnecessary. + + std::lock_guard marginalLock(cachedSeparatorMarginalMutex_); if (cachedSeparatorMarginal_) { for(derived_ptr& child: children) { child->deleteCachedShortcuts(); diff --git a/gtsam/inference/BayesTreeCliqueBase.h b/gtsam/inference/BayesTreeCliqueBase.h index 7aca84635..be71801b8 100644 --- a/gtsam/inference/BayesTreeCliqueBase.h +++ b/gtsam/inference/BayesTreeCliqueBase.h @@ -24,6 +24,7 @@ #include #include +#include namespace gtsam { @@ -75,10 +76,28 @@ namespace gtsam { /** Construct from a conditional, leaving parent and child pointers uninitialized */ BayesTreeCliqueBase(const sharedConditional& conditional) : conditional_(conditional), problemSize_(1) {} + /** Shallow copy constructor */ + BayesTreeCliqueBase(const BayesTreeCliqueBase& c) : conditional_(c.conditional_), parent_(c.parent_), children(c.children), problemSize_(c.problemSize_), is_root(c.is_root) {} + + /** Shallow copy assignment constructor */ + BayesTreeCliqueBase& operator=(const BayesTreeCliqueBase& c) { + conditional_ = c.conditional_; + parent_ = c.parent_; + children = c.children; + problemSize_ = c.problemSize_; + is_root = c.is_root; + return *this; + } + /// @} - /// This stores the Cached separator margnal P(S) + /// This stores the Cached separator marginal P(S) mutable boost::optional cachedSeparatorMarginal_; + /// This protects Cached seperator marginal P(S) from concurent read/writes + /// as many the functions which access it are const (hence the mutable) + /// leading to the false impression that these const functions are thread-safe + /// which is not true due to these mutable values. This is fixed by applying this mutex. + mutable std::mutex cachedSeparatorMarginalMutex_; public: sharedConditional conditional_; @@ -144,7 +163,9 @@ namespace gtsam { void deleteCachedShortcuts(); const boost::optional& cachedSeparatorMarginal() const { - return cachedSeparatorMarginal_; } + std::lock_guard marginalLock(cachedSeparatorMarginalMutex_); + return cachedSeparatorMarginal_; + } friend class BayesTree; @@ -159,7 +180,10 @@ namespace gtsam { KeyVector shortcut_indices(const derived_ptr& B, const FactorGraphType& p_Cp_B) const; /** Non-recursive delete cached shortcuts and marginals - internal only. */ - void deleteCachedShortcutsNonRecursive() { cachedSeparatorMarginal_ = boost::none; } + void deleteCachedShortcutsNonRecursive() { + std::lock_guard marginalLock(cachedSeparatorMarginalMutex_); + cachedSeparatorMarginal_ = boost::none; + } private: From 9564c4873b62ce7a4b6e3a467da10f1ad1138b5d Mon Sep 17 00:00:00 2001 From: Sam Bateman Date: Thu, 6 Aug 2020 17:48:21 -0700 Subject: [PATCH 326/869] update spelling/indent --- gtsam/inference/BayesTreeCliqueBase-inst.h | 2 +- gtsam/inference/BayesTreeCliqueBase.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/gtsam/inference/BayesTreeCliqueBase-inst.h b/gtsam/inference/BayesTreeCliqueBase-inst.h index df775557c..dfcc7c318 100644 --- a/gtsam/inference/BayesTreeCliqueBase-inst.h +++ b/gtsam/inference/BayesTreeCliqueBase-inst.h @@ -91,7 +91,7 @@ namespace gtsam { template size_t BayesTreeCliqueBase::numCachedSeparatorMarginals() const { - std::lock_guard marginalLock(cachedSeparatorMarginalMutex_); + std::lock_guard marginalLock(cachedSeparatorMarginalMutex_); if (!cachedSeparatorMarginal_) return 0; diff --git a/gtsam/inference/BayesTreeCliqueBase.h b/gtsam/inference/BayesTreeCliqueBase.h index be71801b8..7b79ccf68 100644 --- a/gtsam/inference/BayesTreeCliqueBase.h +++ b/gtsam/inference/BayesTreeCliqueBase.h @@ -93,7 +93,7 @@ namespace gtsam { /// This stores the Cached separator marginal P(S) mutable boost::optional cachedSeparatorMarginal_; - /// This protects Cached seperator marginal P(S) from concurent read/writes + /// This protects Cached seperator marginal P(S) from concurrent read/writes /// as many the functions which access it are const (hence the mutable) /// leading to the false impression that these const functions are thread-safe /// which is not true due to these mutable values. This is fixed by applying this mutex. From 9579db73ead0e154260e338b0af7a15dab07c999 Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Thu, 6 Aug 2020 20:56:18 -0500 Subject: [PATCH 327/869] Revert "fix warning in FrobeniusWormholeFactor" This reverts commit 00a95642993be561421dec2a50add5be53e04d2c. --- gtsam/slam/FrobeniusFactor.cpp | 33 +++++++++++++++------------------ 1 file changed, 15 insertions(+), 18 deletions(-) diff --git a/gtsam/slam/FrobeniusFactor.cpp b/gtsam/slam/FrobeniusFactor.cpp index 6d73a73d3..6981a6a1c 100644 --- a/gtsam/slam/FrobeniusFactor.cpp +++ b/gtsam/slam/FrobeniusFactor.cpp @@ -32,7 +32,7 @@ namespace gtsam { //****************************************************************************** boost::shared_ptr ConvertPose3NoiseModel( - const SharedNoiseModel &model, size_t d, bool defaultToUnit) { + const SharedNoiseModel& model, size_t d, bool defaultToUnit) { double sigma = 1.0; if (model != nullptr) { if (model->dim() != 6) { @@ -56,29 +56,26 @@ FrobeniusWormholeFactor::FrobeniusWormholeFactor( Key j1, Key j2, const Rot3 &R12, size_t p, const SharedNoiseModel &model, const boost::shared_ptr &G) : NoiseModelFactor2(ConvertPose3NoiseModel(model, p * 3), j1, j2), - M_(R12.matrix()), // 3*3 in all cases - p_(p), // 4 for SO(4) - pp_(p * p), // 16 for SO(4) + M_(R12.matrix()), // 3*3 in all cases + p_(p), // 4 for SO(4) + pp_(p * p), // 16 for SO(4) G_(G) { if (noiseModel()->dim() != 3 * p_) throw std::invalid_argument( "FrobeniusWormholeFactor: model with incorrect dimension."); if (!G) { G_ = boost::make_shared(); - *G_ = SOn::VectorizedGenerators(p); // expensive! + *G_ = SOn::VectorizedGenerators(p); // expensive! } - if (static_cast(G_->rows()) != pp_ || - static_cast(G_->cols()) != SOn::Dimension(p)) - throw std::invalid_argument( - "FrobeniusWormholeFactor: passed in generators " - "of incorrect dimension."); + if (G_->rows() != pp_ || G_->cols() != SOn::Dimension(p)) + throw std::invalid_argument("FrobeniusWormholeFactor: passed in generators " + "of incorrect dimension."); } //****************************************************************************** -void FrobeniusWormholeFactor::print(const std::string &s, - const KeyFormatter &keyFormatter) const { - std::cout << s << "FrobeniusWormholeFactor<" << p_ << ">(" - << keyFormatter(key1()) << "," << keyFormatter(key2()) << ")\n"; +void FrobeniusWormholeFactor::print(const std::string &s, const KeyFormatter &keyFormatter) const { + std::cout << s << "FrobeniusWormholeFactor<" << p_ << ">(" << keyFormatter(key1()) << "," + << keyFormatter(key2()) << ")\n"; traits::Print(M_, " M: "); noiseModel_->print(" noise model: "); } @@ -93,12 +90,12 @@ bool FrobeniusWormholeFactor::equals(const NonlinearFactor &expected, //****************************************************************************** Vector FrobeniusWormholeFactor::evaluateError( - const SOn &Q1, const SOn &Q2, boost::optional H1, - boost::optional H2) const { + const SOn& Q1, const SOn& Q2, boost::optional H1, + boost::optional H2) const { gttic(FrobeniusWormholeFactorP_evaluateError); - const Matrix &M1 = Q1.matrix(); - const Matrix &M2 = Q2.matrix(); + const Matrix& M1 = Q1.matrix(); + const Matrix& M2 = Q2.matrix(); assert(M1.rows() == p_ && M2.rows() == p_); const size_t dim = 3 * p_; // Stiefel manifold dimension From b9ce41ce025f5199f2844a21b800e4346d800206 Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Thu, 6 Aug 2020 20:58:14 -0500 Subject: [PATCH 328/869] fix warning in FrobeniusWormholeFactor --- gtsam/slam/FrobeniusFactor.cpp | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/gtsam/slam/FrobeniusFactor.cpp b/gtsam/slam/FrobeniusFactor.cpp index 6981a6a1c..80aeea947 100644 --- a/gtsam/slam/FrobeniusFactor.cpp +++ b/gtsam/slam/FrobeniusFactor.cpp @@ -67,7 +67,8 @@ FrobeniusWormholeFactor::FrobeniusWormholeFactor( G_ = boost::make_shared(); *G_ = SOn::VectorizedGenerators(p); // expensive! } - if (G_->rows() != pp_ || G_->cols() != SOn::Dimension(p)) + if (static_cast(G_->rows()) != pp_ || + static_cast(G_->cols()) != SOn::Dimension(p)) throw std::invalid_argument("FrobeniusWormholeFactor: passed in generators " "of incorrect dimension."); } From 3ea989772375b0a78c8dd8e9bd68bbc22de38982 Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Fri, 7 Aug 2020 16:11:05 -0500 Subject: [PATCH 329/869] function for consistent width printing of CMake flags --- CMakeLists.txt | 104 +++++++++++++++++++------------------- cmake/GtsamPrinting.cmake | 32 ++++++++---- 2 files changed, 73 insertions(+), 63 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index 61730d45a..d2b9bc75e 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -509,104 +509,104 @@ set(CPACK_DEBIAN_PACKAGE_DEPENDS "libboost-dev (>= 1.43)") #Example: "libc6 (>= # Print configuration variables message(STATUS "===============================================================") message(STATUS "================ Configuration Options ======================") -message(STATUS " CMAKE_CXX_COMPILER_ID type : ${CMAKE_CXX_COMPILER_ID}") -message(STATUS " CMAKE_CXX_COMPILER_VERSION : ${CMAKE_CXX_COMPILER_VERSION}") -message(STATUS " CMake version : ${CMAKE_VERSION}") -message(STATUS " CMake generator : ${CMAKE_GENERATOR}") -message(STATUS " CMake build tool : ${CMAKE_BUILD_TOOL}") +print_config("CMAKE_CXX_COMPILER_ID type" "${CMAKE_CXX_COMPILER_ID}") +print_config("CMAKE_CXX_COMPILER_VERSION" "${CMAKE_CXX_COMPILER_VERSION}") +print_config("CMake version" "${CMAKE_VERSION}") +print_config("CMake generator" "${CMAKE_GENERATOR}") +print_config("CMake build tool" "${CMAKE_BUILD_TOOL}") message(STATUS "Build flags ") -print_config_flag(${GTSAM_BUILD_TESTS} "Build Tests ") -print_config_flag(${GTSAM_BUILD_EXAMPLES_ALWAYS} "Build examples with 'make all' ") -print_config_flag(${GTSAM_BUILD_TIMING_ALWAYS} "Build timing scripts with 'make all'") +print_enabled_config(${GTSAM_BUILD_TESTS} "Build Tests") +print_enabled_config(${GTSAM_BUILD_EXAMPLES_ALWAYS} "Build examples with 'make all'") +print_enabled_config(${GTSAM_BUILD_TIMING_ALWAYS} "Build timing scripts with 'make all'") if (DOXYGEN_FOUND) - print_config_flag(${GTSAM_BUILD_DOCS} "Build Docs ") + print_enabled_config(${GTSAM_BUILD_DOCS} "Build Docs") endif() -print_config_flag(${BUILD_SHARED_LIBS} "Build shared GTSAM libraries ") -print_config_flag(${GTSAM_BUILD_TYPE_POSTFIXES} "Put build type in library name ") +print_enabled_config(${BUILD_SHARED_LIBS} "Build shared GTSAM libraries") +print_enabled_config(${GTSAM_BUILD_TYPE_POSTFIXES} "Put build type in library name") if(GTSAM_UNSTABLE_AVAILABLE) - print_config_flag(${GTSAM_BUILD_UNSTABLE} "Build libgtsam_unstable ") + print_enabled_config(${GTSAM_BUILD_UNSTABLE} "Build libgtsam_unstable") endif() if(NOT MSVC AND NOT XCODE_VERSION) - print_config_flag(${GTSAM_BUILD_WITH_MARCH_NATIVE} "Build for native architecture ") - message(STATUS " Build type : ${CMAKE_BUILD_TYPE}") - message(STATUS " C compilation flags : ${CMAKE_C_FLAGS} ${CMAKE_C_FLAGS_${CMAKE_BUILD_TYPE_UPPER}}") - message(STATUS " C++ compilation flags : ${CMAKE_CXX_FLAGS} ${CMAKE_CXX_FLAGS_${CMAKE_BUILD_TYPE_UPPER}}") + print_enabled_config(${GTSAM_BUILD_WITH_MARCH_NATIVE} "Build for native architecture ") + print_config("Build type" "${CMAKE_BUILD_TYPE}") + print_config("C compilation flags" "${CMAKE_C_FLAGS} ${CMAKE_C_FLAGS_${CMAKE_BUILD_TYPE_UPPER}}") + print_config("C++ compilation flags" "${CMAKE_CXX_FLAGS} ${CMAKE_CXX_FLAGS_${CMAKE_BUILD_TYPE_UPPER}}") endif() print_build_options_for_target(gtsam) -message(STATUS " Use System Eigen : ${GTSAM_USE_SYSTEM_EIGEN} (Using version: ${GTSAM_EIGEN_VERSION})") +print_config("Use System Eigen" "${GTSAM_USE_SYSTEM_EIGEN} (Using version: ${GTSAM_EIGEN_VERSION})") if(GTSAM_USE_TBB) - message(STATUS " Use Intel TBB : Yes") + print_config("Use Intel TBB" "Yes") elseif(TBB_FOUND) - message(STATUS " Use Intel TBB : TBB found but GTSAM_WITH_TBB is disabled") + print_config("Use Intel TBB" "TBB found but GTSAM_WITH_TBB is disabled") else() - message(STATUS " Use Intel TBB : TBB not found") + print_config("Use Intel TBB" "TBB not found") endif() if(GTSAM_USE_EIGEN_MKL) - message(STATUS " Eigen will use MKL : Yes") + print_config("Eigen will use MKL" "Yes") elseif(MKL_FOUND) - message(STATUS " Eigen will use MKL : MKL found but GTSAM_WITH_EIGEN_MKL is disabled") + print_config("Eigen will use MKL" "MKL found but GTSAM_WITH_EIGEN_MKL is disabled") else() - message(STATUS " Eigen will use MKL : MKL not found") + print_config("Eigen will use MKL" "MKL not found") endif() if(GTSAM_USE_EIGEN_MKL_OPENMP) - message(STATUS " Eigen will use MKL and OpenMP : Yes") + print_config("Eigen will use MKL and OpenMP" "Yes") elseif(OPENMP_FOUND AND NOT GTSAM_WITH_EIGEN_MKL) - message(STATUS " Eigen will use MKL and OpenMP : OpenMP found but GTSAM_WITH_EIGEN_MKL is disabled") + print_config("Eigen will use MKL and OpenMP" "OpenMP found but GTSAM_WITH_EIGEN_MKL is disabled") elseif(OPENMP_FOUND AND NOT MKL_FOUND) - message(STATUS " Eigen will use MKL and OpenMP : OpenMP found but MKL not found") + print_config("Eigen will use MKL and OpenMP" "OpenMP found but MKL not found") elseif(OPENMP_FOUND) - message(STATUS " Eigen will use MKL and OpenMP : OpenMP found but GTSAM_WITH_EIGEN_MKL_OPENMP is disabled") + print_config("Eigen will use MKL and OpenMP" "OpenMP found but GTSAM_WITH_EIGEN_MKL_OPENMP is disabled") else() - message(STATUS " Eigen will use MKL and OpenMP : OpenMP not found") + print_config("Eigen will use MKL and OpenMP" "OpenMP not found") endif() -message(STATUS " Default allocator : ${GTSAM_DEFAULT_ALLOCATOR}") +print_config("Default allocator" "${GTSAM_DEFAULT_ALLOCATOR}") if(GTSAM_THROW_CHEIRALITY_EXCEPTION) - message(STATUS " Cheirality exceptions enabled : YES") + print_config("Cheirality exceptions enabled" "YES") else() - message(STATUS " Cheirality exceptions enabled : NO") + print_config("Cheirality exceptions enabled" "NO") endif() if(NOT MSVC AND NOT XCODE_VERSION) if(CCACHE_FOUND AND GTSAM_BUILD_WITH_CCACHE) - message(STATUS " Build with ccache : Yes") + print_config("Build with ccache" "Yes") elseif(CCACHE_FOUND) - message(STATUS " Build with ccache : ccache found but GTSAM_BUILD_WITH_CCACHE is disabled") + print_config("Build with ccache" "ccache found but GTSAM_BUILD_WITH_CCACHE is disabled") else() - message(STATUS " Build with ccache : No") + print_config("Build with ccache" "No") endif() endif() -message(STATUS "Packaging flags ") -message(STATUS " CPack Source Generator : ${CPACK_SOURCE_GENERATOR}") -message(STATUS " CPack Generator : ${CPACK_GENERATOR}") +message(STATUS "Packaging flags") +print_config("CPack Source Generator" "${CPACK_SOURCE_GENERATOR}") +print_config("CPack Generator" "${CPACK_GENERATOR}") message(STATUS "GTSAM flags ") -print_config_flag(${GTSAM_USE_QUATERNIONS} "Quaternions as default Rot3 ") -print_config_flag(${GTSAM_ENABLE_CONSISTENCY_CHECKS} "Runtime consistency checking ") -print_config_flag(${GTSAM_ROT3_EXPMAP} "Rot3 retract is full ExpMap ") -print_config_flag(${GTSAM_POSE3_EXPMAP} "Pose3 retract is full ExpMap ") -print_config_flag(${GTSAM_ALLOW_DEPRECATED_SINCE_V41} "Allow features deprecated in GTSAM 4.1") -print_config_flag(${GTSAM_TYPEDEF_POINTS_TO_VECTORS} "Point3 is typedef to Vector3 ") -print_config_flag(${GTSAM_SUPPORT_NESTED_DISSECTION} "Metis-based Nested Dissection ") -print_config_flag(${GTSAM_TANGENT_PREINTEGRATION} "Use tangent-space preintegration") -print_config_flag(${GTSAM_BUILD_WRAP} "Build Wrap ") +print_enabled_config(${GTSAM_USE_QUATERNIONS} "Quaternions as default Rot3 ") +print_enabled_config(${GTSAM_ENABLE_CONSISTENCY_CHECKS} "Runtime consistency checking ") +print_enabled_config(${GTSAM_ROT3_EXPMAP} "Rot3 retract is full ExpMap ") +print_enabled_config(${GTSAM_POSE3_EXPMAP} "Pose3 retract is full ExpMap ") +print_enabled_config(${GTSAM_ALLOW_DEPRECATED_SINCE_V41} "Allow features deprecated in GTSAM 4.1") +print_enabled_config(${GTSAM_TYPEDEF_POINTS_TO_VECTORS} "Point3 is typedef to Vector3 ") +print_enabled_config(${GTSAM_SUPPORT_NESTED_DISSECTION} "Metis-based Nested Dissection ") +print_enabled_config(${GTSAM_TANGENT_PREINTEGRATION} "Use tangent-space preintegration") +print_enabled_config(${GTSAM_BUILD_WRAP} "Build Wrap ") -message(STATUS "MATLAB toolbox flags ") -print_config_flag(${GTSAM_INSTALL_MATLAB_TOOLBOX} "Install MATLAB toolbox ") +message(STATUS "MATLAB toolbox flags") +print_enabled_config(${GTSAM_INSTALL_MATLAB_TOOLBOX} "Install MATLAB toolbox ") if (${GTSAM_INSTALL_MATLAB_TOOLBOX}) - message(STATUS " MATLAB root : ${MATLAB_ROOT}") - message(STATUS " MEX binary : ${MEX_COMMAND}") + print_config("MATLAB root" "${MATLAB_ROOT}") + print_config("MEX binary" "${MEX_COMMAND}") endif() message(STATUS "Cython toolbox flags ") -print_config_flag(${GTSAM_INSTALL_CYTHON_TOOLBOX} "Install Cython toolbox ") +print_enabled_config(${GTSAM_INSTALL_CYTHON_TOOLBOX} "Install Cython toolbox ") if(GTSAM_INSTALL_CYTHON_TOOLBOX) - message(STATUS " Python version : ${GTSAM_PYTHON_VERSION}") + print_config("Python version" "${GTSAM_PYTHON_VERSION}") endif() message(STATUS "===============================================================") diff --git a/cmake/GtsamPrinting.cmake b/cmake/GtsamPrinting.cmake index e53f9c54f..5757f5ee1 100644 --- a/cmake/GtsamPrinting.cmake +++ b/cmake/GtsamPrinting.cmake @@ -1,14 +1,3 @@ -# print configuration variables -# Usage: -#print_config_flag(${GTSAM_BUILD_TESTS} "Build Tests ") -function(print_config_flag flag msg) - if (flag) - message(STATUS " ${msg}: Enabled") - else () - message(STATUS " ${msg}: Disabled") - endif () -endfunction() - # Based on https://github.com/jimbraun/XCDF/blob/master/cmake/CMakePadString.cmake function(string_pad RESULT_NAME DESIRED_LENGTH VALUE) string(LENGTH "${VALUE}" VALUE_LENGTH) @@ -26,6 +15,27 @@ endfunction() set(GTSAM_PRINT_SUMMARY_PADDING_LENGTH 50 CACHE STRING "Padding of cmake summary report lines after configuring.") mark_as_advanced(GTSAM_PRINT_SUMMARY_PADDING_LENGTH) +# print configuration variables with automatic padding +# Usage: +# print_config(${GTSAM_BUILD_TESTS} "Build Tests") +function(print_config config msg) + string_pad(padded_config ${GTSAM_PRINT_SUMMARY_PADDING_LENGTH} " ${config}") + message(STATUS "${padded_config}: ${msg}") +endfunction() + +# print configuration variable with enabled/disabled value +# Usage: +# print_enabled_config(${GTSAM_BUILD_TESTS} "Build Tests ") +function(print_enabled_config config msg) + string_pad(padded_msg ${GTSAM_PRINT_SUMMARY_PADDING_LENGTH} " ${msg}") + if (config) + message(STATUS "${padded_msg}: Enabled") + else () + message(STATUS "${padded_msg}: Disabled") + endif () +endfunction() + + # Print " var: ${var}" padding with spaces as needed function(print_padded variable_name) string_pad(padded_prop ${GTSAM_PRINT_SUMMARY_PADDING_LENGTH} " ${variable_name}") From 2540285afe0ab2d252fba83ea7afd1ea4a3ad88a Mon Sep 17 00:00:00 2001 From: akrishnan86 Date: Sat, 8 Aug 2020 12:09:30 -0700 Subject: [PATCH 330/869] sfm changes to docs, format, wrapper --- gtsam.h | 22 ----- gtsam/sfm/BinaryMeasurement.h | 97 +++++++++++------------ gtsam/sfm/TranslationRecovery.cpp | 12 +-- gtsam/sfm/TranslationRecovery.h | 10 +-- gtsam/sfm/tests/testBinaryMeasurement.cpp | 13 ++- gtsam/sfm/tests/testTranslationFactor.cpp | 8 +- 6 files changed, 71 insertions(+), 91 deletions(-) diff --git a/gtsam.h b/gtsam.h index 80fbddec7..4cac956b6 100644 --- a/gtsam.h +++ b/gtsam.h @@ -2894,28 +2894,6 @@ class BinaryMeasurement { typedef gtsam::BinaryMeasurement BinaryMeasurementUnit3; typedef gtsam::BinaryMeasurement BinaryMeasurementRot3; -// std::vector::shared_ptr> -class BinaryMeasurementUnit3s -{ - BinaryMeasurementUnit3s(); - size_t size() const; - gtsam::BinaryMeasurementUnit3* at(size_t i) const; - void push_back(const gtsam::BinaryMeasurementUnit3* measurement); -}; - -// std::vector::shared_ptr> -class BinaryMeasurementRot3s -{ - BinaryMeasurementRot3s(); - size_t size() const; - gtsam::BinaryMeasurementRot3* at(size_t i) const; - void push_back(const gtsam::BinaryMeasurementRot3* measurement); -}; - -#include -class TranslationRecovery { - TranslationRecovery() -} //************************************************************************* // Navigation //************************************************************************* diff --git a/gtsam/sfm/BinaryMeasurement.h b/gtsam/sfm/BinaryMeasurement.h index c5bb9c625..9b0874106 100644 --- a/gtsam/sfm/BinaryMeasurement.h +++ b/gtsam/sfm/BinaryMeasurement.h @@ -15,12 +15,15 @@ * @file BinaryMeasurement.h * @author Akshay Krishnan * @date July 2020 - * @brief Binary measurement for representing edges in the epipolar graph + * @brief Binary measurement for representing edges in the epipolar graph. + * A binary measurement is similar to a BetweenFactor, except that it does not contain + * an error function. It is a measurement (along with a noise model) from one key to + * another. Note that the direction is important. A measurement from key1 to key2 is not + * the same as the same measurement from key2 to key1. */ #include - #include #include #include @@ -30,68 +33,60 @@ namespace gtsam { -template +template class BinaryMeasurement { - // Check that VALUE type is testable - BOOST_CONCEPT_ASSERT((IsTestable)); + // Check that VALUE type is testable + BOOST_CONCEPT_ASSERT((IsTestable)); -public: - typedef VALUE T; + public: + typedef VALUE T; - // shorthand for a smart pointer to a measurement - typedef typename boost::shared_ptr shared_ptr; + // shorthand for a smart pointer to a measurement + typedef typename boost::shared_ptr shared_ptr; -private: - Key key1_, key2_; /** Keys */ + private: + Key key1_, key2_; /** Keys */ - VALUE measured_; /** The measurement */ + VALUE measured_; /** The measurement */ - SharedNoiseModel noiseModel_; /** Noise model */ + SharedNoiseModel noiseModel_; /** Noise model */ -public: - /** default constructor - only use for serialization */ - BinaryMeasurement() {} - - /** Constructor */ - BinaryMeasurement(Key key1, Key key2, const VALUE& measured, - const SharedNoiseModel& model = nullptr) : + public: + /** Constructor */ + BinaryMeasurement(Key key1, Key key2, const VALUE &measured, + const SharedNoiseModel &model = nullptr) : key1_(key1), key2_(key2), measured_(measured), noiseModel_(model) { - } + } - virtual ~BinaryMeasurement() {} + Key key1() const { return key1_; } - Key key1() const { return key1_; } + Key key2() const { return key2_; } - Key key2() const { return key2_; } + const SharedNoiseModel &noiseModel() const { return noiseModel_; } - const SharedNoiseModel& noiseModel() const { return noiseModel_; } + /** implement functions needed for Testable */ - /** implement functions needed for Testable */ + /** print */ + void print(const std::string &s, const KeyFormatter &keyFormatter = DefaultKeyFormatter) const { + std::cout << s << "BinaryMeasurement(" + << keyFormatter(this->key1()) << "," + << keyFormatter(this->key2()) << ")\n"; + traits::Print(measured_, " measured: "); + this->noiseModel_->print(" noise model: "); + } - /** print */ - void print(const std::string& s, const KeyFormatter& keyFormatter = DefaultKeyFormatter) const { - std::cout << s << "BinaryMeasurement(" - << keyFormatter(this->key1()) << "," - << keyFormatter(this->key2()) << ")\n"; - traits::Print(measured_, " measured: "); - this->noiseModel_->print(" noise model: "); - } + /** equals */ + bool equals(const BinaryMeasurement &expected, double tol = 1e-9) const { + const BinaryMeasurement *e = dynamic_cast *> (&expected); + return e != nullptr && key1_ == e->key1_ && + key2_ == e->key2_ + && traits::Equals(this->measured_, e->measured_, tol) && + noiseModel_->equals(*expected.noiseModel()); + } - /** equals */ - bool equals(const BinaryMeasurement& expected, double tol=1e-9) const { - const BinaryMeasurement *e = dynamic_cast*> (&expected); - return e != nullptr && key1_ == e->key1_ && - key2_ == e->key2_ - && traits::Equals(this->measured_, e->measured_, tol) && - noiseModel_->equals(expected.noiseModel()); - } - - /** return the measured */ - VALUE measured() const { - return measured_; - } - }; // \class BetweenMeasurement - - using BinaryMeasurementUnit3s = std::vector::shared_ptr>; - using BinaryMeasurementRot3s = std::vector::shared_ptr>; + /** return the measured value */ + VALUE measured() const { + return measured_; + } +}; // \class BetweenMeasurement } \ No newline at end of file diff --git a/gtsam/sfm/TranslationRecovery.cpp b/gtsam/sfm/TranslationRecovery.cpp index c3be003ba..665336cc4 100644 --- a/gtsam/sfm/TranslationRecovery.cpp +++ b/gtsam/sfm/TranslationRecovery.cpp @@ -10,10 +10,10 @@ * -------------------------------------------------------------------------- */ /** - * @file TranslationRecovery.h + * @file TranslationRecovery.cpp * @author Frank Dellaert * @date March 2020 - * @brief test recovering translations when rotations are given. + * @brief Source code for recovering translations when rotations are given */ #include @@ -37,15 +37,15 @@ NonlinearFactorGraph TranslationRecovery::buildGraph() const { // Add all relative translation edges for (auto edge : relativeTranslations_) { - graph.emplace_shared(edge.key1(), edge.key2(), - edge.measured(), edge.noiseModel()); + graph.emplace_shared(edge.key1(), edge.key2(), + edge.measured(), edge.noiseModel()); } return graph; } void TranslationRecovery::addPrior(const double scale, - NonlinearFactorGraph* graph) const { + NonlinearFactorGraph *graph) const { //TODO(akshay-krishnan): make this an input argument auto priorNoiseModel = noiseModel::Isotropic::Sigma(3, 0.01); auto edge = relativeTranslations_.begin(); @@ -82,7 +82,7 @@ Values TranslationRecovery::run(const double scale) const { } TranslationRecovery::TranslationEdges TranslationRecovery::SimulateMeasurements( - const Values& poses, const vector& edges) { + const Values &poses, const vector &edges) { auto edgeNoiseModel = noiseModel::Isotropic::Sigma(3, 0.01); TranslationEdges relativeTranslations; for (auto edge : edges) { diff --git a/gtsam/sfm/TranslationRecovery.h b/gtsam/sfm/TranslationRecovery.h index 1392817b2..4c6a95cbe 100644 --- a/gtsam/sfm/TranslationRecovery.h +++ b/gtsam/sfm/TranslationRecovery.h @@ -13,7 +13,7 @@ * @file TranslationRecovery.h * @author Frank Dellaert * @date March 2020 - * @brief test recovering translations when rotations are given. + * @brief Recovering translations in an epipolar graph when rotations are given. */ #include @@ -66,8 +66,8 @@ class TranslationRecovery { * used to modify the parameters for the LM optimizer. By default, uses the * default LM parameters. */ - TranslationRecovery(const TranslationEdges& relativeTranslations, - const LevenbergMarquardtParams& lmParams = LevenbergMarquardtParams()) + TranslationRecovery(const TranslationEdges &relativeTranslations, + const LevenbergMarquardtParams &lmParams = LevenbergMarquardtParams()) : relativeTranslations_(relativeTranslations), params_(lmParams) { params_.setVerbosityLM("Summary"); } @@ -85,7 +85,7 @@ class TranslationRecovery { * @param scale scale for first relative translation which fixes gauge. * @param graph factor graph to which prior is added. */ - void addPrior(const double scale, NonlinearFactorGraph* graph) const; + void addPrior(const double scale, NonlinearFactorGraph *graph) const; /** * @brief Create random initial translations. @@ -112,6 +112,6 @@ class TranslationRecovery { * direction between the cameras. */ static TranslationEdges SimulateMeasurements( - const Values& poses, const std::vector& edges); + const Values &poses, const std::vector &edges); }; } // namespace gtsam diff --git a/gtsam/sfm/tests/testBinaryMeasurement.cpp b/gtsam/sfm/tests/testBinaryMeasurement.cpp index ae3ba23e5..3dd81c2c1 100644 --- a/gtsam/sfm/tests/testBinaryMeasurement.cpp +++ b/gtsam/sfm/tests/testBinaryMeasurement.cpp @@ -27,7 +27,6 @@ using namespace std; using namespace gtsam; -// Keys are deliberately *not* in sorted order to test that case. static const Key kKey1(2), kKey2(1); // Create noise models for unit3 and rot3 @@ -43,14 +42,24 @@ TEST(BinaryMeasurement, Unit3) { EXPECT_LONGS_EQUAL(unit3Measurement.key1(), kKey1); EXPECT_LONGS_EQUAL(unit3Measurement.key2(), kKey2); EXPECT(unit3Measurement.measured().equals(unit3Measured)); + + BinaryMeasurement unit3MeasurementCopy(kKey1, kKey2, unit3Measured, + unit3_model); + EXPECT(unit3Measurement.equals(unit3MeasurementCopy)); } TEST(BinaryMeasurement, Rot3) { + // testing the accessors BinaryMeasurement rot3Measurement(kKey1, kKey2, rot3Measured, - rot3_model); + rot3_model); EXPECT_LONGS_EQUAL(rot3Measurement.key1(), kKey1); EXPECT_LONGS_EQUAL(rot3Measurement.key2(), kKey2); EXPECT(rot3Measurement.measured().equals(rot3Measured)); + + // testing the equals function + BinaryMeasurement rot3MeasurementCopy(kKey1, kKey2, rot3Measured, + rot3_model); + EXPECT(rot3Measurement.equals(rot3MeasurementCopy)); } /* ************************************************************************* */ diff --git a/gtsam/sfm/tests/testTranslationFactor.cpp b/gtsam/sfm/tests/testTranslationFactor.cpp index 37e8b6c0f..3ff76ac5c 100644 --- a/gtsam/sfm/tests/testTranslationFactor.cpp +++ b/gtsam/sfm/tests/testTranslationFactor.cpp @@ -51,8 +51,6 @@ TEST(TranslationFactor, ZeroError) { // Verify we get the expected error Vector expected = (Vector3() << 0, 0, 0).finished(); EXPECT(assert_equal(expected, actualError, 1e-9)); - - } /* ************************************************************************* */ @@ -67,13 +65,13 @@ TEST(TranslationFactor, NonZeroError) { Vector actualError(factor.evaluateError(T1, T2)); // verify we get the expected error - Vector expected = (Vector3() << -1, 1/sqrt(2), 1/sqrt(2)).finished(); + Vector expected = (Vector3() << -1, 1 / sqrt(2), 1 / sqrt(2)).finished(); EXPECT(assert_equal(expected, actualError, 1e-9)); } /* ************************************************************************* */ -Vector factorError(const Point3& T1, const Point3& T2, - const TranslationFactor& factor) { +Vector factorError(const Point3 &T1, const Point3 &T2, + const TranslationFactor &factor) { return factor.evaluateError(T1, T2); } From 8425957e3ff52caa606d4c3de8c28b93b91edb75 Mon Sep 17 00:00:00 2001 From: ss Date: Sun, 9 Aug 2020 21:53:35 -0400 Subject: [PATCH 331/869] Finish Sim3 align and transformFrom functions. --- gtsam/geometry/Pose3.h | 3 + gtsam_unstable/geometry/Similarity3.cpp | 95 ++++++++++++++++ gtsam_unstable/geometry/Similarity3.h | 19 ++++ .../geometry/tests/testSimilarity3.cpp | 103 ++++++++++++++++++ 4 files changed, 220 insertions(+) diff --git a/gtsam/geometry/Pose3.h b/gtsam/geometry/Pose3.h index 159fd2927..57bec4dee 100644 --- a/gtsam/geometry/Pose3.h +++ b/gtsam/geometry/Pose3.h @@ -356,6 +356,9 @@ inline Matrix wedge(const Vector& xi) { return Pose3::wedge(xi(0), xi(1), xi(2), xi(3), xi(4), xi(5)); } +// Convenience typedef +typedef std::pair Pose3Pair; + // For MATLAB wrapper typedef std::vector Pose3Vector; diff --git a/gtsam_unstable/geometry/Similarity3.cpp b/gtsam_unstable/geometry/Similarity3.cpp index d40fb0b59..740960f0f 100644 --- a/gtsam_unstable/geometry/Similarity3.cpp +++ b/gtsam_unstable/geometry/Similarity3.cpp @@ -85,10 +85,105 @@ Point3 Similarity3::transformFrom(const Point3& p, // return s_ * q; } +Pose3 Similarity3::transformFrom(const Pose3& T) const { + Rot3 R = R_.compose(T.rotation()); + Point3 t = Point3(s_ * (R_.matrix() * T.translation().vector() + t_.vector())); + return Pose3(R, t); +} + Point3 Similarity3::operator*(const Point3& p) const { return transformFrom(p); } +Similarity3 Similarity3::Align(const std::vector& abPointPairs) { + const size_t n = abPointPairs.size(); + if (n < 3) throw std::runtime_error("less than 3 pairs"); // we need at least three pairs + + // calculate centroids + Point3 aCentroid(0, 0, 0), bCentroid(0, 0, 0); + for (const Point3Pair& abPair : abPointPairs) { + aCentroid += abPair.first; + bCentroid += abPair.second; + } + double f = 1.0 / n; + aCentroid *= f; + bCentroid *= f; + + // Add to form H matrix + Matrix3 H = Z_3x3; + for (const Point3Pair& abPair : abPointPairs) { + Point3 da = abPair.first - aCentroid; + Point3 db = abPair.second - bCentroid; + H += da * db.transpose(); + } + + // ClosestTo finds rotation matrix closest to H in Frobenius sense + Rot3 aRb = Rot3::ClosestTo(H); + + // Calculate scale + double x = 0; + double y = 0; + for (const Point3Pair& abPair : abPointPairs) { + Point3 da = abPair.first - aCentroid; + Point3 db = abPair.second - bCentroid; + Vector3 Rdb = aRb * db; + y += da.transpose() * Rdb; + x += Rdb.transpose() * Rdb; + } + double s = y / x; + + Point3 aTb = (Point3(aCentroid) - s * (aRb * Point3(bCentroid))) / s; + return Similarity3(aRb, aTb, s); +} + +Rot3 Similarity3::rotationAveraging(const std::vector& rotations, double error) { + Rot3 R = rotations[0]; + const size_t n = rotations.size(); + Vector3 r; + r << 0, 0, 0; + while (1) { + for (const Rot3 R_i : rotations) { + r += Rot3::Logmap(R.inverse().compose(R_i)); + } + r /= n; + if (r.norm() < error) return R; + R = R.compose(Rot3::Expmap(r)); + } +} + +Similarity3 Similarity3::Align(const std::vector& abPosePairs) { + const size_t n = abPosePairs.size(); + if (n < 2) throw std::runtime_error("less than 2 pairs"); // we need at least two pairs + + // calculate centroids + Point3 aCentroid(0, 0, 0), bCentroid(0, 0, 0); + vector rotationList; + for (const Pose3Pair& abPair : abPosePairs) { + aCentroid += abPair.first.translation(); + bCentroid += abPair.second.translation(); + rotationList.push_back(abPair.first.rotation().compose(abPair.second.rotation().inverse())); + } + double f = 1.0 / n; + aCentroid *= f; + bCentroid *= f; + Rot3 aRb = Similarity3::rotationAveraging(rotationList); + + // Calculate scale + double x = 0; + double y = 0; + for (const Pose3Pair& abPair : abPosePairs) { + Point3 da = abPair.first.translation() - aCentroid; + Point3 db = abPair.second.translation() - bCentroid; + Vector3 Rdb = aRb * db; + y += da.transpose() * Rdb; + x += Rdb.transpose() * Rdb; + } + double s = y / x; + + Point3 aTb = (Point3(aCentroid) - s * (aRb * Point3(bCentroid))) / s; + return Similarity3(aRb, aTb, s); +} + Matrix4 Similarity3::wedge(const Vector7& xi) { // http://www.ethaneade.org/latex2html/lie/node29.html const auto w = xi.head<3>(); diff --git a/gtsam_unstable/geometry/Similarity3.h b/gtsam_unstable/geometry/Similarity3.h index bf4937ed4..06b609eee 100644 --- a/gtsam_unstable/geometry/Similarity3.h +++ b/gtsam_unstable/geometry/Similarity3.h @@ -19,6 +19,7 @@ #include #include +#include #include #include #include @@ -101,9 +102,27 @@ public: OptionalJacobian<3, 7> H1 = boost::none, // OptionalJacobian<3, 3> H2 = boost::none) const; + /// Action on a pose T + GTSAM_UNSTABLE_EXPORT Pose3 transformFrom(const Pose3& T) const; + /** syntactic sugar for transformFrom */ GTSAM_UNSTABLE_EXPORT Point3 operator*(const Point3& p) const; + /** + * Create Similarity3 by aligning two point pairs + */ + GTSAM_UNSTABLE_EXPORT static Similarity3 Align(const std::vector& abPointPairs); + + /** + * Calculate the average rotation from a list of rotations + */ + GTSAM_UNSTABLE_EXPORT static Rot3 rotationAveraging(const std::vector& rotations, double error = 1e-10); + + /** + * Create Similarity3 by aligning two pose pairs + */ + GTSAM_UNSTABLE_EXPORT static Similarity3 Align(const std::vector& abPosePairs); + /// @} /// @name Lie Group /// @{ diff --git a/gtsam_unstable/geometry/tests/testSimilarity3.cpp b/gtsam_unstable/geometry/tests/testSimilarity3.cpp index d23346896..770196e20 100644 --- a/gtsam_unstable/geometry/tests/testSimilarity3.cpp +++ b/gtsam_unstable/geometry/tests/testSimilarity3.cpp @@ -51,6 +51,8 @@ static const Similarity3 T4(R, P, s); static const Similarity3 T5(R, P, 10); static const Similarity3 T6(Rot3(), Point3(1, 1, 0), 2); // Simpler transform +const double degree = M_PI / 180; + //****************************************************************************** TEST(Similarity3, Concepts) { BOOST_CONCEPT_ASSERT((IsGroup)); @@ -255,6 +257,107 @@ TEST(Similarity3, GroupAction) { } } +//****************************************************************************** +// Group action on Pose3 +TEST(Similarity3, GroupActionPose3) { + Similarity3 bTa(Rot3::Ry(180 * degree), Point3(2, 3, 5), 2.0); + + // Create source poses + Pose3 Ta1 = Pose3(Rot3(), Point3(0, 0, 0)); + Pose3 Ta2 = Pose3(Rot3(-1, 0, 0, 0, 1, 0, 0, 0, 1), Point3(4, 0, 0)); + + // Create destination poses + Pose3 expectedTb1 = Pose3(Rot3(-1, 0, 0, 0, 1, 0, 0, 0, -1), Point3(4, 6, 10)); + Pose3 expectedTb2 = Pose3(Rot3(1, 0, 0, 0, 1, 0, 0, 0, -1), Point3(-4, 6, 10)); + + EXPECT(assert_equal(expectedTb1, bTa.transformFrom(Ta1))); + EXPECT(assert_equal(expectedTb2, bTa.transformFrom(Ta2))); +} + +//****************************************************************************** +// Align with Point3 Pairs +TEST(Similarity3, AlignPoint3_1) { + Similarity3 expected(Rot3::Rz(-90 * degree), Point3(3, 4, 5), 2.0); + + Point3 p1 = Point3(0, 0, 0); + Point3 p2 = Point3(3, 0, 0); + Point3 p3 = Point3(3, 0, 4); + + Point3Pair ab1(make_pair(expected.transformFrom(p1), p1)); + Point3Pair ab2(make_pair(expected.transformFrom(p2), p2)); + Point3Pair ab3(make_pair(expected.transformFrom(p3), p3)); + + vector correspondences{ab1, ab2, ab3}; + + Similarity3 actual = Similarity3::Align(correspondences); + EXPECT(assert_equal(expected, actual)); +} + +TEST(Similarity3, AlignPoint3_2) { + Similarity3 expected(Rot3(), Point3(10, 10, 0), 1.0); + + Point3 p1 = Point3(0, 0, 0); + Point3 p2 = Point3(20, 10, 0); + Point3 p3 = Point3(10, 20, 0); + + Point3Pair ab1(make_pair(expected.transformFrom(p1), p1)); + Point3Pair ab2(make_pair(expected.transformFrom(p2), p2)); + Point3Pair ab3(make_pair(expected.transformFrom(p3), p3)); + + vector correspondences{ab1, ab2, ab3}; + + Similarity3 actual = Similarity3::Align(correspondences); + EXPECT(assert_equal(expected, actual)); +} + +TEST(Similarity3, AlignPoint3_3) { + Similarity3 expected(Rot3::RzRyRx(0.3, 0.2, 0.1), Point3(20, 10, 5), 1.0); + + Point3 p1 = Point3(0, 0, 1); + Point3 p2 = Point3(10, 0, 2); + Point3 p3 = Point3(20, -10, 30); + + Point3Pair ab1(make_pair(expected.transformFrom(p1), p1)); + Point3Pair ab2(make_pair(expected.transformFrom(p2), p2)); + Point3Pair ab3(make_pair(expected.transformFrom(p3), p3)); + + vector correspondences{ab1, ab2, ab3}; + + Similarity3 actual = Similarity3::Align(correspondences); + EXPECT(assert_equal(expected, actual)); +} + +//****************************************************************************** +// Rotation Averaging +TEST(Similarity3, RotationAveraging) { + Rot3 expected = Rot3::Rx(90 * degree); + vector rotations{Rot3(), Rot3::Rx(90 * degree), Rot3::Rx(180 * degree)}; + Rot3 actual = Similarity3::rotationAveraging(rotations); + EXPECT(assert_equal(expected, actual)); +} + +//****************************************************************************** +// Align with Pose3 Pairs +TEST(Similarity3, AlignPose3) { + Similarity3 expected(Rot3::Ry(180 * degree), Point3(2, 3, 5), 2.0); + + // Create source poses + Pose3 Ta1 = Pose3(Rot3(), Point3(0, 0, 0)); + Pose3 Ta2 = Pose3(Rot3(-1, 0, 0, 0, 1, 0, 0, 0, 1), Point3(4, 0, 0)); + + // Create destination poses + Pose3 Tb1 = Pose3(Rot3(-1, 0, 0, 0, 1, 0, 0, 0, -1), Point3(4, 6, 10)); + Pose3 Tb2 = Pose3(Rot3(1, 0, 0, 0, 1, 0, 0, 0, -1), Point3(-4, 6, 10)); + + Pose3Pair bTa1(make_pair(Tb1, Ta1)); + Pose3Pair bTa2(make_pair(Tb2, Ta2)); + + vector correspondences{bTa1, bTa2}; + + Similarity3 actual = Similarity3::Align(correspondences); + EXPECT(assert_equal(expected, actual)); +} + //****************************************************************************** // Test very simple prior optimization example TEST(Similarity3, Optimization) { From 1159032d89f39b791e2b557f841349babbf4422f Mon Sep 17 00:00:00 2001 From: akrishnan86 Date: Sun, 9 Aug 2020 22:03:01 -0700 Subject: [PATCH 332/869] update binary measurement brief --- gtsam/sfm/BinaryMeasurement.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/gtsam/sfm/BinaryMeasurement.h b/gtsam/sfm/BinaryMeasurement.h index 9b0874106..c4b4a9804 100644 --- a/gtsam/sfm/BinaryMeasurement.h +++ b/gtsam/sfm/BinaryMeasurement.h @@ -15,7 +15,7 @@ * @file BinaryMeasurement.h * @author Akshay Krishnan * @date July 2020 - * @brief Binary measurement for representing edges in the epipolar graph. + * @brief Binary measurement represents a measurement between two keys in a graph. * A binary measurement is similar to a BetweenFactor, except that it does not contain * an error function. It is a measurement (along with a noise model) from one key to * another. Note that the direction is important. A measurement from key1 to key2 is not From e6b1599063e5eff2e73b948ad860ac2c8011f23e Mon Sep 17 00:00:00 2001 From: ss Date: Mon, 10 Aug 2020 08:25:21 -0400 Subject: [PATCH 333/869] Fix document. --- gtsam_unstable/geometry/Similarity3.h | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/gtsam_unstable/geometry/Similarity3.h b/gtsam_unstable/geometry/Similarity3.h index 06b609eee..e04db4df7 100644 --- a/gtsam_unstable/geometry/Similarity3.h +++ b/gtsam_unstable/geometry/Similarity3.h @@ -102,14 +102,14 @@ public: OptionalJacobian<3, 7> H1 = boost::none, // OptionalJacobian<3, 3> H2 = boost::none) const; - /// Action on a pose T + /// Action on a pose T, R = R*T.R, t = s(R*T.t+t) GTSAM_UNSTABLE_EXPORT Pose3 transformFrom(const Pose3& T) const; /** syntactic sugar for transformFrom */ GTSAM_UNSTABLE_EXPORT Point3 operator*(const Point3& p) const; /** - * Create Similarity3 by aligning two point pairs + * Create Similarity3 by aligning at least three point pairs */ GTSAM_UNSTABLE_EXPORT static Similarity3 Align(const std::vector& abPointPairs); @@ -119,7 +119,7 @@ public: GTSAM_UNSTABLE_EXPORT static Rot3 rotationAveraging(const std::vector& rotations, double error = 1e-10); /** - * Create Similarity3 by aligning two pose pairs + * Create Similarity3 by aligning at least two pose pairs */ GTSAM_UNSTABLE_EXPORT static Similarity3 Align(const std::vector& abPosePairs); From 8dd9ff5c52b7b12d974097e06cf782c676fa3085 Mon Sep 17 00:00:00 2001 From: ss Date: Mon, 10 Aug 2020 08:25:42 -0400 Subject: [PATCH 334/869] Improve code quality. --- gtsam_unstable/geometry/Similarity3.cpp | 14 ++++++++------ 1 file changed, 8 insertions(+), 6 deletions(-) diff --git a/gtsam_unstable/geometry/Similarity3.cpp b/gtsam_unstable/geometry/Similarity3.cpp index 740960f0f..87c4d3ae2 100644 --- a/gtsam_unstable/geometry/Similarity3.cpp +++ b/gtsam_unstable/geometry/Similarity3.cpp @@ -97,7 +97,7 @@ Point3 Similarity3::operator*(const Point3& p) const { Similarity3 Similarity3::Align(const std::vector& abPointPairs) { const size_t n = abPointPairs.size(); - if (n < 3) throw std::runtime_error("less than 3 pairs"); // we need at least three pairs + if (n < 3) throw std::runtime_error("input should have at least 3 pairs of points"); // we need at least three pairs // calculate centroids Point3 aCentroid(0, 0, 0), bCentroid(0, 0, 0); @@ -111,9 +111,11 @@ Similarity3 Similarity3::Align(const std::vector& abPointPairs) { // Add to form H matrix Matrix3 H = Z_3x3; + vector d_abPairs; for (const Point3Pair& abPair : abPointPairs) { Point3 da = abPair.first - aCentroid; Point3 db = abPair.second - bCentroid; + d_abPairs.push_back(make_pair(da,db)); H += da * db.transpose(); } @@ -123,9 +125,9 @@ Similarity3 Similarity3::Align(const std::vector& abPointPairs) { // Calculate scale double x = 0; double y = 0; - for (const Point3Pair& abPair : abPointPairs) { - Point3 da = abPair.first - aCentroid; - Point3 db = abPair.second - bCentroid; + for (const Point3Pair& d_abPair : d_abPairs) { + Point3 da = d_abPair.first; + Point3 db = d_abPair.second; Vector3 Rdb = aRb * db; y += da.transpose() * Rdb; x += Rdb.transpose() * Rdb; @@ -153,9 +155,9 @@ Rot3 Similarity3::rotationAveraging(const std::vector& rotations, double e Similarity3 Similarity3::Align(const std::vector& abPosePairs) { const size_t n = abPosePairs.size(); - if (n < 2) throw std::runtime_error("less than 2 pairs"); // we need at least two pairs + if (n < 2) throw std::runtime_error("input should have at least 2 pairs of poses"); // we need at least two pairs - // calculate centroids + // calculate rotation and centroids Point3 aCentroid(0, 0, 0), bCentroid(0, 0, 0); vector rotationList; for (const Pose3Pair& abPair : abPosePairs) { From 7cfcbff4dbb0c143501027f55407431780dfea57 Mon Sep 17 00:00:00 2001 From: ss Date: Mon, 10 Aug 2020 08:37:39 -0400 Subject: [PATCH 335/869] Update doc. --- gtsam_unstable/geometry/Similarity3.cpp | 3 +++ 1 file changed, 3 insertions(+) diff --git a/gtsam_unstable/geometry/Similarity3.cpp b/gtsam_unstable/geometry/Similarity3.cpp index 87c4d3ae2..4a330b15b 100644 --- a/gtsam_unstable/geometry/Similarity3.cpp +++ b/gtsam_unstable/geometry/Similarity3.cpp @@ -95,6 +95,7 @@ Point3 Similarity3::operator*(const Point3& p) const { return transformFrom(p); } +// Refer to: http://www5.informatik.uni-erlangen.de/Forschung/Publikationen/2005/Zinsser05-PSR.pdf Chapter 3 Similarity3 Similarity3::Align(const std::vector& abPointPairs) { const size_t n = abPointPairs.size(); if (n < 3) throw std::runtime_error("input should have at least 3 pairs of points"); // we need at least three pairs @@ -138,6 +139,8 @@ Similarity3 Similarity3::Align(const std::vector& abPointPairs) { return Similarity3(aRb, aTb, s); } +// Use the geodesic L2 mean to solve the mean of rotations, +// Refer to: http://users.cecs.anu.edu.au/~hongdong/rotationaveraging.pdf (on page 18) Rot3 Similarity3::rotationAveraging(const std::vector& rotations, double error) { Rot3 R = rotations[0]; const size_t n = rotations.size(); From 7cfc5c352254b5bbc710f3e1d5b1f9bf19cfd84f Mon Sep 17 00:00:00 2001 From: Frank Dellaert Date: Mon, 10 Aug 2020 22:56:43 -0400 Subject: [PATCH 336/869] Added Spectra 0.9.0 to 3rdparty --- LICENSE | 2 + gtsam/3rdparty/CMakeLists.txt | 3 +- gtsam/3rdparty/Spectra/GenEigsBase.h | 482 +++++++++++++ .../Spectra/GenEigsComplexShiftSolver.h | 157 ++++ .../3rdparty/Spectra/GenEigsRealShiftSolver.h | 89 +++ gtsam/3rdparty/Spectra/GenEigsSolver.h | 158 +++++ gtsam/3rdparty/Spectra/LinAlg/Arnoldi.h | 284 ++++++++ gtsam/3rdparty/Spectra/LinAlg/BKLDLT.h | 530 ++++++++++++++ gtsam/3rdparty/Spectra/LinAlg/DoubleShiftQR.h | 384 ++++++++++ gtsam/3rdparty/Spectra/LinAlg/Lanczos.h | 167 +++++ gtsam/3rdparty/Spectra/LinAlg/TridiagEigen.h | 219 ++++++ .../Spectra/LinAlg/UpperHessenbergEigen.h | 319 +++++++++ .../Spectra/LinAlg/UpperHessenbergQR.h | 670 ++++++++++++++++++ gtsam/3rdparty/Spectra/MatOp/DenseCholesky.h | 108 +++ .../Spectra/MatOp/DenseGenComplexShiftSolve.h | 102 +++ .../3rdparty/Spectra/MatOp/DenseGenMatProd.h | 80 +++ .../Spectra/MatOp/DenseGenRealShiftSolve.h | 88 +++ .../3rdparty/Spectra/MatOp/DenseSymMatProd.h | 73 ++ .../Spectra/MatOp/DenseSymShiftSolve.h | 92 +++ gtsam/3rdparty/Spectra/MatOp/SparseCholesky.h | 109 +++ .../3rdparty/Spectra/MatOp/SparseGenMatProd.h | 74 ++ .../Spectra/MatOp/SparseGenRealShiftSolve.h | 93 +++ .../Spectra/MatOp/SparseRegularInverse.h | 100 +++ .../3rdparty/Spectra/MatOp/SparseSymMatProd.h | 73 ++ .../Spectra/MatOp/SparseSymShiftSolve.h | 95 +++ .../Spectra/MatOp/internal/ArnoldiOp.h | 150 ++++ .../MatOp/internal/SymGEigsCholeskyOp.h | 75 ++ .../Spectra/MatOp/internal/SymGEigsRegInvOp.h | 72 ++ gtsam/3rdparty/Spectra/SymEigsBase.h | 448 ++++++++++++ gtsam/3rdparty/Spectra/SymEigsShiftSolver.h | 203 ++++++ gtsam/3rdparty/Spectra/SymEigsSolver.h | 171 +++++ gtsam/3rdparty/Spectra/SymGEigsSolver.h | 326 +++++++++ gtsam/3rdparty/Spectra/Util/CompInfo.h | 35 + gtsam/3rdparty/Spectra/Util/GEigsMode.h | 32 + gtsam/3rdparty/Spectra/Util/SelectionRule.h | 275 +++++++ gtsam/3rdparty/Spectra/Util/SimpleRandom.h | 91 +++ gtsam/3rdparty/Spectra/Util/TypeTraits.h | 71 ++ gtsam/3rdparty/Spectra/contrib/LOBPCGSolver.h | 552 +++++++++++++++ .../Spectra/contrib/PartialSVDSolver.h | 202 ++++++ gtsam/CMakeLists.txt | 2 + 40 files changed, 7255 insertions(+), 1 deletion(-) create mode 100644 gtsam/3rdparty/Spectra/GenEigsBase.h create mode 100644 gtsam/3rdparty/Spectra/GenEigsComplexShiftSolver.h create mode 100644 gtsam/3rdparty/Spectra/GenEigsRealShiftSolver.h create mode 100644 gtsam/3rdparty/Spectra/GenEigsSolver.h create mode 100644 gtsam/3rdparty/Spectra/LinAlg/Arnoldi.h create mode 100644 gtsam/3rdparty/Spectra/LinAlg/BKLDLT.h create mode 100644 gtsam/3rdparty/Spectra/LinAlg/DoubleShiftQR.h create mode 100644 gtsam/3rdparty/Spectra/LinAlg/Lanczos.h create mode 100644 gtsam/3rdparty/Spectra/LinAlg/TridiagEigen.h create mode 100644 gtsam/3rdparty/Spectra/LinAlg/UpperHessenbergEigen.h create mode 100644 gtsam/3rdparty/Spectra/LinAlg/UpperHessenbergQR.h create mode 100644 gtsam/3rdparty/Spectra/MatOp/DenseCholesky.h create mode 100644 gtsam/3rdparty/Spectra/MatOp/DenseGenComplexShiftSolve.h create mode 100644 gtsam/3rdparty/Spectra/MatOp/DenseGenMatProd.h create mode 100644 gtsam/3rdparty/Spectra/MatOp/DenseGenRealShiftSolve.h create mode 100644 gtsam/3rdparty/Spectra/MatOp/DenseSymMatProd.h create mode 100644 gtsam/3rdparty/Spectra/MatOp/DenseSymShiftSolve.h create mode 100644 gtsam/3rdparty/Spectra/MatOp/SparseCholesky.h create mode 100644 gtsam/3rdparty/Spectra/MatOp/SparseGenMatProd.h create mode 100644 gtsam/3rdparty/Spectra/MatOp/SparseGenRealShiftSolve.h create mode 100644 gtsam/3rdparty/Spectra/MatOp/SparseRegularInverse.h create mode 100644 gtsam/3rdparty/Spectra/MatOp/SparseSymMatProd.h create mode 100644 gtsam/3rdparty/Spectra/MatOp/SparseSymShiftSolve.h create mode 100644 gtsam/3rdparty/Spectra/MatOp/internal/ArnoldiOp.h create mode 100644 gtsam/3rdparty/Spectra/MatOp/internal/SymGEigsCholeskyOp.h create mode 100644 gtsam/3rdparty/Spectra/MatOp/internal/SymGEigsRegInvOp.h create mode 100644 gtsam/3rdparty/Spectra/SymEigsBase.h create mode 100644 gtsam/3rdparty/Spectra/SymEigsShiftSolver.h create mode 100644 gtsam/3rdparty/Spectra/SymEigsSolver.h create mode 100644 gtsam/3rdparty/Spectra/SymGEigsSolver.h create mode 100644 gtsam/3rdparty/Spectra/Util/CompInfo.h create mode 100644 gtsam/3rdparty/Spectra/Util/GEigsMode.h create mode 100644 gtsam/3rdparty/Spectra/Util/SelectionRule.h create mode 100644 gtsam/3rdparty/Spectra/Util/SimpleRandom.h create mode 100644 gtsam/3rdparty/Spectra/Util/TypeTraits.h create mode 100644 gtsam/3rdparty/Spectra/contrib/LOBPCGSolver.h create mode 100644 gtsam/3rdparty/Spectra/contrib/PartialSVDSolver.h diff --git a/LICENSE b/LICENSE index d828deb55..228a6b942 100644 --- a/LICENSE +++ b/LICENSE @@ -23,3 +23,5 @@ ordering library - Included unmodified in gtsam/3rdparty/metis - Licenced under Apache License v 2.0, provided in gtsam/3rdparty/metis/LICENSE.txt +- Spectra v0.9.0: Sparse Eigenvalue Computation Toolkit as a Redesigned ARPACK. + - Licenced under MPL2, provided at https://github.com/yixuan/spectra diff --git a/gtsam/3rdparty/CMakeLists.txt b/gtsam/3rdparty/CMakeLists.txt index c8fecc339..8b356393b 100644 --- a/gtsam/3rdparty/CMakeLists.txt +++ b/gtsam/3rdparty/CMakeLists.txt @@ -1,7 +1,8 @@ -# install CCOLAMD headers +# install CCOLAMD and SuiteSparse_config headers install(FILES CCOLAMD/Include/ccolamd.h DESTINATION ${CMAKE_INSTALL_INCLUDEDIR}/gtsam/3rdparty/CCOLAMD) install(FILES SuiteSparse_config/SuiteSparse_config.h DESTINATION ${CMAKE_INSTALL_INCLUDEDIR}/gtsam/3rdparty/SuiteSparse_config) +# install Eigen unless System Eigen is used if(NOT GTSAM_USE_SYSTEM_EIGEN) # Find plain .h files file(GLOB_RECURSE eigen_headers "${CMAKE_CURRENT_SOURCE_DIR}/Eigen/Eigen/*.h") diff --git a/gtsam/3rdparty/Spectra/GenEigsBase.h b/gtsam/3rdparty/Spectra/GenEigsBase.h new file mode 100644 index 000000000..e084033d7 --- /dev/null +++ b/gtsam/3rdparty/Spectra/GenEigsBase.h @@ -0,0 +1,482 @@ +// Copyright (C) 2018-2019 Yixuan Qiu +// +// This Source Code Form is subject to the terms of the Mozilla +// Public License v. 2.0. If a copy of the MPL was not distributed +// with this file, You can obtain one at https://mozilla.org/MPL/2.0/. + +#ifndef GEN_EIGS_BASE_H +#define GEN_EIGS_BASE_H + +#include +#include // std::vector +#include // std::abs, std::pow, std::sqrt +#include // std::min, std::copy +#include // std::complex, std::conj, std::norm, std::abs +#include // std::invalid_argument + +#include "Util/TypeTraits.h" +#include "Util/SelectionRule.h" +#include "Util/CompInfo.h" +#include "Util/SimpleRandom.h" +#include "MatOp/internal/ArnoldiOp.h" +#include "LinAlg/UpperHessenbergQR.h" +#include "LinAlg/DoubleShiftQR.h" +#include "LinAlg/UpperHessenbergEigen.h" +#include "LinAlg/Arnoldi.h" + +namespace Spectra { + +/// +/// \ingroup EigenSolver +/// +/// This is the base class for general eigen solvers, mainly for internal use. +/// It is kept here to provide the documentation for member functions of concrete eigen solvers +/// such as GenEigsSolver and GenEigsRealShiftSolver. +/// +template +class GenEigsBase +{ +private: + typedef Eigen::Index Index; + typedef Eigen::Matrix Matrix; + typedef Eigen::Matrix Vector; + typedef Eigen::Array Array; + typedef Eigen::Array BoolArray; + typedef Eigen::Map MapMat; + typedef Eigen::Map MapVec; + typedef Eigen::Map MapConstVec; + + typedef std::complex Complex; + typedef Eigen::Matrix ComplexMatrix; + typedef Eigen::Matrix ComplexVector; + + typedef ArnoldiOp ArnoldiOpType; + typedef Arnoldi ArnoldiFac; + +protected: + // clang-format off + OpType* m_op; // object to conduct matrix operation, + // e.g. matrix-vector product + const Index m_n; // dimension of matrix A + const Index m_nev; // number of eigenvalues requested + const Index m_ncv; // dimension of Krylov subspace in the Arnoldi method + Index m_nmatop; // number of matrix operations called + Index m_niter; // number of restarting iterations + + ArnoldiFac m_fac; // Arnoldi factorization + + ComplexVector m_ritz_val; // Ritz values + ComplexMatrix m_ritz_vec; // Ritz vectors + ComplexVector m_ritz_est; // last row of m_ritz_vec + +private: + BoolArray m_ritz_conv; // indicator of the convergence of Ritz values + int m_info; // status of the computation + + const Scalar m_near_0; // a very small value, but 1.0 / m_near_0 does not overflow + // ~= 1e-307 for the "double" type + const Scalar m_eps; // the machine precision, ~= 1e-16 for the "double" type + const Scalar m_eps23; // m_eps^(2/3), used to test the convergence + // clang-format on + + // Real Ritz values calculated from UpperHessenbergEigen have exact zero imaginary part + // Complex Ritz values have exact conjugate pairs + // So we use exact tests here + static bool is_complex(const Complex& v) { return v.imag() != Scalar(0); } + static bool is_conj(const Complex& v1, const Complex& v2) { return v1 == Eigen::numext::conj(v2); } + + // Implicitly restarted Arnoldi factorization + void restart(Index k) + { + using std::norm; + + if (k >= m_ncv) + return; + + DoubleShiftQR decomp_ds(m_ncv); + UpperHessenbergQR decomp_hb(m_ncv); + Matrix Q = Matrix::Identity(m_ncv, m_ncv); + + for (Index i = k; i < m_ncv; i++) + { + if (is_complex(m_ritz_val[i]) && is_conj(m_ritz_val[i], m_ritz_val[i + 1])) + { + // H - mu * I = Q1 * R1 + // H <- R1 * Q1 + mu * I = Q1' * H * Q1 + // H - conj(mu) * I = Q2 * R2 + // H <- R2 * Q2 + conj(mu) * I = Q2' * H * Q2 + // + // (H - mu * I) * (H - conj(mu) * I) = Q1 * Q2 * R2 * R1 = Q * R + const Scalar s = Scalar(2) * m_ritz_val[i].real(); + const Scalar t = norm(m_ritz_val[i]); + + decomp_ds.compute(m_fac.matrix_H(), s, t); + + // Q -> Q * Qi + decomp_ds.apply_YQ(Q); + // H -> Q'HQ + // Matrix Q = Matrix::Identity(m_ncv, m_ncv); + // decomp_ds.apply_YQ(Q); + // m_fac_H = Q.transpose() * m_fac_H * Q; + m_fac.compress_H(decomp_ds); + + i++; + } + else + { + // QR decomposition of H - mu * I, mu is real + decomp_hb.compute(m_fac.matrix_H(), m_ritz_val[i].real()); + + // Q -> Q * Qi + decomp_hb.apply_YQ(Q); + // H -> Q'HQ = RQ + mu * I + m_fac.compress_H(decomp_hb); + } + } + + m_fac.compress_V(Q); + m_fac.factorize_from(k, m_ncv, m_nmatop); + + retrieve_ritzpair(); + } + + // Calculates the number of converged Ritz values + Index num_converged(Scalar tol) + { + // thresh = tol * max(m_eps23, abs(theta)), theta for Ritz value + Array thresh = tol * m_ritz_val.head(m_nev).array().abs().max(m_eps23); + Array resid = m_ritz_est.head(m_nev).array().abs() * m_fac.f_norm(); + // Converged "wanted" Ritz values + m_ritz_conv = (resid < thresh); + + return m_ritz_conv.cast().sum(); + } + + // Returns the adjusted nev for restarting + Index nev_adjusted(Index nconv) + { + using std::abs; + + Index nev_new = m_nev; + for (Index i = m_nev; i < m_ncv; i++) + if (abs(m_ritz_est[i]) < m_near_0) + nev_new++; + + // Adjust nev_new, according to dnaup2.f line 660~674 in ARPACK + nev_new += std::min(nconv, (m_ncv - nev_new) / 2); + if (nev_new == 1 && m_ncv >= 6) + nev_new = m_ncv / 2; + else if (nev_new == 1 && m_ncv > 3) + nev_new = 2; + + if (nev_new > m_ncv - 2) + nev_new = m_ncv - 2; + + // Increase nev by one if ritz_val[nev - 1] and + // ritz_val[nev] are conjugate pairs + if (is_complex(m_ritz_val[nev_new - 1]) && + is_conj(m_ritz_val[nev_new - 1], m_ritz_val[nev_new])) + { + nev_new++; + } + + return nev_new; + } + + // Retrieves and sorts Ritz values and Ritz vectors + void retrieve_ritzpair() + { + UpperHessenbergEigen decomp(m_fac.matrix_H()); + const ComplexVector& evals = decomp.eigenvalues(); + ComplexMatrix evecs = decomp.eigenvectors(); + + SortEigenvalue sorting(evals.data(), evals.size()); + std::vector ind = sorting.index(); + + // Copy the Ritz values and vectors to m_ritz_val and m_ritz_vec, respectively + for (Index i = 0; i < m_ncv; i++) + { + m_ritz_val[i] = evals[ind[i]]; + m_ritz_est[i] = evecs(m_ncv - 1, ind[i]); + } + for (Index i = 0; i < m_nev; i++) + { + m_ritz_vec.col(i).noalias() = evecs.col(ind[i]); + } + } + +protected: + // Sorts the first nev Ritz pairs in the specified order + // This is used to return the final results + virtual void sort_ritzpair(int sort_rule) + { + // First make sure that we have a valid index vector + SortEigenvalue sorting(m_ritz_val.data(), m_nev); + std::vector ind = sorting.index(); + + switch (sort_rule) + { + case LARGEST_MAGN: + break; + case LARGEST_REAL: + { + SortEigenvalue sorting(m_ritz_val.data(), m_nev); + ind = sorting.index(); + break; + } + case LARGEST_IMAG: + { + SortEigenvalue sorting(m_ritz_val.data(), m_nev); + ind = sorting.index(); + break; + } + case SMALLEST_MAGN: + { + SortEigenvalue sorting(m_ritz_val.data(), m_nev); + ind = sorting.index(); + break; + } + case SMALLEST_REAL: + { + SortEigenvalue sorting(m_ritz_val.data(), m_nev); + ind = sorting.index(); + break; + } + case SMALLEST_IMAG: + { + SortEigenvalue sorting(m_ritz_val.data(), m_nev); + ind = sorting.index(); + break; + } + default: + throw std::invalid_argument("unsupported sorting rule"); + } + + ComplexVector new_ritz_val(m_ncv); + ComplexMatrix new_ritz_vec(m_ncv, m_nev); + BoolArray new_ritz_conv(m_nev); + + for (Index i = 0; i < m_nev; i++) + { + new_ritz_val[i] = m_ritz_val[ind[i]]; + new_ritz_vec.col(i).noalias() = m_ritz_vec.col(ind[i]); + new_ritz_conv[i] = m_ritz_conv[ind[i]]; + } + + m_ritz_val.swap(new_ritz_val); + m_ritz_vec.swap(new_ritz_vec); + m_ritz_conv.swap(new_ritz_conv); + } + +public: + /// \cond + + GenEigsBase(OpType* op, BOpType* Bop, Index nev, Index ncv) : + m_op(op), + m_n(m_op->rows()), + m_nev(nev), + m_ncv(ncv > m_n ? m_n : ncv), + m_nmatop(0), + m_niter(0), + m_fac(ArnoldiOpType(op, Bop), m_ncv), + m_info(NOT_COMPUTED), + m_near_0(TypeTraits::min() * Scalar(10)), + m_eps(Eigen::NumTraits::epsilon()), + m_eps23(Eigen::numext::pow(m_eps, Scalar(2.0) / 3)) + { + if (nev < 1 || nev > m_n - 2) + throw std::invalid_argument("nev must satisfy 1 <= nev <= n - 2, n is the size of matrix"); + + if (ncv < nev + 2 || ncv > m_n) + throw std::invalid_argument("ncv must satisfy nev + 2 <= ncv <= n, n is the size of matrix"); + } + + /// + /// Virtual destructor + /// + virtual ~GenEigsBase() {} + + /// \endcond + + /// + /// Initializes the solver by providing an initial residual vector. + /// + /// \param init_resid Pointer to the initial residual vector. + /// + /// **Spectra** (and also **ARPACK**) uses an iterative algorithm + /// to find eigenvalues. This function allows the user to provide the initial + /// residual vector. + /// + void init(const Scalar* init_resid) + { + // Reset all matrices/vectors to zero + m_ritz_val.resize(m_ncv); + m_ritz_vec.resize(m_ncv, m_nev); + m_ritz_est.resize(m_ncv); + m_ritz_conv.resize(m_nev); + + m_ritz_val.setZero(); + m_ritz_vec.setZero(); + m_ritz_est.setZero(); + m_ritz_conv.setZero(); + + m_nmatop = 0; + m_niter = 0; + + // Initialize the Arnoldi factorization + MapConstVec v0(init_resid, m_n); + m_fac.init(v0, m_nmatop); + } + + /// + /// Initializes the solver by providing a random initial residual vector. + /// + /// This overloaded function generates a random initial residual vector + /// (with a fixed random seed) for the algorithm. Elements in the vector + /// follow independent Uniform(-0.5, 0.5) distribution. + /// + void init() + { + SimpleRandom rng(0); + Vector init_resid = rng.random_vec(m_n); + init(init_resid.data()); + } + + /// + /// Conducts the major computation procedure. + /// + /// \param maxit Maximum number of iterations allowed in the algorithm. + /// \param tol Precision parameter for the calculated eigenvalues. + /// \param sort_rule Rule to sort the eigenvalues and eigenvectors. + /// Supported values are + /// `Spectra::LARGEST_MAGN`, `Spectra::LARGEST_REAL`, + /// `Spectra::LARGEST_IMAG`, `Spectra::SMALLEST_MAGN`, + /// `Spectra::SMALLEST_REAL` and `Spectra::SMALLEST_IMAG`, + /// for example `LARGEST_MAGN` indicates that eigenvalues + /// with largest magnitude come first. + /// Note that this argument is only used to + /// **sort** the final result, and the **selection** rule + /// (e.g. selecting the largest or smallest eigenvalues in the + /// full spectrum) is specified by the template parameter + /// `SelectionRule` of GenEigsSolver. + /// + /// \return Number of converged eigenvalues. + /// + Index compute(Index maxit = 1000, Scalar tol = 1e-10, int sort_rule = LARGEST_MAGN) + { + // The m-step Arnoldi factorization + m_fac.factorize_from(1, m_ncv, m_nmatop); + retrieve_ritzpair(); + // Restarting + Index i, nconv = 0, nev_adj; + for (i = 0; i < maxit; i++) + { + nconv = num_converged(tol); + if (nconv >= m_nev) + break; + + nev_adj = nev_adjusted(nconv); + restart(nev_adj); + } + // Sorting results + sort_ritzpair(sort_rule); + + m_niter += i + 1; + m_info = (nconv >= m_nev) ? SUCCESSFUL : NOT_CONVERGING; + + return std::min(m_nev, nconv); + } + + /// + /// Returns the status of the computation. + /// The full list of enumeration values can be found in \ref Enumerations. + /// + int info() const { return m_info; } + + /// + /// Returns the number of iterations used in the computation. + /// + Index num_iterations() const { return m_niter; } + + /// + /// Returns the number of matrix operations used in the computation. + /// + Index num_operations() const { return m_nmatop; } + + /// + /// Returns the converged eigenvalues. + /// + /// \return A complex-valued vector containing the eigenvalues. + /// Returned vector type will be `Eigen::Vector, ...>`, depending on + /// the template parameter `Scalar` defined. + /// + ComplexVector eigenvalues() const + { + const Index nconv = m_ritz_conv.cast().sum(); + ComplexVector res(nconv); + + if (!nconv) + return res; + + Index j = 0; + for (Index i = 0; i < m_nev; i++) + { + if (m_ritz_conv[i]) + { + res[j] = m_ritz_val[i]; + j++; + } + } + + return res; + } + + /// + /// Returns the eigenvectors associated with the converged eigenvalues. + /// + /// \param nvec The number of eigenvectors to return. + /// + /// \return A complex-valued matrix containing the eigenvectors. + /// Returned matrix type will be `Eigen::Matrix, ...>`, + /// depending on the template parameter `Scalar` defined. + /// + ComplexMatrix eigenvectors(Index nvec) const + { + const Index nconv = m_ritz_conv.cast().sum(); + nvec = std::min(nvec, nconv); + ComplexMatrix res(m_n, nvec); + + if (!nvec) + return res; + + ComplexMatrix ritz_vec_conv(m_ncv, nvec); + Index j = 0; + for (Index i = 0; i < m_nev && j < nvec; i++) + { + if (m_ritz_conv[i]) + { + ritz_vec_conv.col(j).noalias() = m_ritz_vec.col(i); + j++; + } + } + + res.noalias() = m_fac.matrix_V() * ritz_vec_conv; + + return res; + } + + /// + /// Returns all converged eigenvectors. + /// + ComplexMatrix eigenvectors() const + { + return eigenvectors(m_nev); + } +}; + +} // namespace Spectra + +#endif // GEN_EIGS_BASE_H diff --git a/gtsam/3rdparty/Spectra/GenEigsComplexShiftSolver.h b/gtsam/3rdparty/Spectra/GenEigsComplexShiftSolver.h new file mode 100644 index 000000000..da7c1b422 --- /dev/null +++ b/gtsam/3rdparty/Spectra/GenEigsComplexShiftSolver.h @@ -0,0 +1,157 @@ +// Copyright (C) 2016-2019 Yixuan Qiu +// +// This Source Code Form is subject to the terms of the Mozilla +// Public License v. 2.0. If a copy of the MPL was not distributed +// with this file, You can obtain one at https://mozilla.org/MPL/2.0/. + +#ifndef GEN_EIGS_COMPLEX_SHIFT_SOLVER_H +#define GEN_EIGS_COMPLEX_SHIFT_SOLVER_H + +#include + +#include "GenEigsBase.h" +#include "Util/SelectionRule.h" +#include "MatOp/DenseGenComplexShiftSolve.h" + +namespace Spectra { + +/// +/// \ingroup EigenSolver +/// +/// This class implements the eigen solver for general real matrices with +/// a complex shift value in the **shift-and-invert mode**. The background +/// knowledge of the shift-and-invert mode can be found in the documentation +/// of the SymEigsShiftSolver class. +/// +/// \tparam Scalar The element type of the matrix. +/// Currently supported types are `float`, `double` and `long double`. +/// \tparam SelectionRule An enumeration value indicating the selection rule of +/// the shifted-and-inverted eigenvalues. +/// The full list of enumeration values can be found in +/// \ref Enumerations. +/// \tparam OpType The name of the matrix operation class. Users could either +/// use the DenseGenComplexShiftSolve wrapper class, or define their +/// own that implements all the public member functions as in +/// DenseGenComplexShiftSolve. +/// +template > +class GenEigsComplexShiftSolver : public GenEigsBase +{ +private: + typedef Eigen::Index Index; + typedef std::complex Complex; + typedef Eigen::Matrix Vector; + typedef Eigen::Matrix ComplexVector; + + const Scalar m_sigmar; + const Scalar m_sigmai; + + // First transform back the Ritz values, and then sort + void sort_ritzpair(int sort_rule) + { + using std::abs; + using std::sqrt; + using std::norm; + + // The eigenvalues we get from the iteration is + // nu = 0.5 * (1 / (lambda - sigma) + 1 / (lambda - conj(sigma))) + // So the eigenvalues of the original problem is + // 1 \pm sqrt(1 - 4 * nu^2 * sigmai^2) + // lambda = sigmar + ----------------------------------- + // 2 * nu + // We need to pick the correct root + // Let (lambdaj, vj) be the j-th eigen pair, then A * vj = lambdaj * vj + // and inv(A - r * I) * vj = 1 / (lambdaj - r) * vj + // where r is any shift value. + // We can use this identity to determine lambdaj + // + // op(v) computes Re(inv(A - r * I) * v) for any real v + // If r is real, then op(v) is also real. Let a = Re(vj), b = Im(vj), + // then op(vj) = op(a) + op(b) * i + // By comparing op(vj) and [1 / (lambdaj - r) * vj], we can determine + // which one is the correct root + + // Select a random shift value + SimpleRandom rng(0); + const Scalar shiftr = rng.random() * m_sigmar + rng.random(); + const Complex shift = Complex(shiftr, Scalar(0)); + this->m_op->set_shift(shiftr, Scalar(0)); + + // Calculate inv(A - r * I) * vj + Vector v_real(this->m_n), v_imag(this->m_n), OPv_real(this->m_n), OPv_imag(this->m_n); + const Scalar eps = Eigen::NumTraits::epsilon(); + for (Index i = 0; i < this->m_nev; i++) + { + v_real.noalias() = this->m_fac.matrix_V() * this->m_ritz_vec.col(i).real(); + v_imag.noalias() = this->m_fac.matrix_V() * this->m_ritz_vec.col(i).imag(); + this->m_op->perform_op(v_real.data(), OPv_real.data()); + this->m_op->perform_op(v_imag.data(), OPv_imag.data()); + + // Two roots computed from the quadratic equation + const Complex nu = this->m_ritz_val[i]; + const Complex root_part1 = m_sigmar + Scalar(0.5) / nu; + const Complex root_part2 = Scalar(0.5) * sqrt(Scalar(1) - Scalar(4) * m_sigmai * m_sigmai * (nu * nu)) / nu; + const Complex root1 = root_part1 + root_part2; + const Complex root2 = root_part1 - root_part2; + + // Test roots + Scalar err1 = Scalar(0), err2 = Scalar(0); + for (int k = 0; k < this->m_n; k++) + { + const Complex rhs1 = Complex(v_real[k], v_imag[k]) / (root1 - shift); + const Complex rhs2 = Complex(v_real[k], v_imag[k]) / (root2 - shift); + const Complex OPv = Complex(OPv_real[k], OPv_imag[k]); + err1 += norm(OPv - rhs1); + err2 += norm(OPv - rhs2); + } + + const Complex lambdaj = (err1 < err2) ? root1 : root2; + this->m_ritz_val[i] = lambdaj; + + if (abs(Eigen::numext::imag(lambdaj)) > eps) + { + this->m_ritz_val[i + 1] = Eigen::numext::conj(lambdaj); + i++; + } + else + { + this->m_ritz_val[i] = Complex(Eigen::numext::real(lambdaj), Scalar(0)); + } + } + + GenEigsBase::sort_ritzpair(sort_rule); + } + +public: + /// + /// Constructor to create a eigen solver object using the shift-and-invert mode. + /// + /// \param op Pointer to the matrix operation object. This class should implement + /// the complex shift-solve operation of \f$A\f$: calculating + /// \f$\mathrm{Re}\{(A-\sigma I)^{-1}v\}\f$ for any vector \f$v\f$. Users could either + /// create the object from the DenseGenComplexShiftSolve wrapper class, or + /// define their own that implements all the public member functions + /// as in DenseGenComplexShiftSolve. + /// \param nev Number of eigenvalues requested. This should satisfy \f$1\le nev \le n-2\f$, + /// where \f$n\f$ is the size of matrix. + /// \param ncv Parameter that controls the convergence speed of the algorithm. + /// Typically a larger `ncv` means faster convergence, but it may + /// also result in greater memory use and more matrix operations + /// in each iteration. This parameter must satisfy \f$nev+2 \le ncv \le n\f$, + /// and is advised to take \f$ncv \ge 2\cdot nev + 1\f$. + /// \param sigmar The real part of the shift. + /// \param sigmai The imaginary part of the shift. + /// + GenEigsComplexShiftSolver(OpType* op, Index nev, Index ncv, const Scalar& sigmar, const Scalar& sigmai) : + GenEigsBase(op, NULL, nev, ncv), + m_sigmar(sigmar), m_sigmai(sigmai) + { + this->m_op->set_shift(m_sigmar, m_sigmai); + } +}; + +} // namespace Spectra + +#endif // GEN_EIGS_COMPLEX_SHIFT_SOLVER_H diff --git a/gtsam/3rdparty/Spectra/GenEigsRealShiftSolver.h b/gtsam/3rdparty/Spectra/GenEigsRealShiftSolver.h new file mode 100644 index 000000000..6f28308f1 --- /dev/null +++ b/gtsam/3rdparty/Spectra/GenEigsRealShiftSolver.h @@ -0,0 +1,89 @@ +// Copyright (C) 2016-2019 Yixuan Qiu +// +// This Source Code Form is subject to the terms of the Mozilla +// Public License v. 2.0. If a copy of the MPL was not distributed +// with this file, You can obtain one at https://mozilla.org/MPL/2.0/. + +#ifndef GEN_EIGS_REAL_SHIFT_SOLVER_H +#define GEN_EIGS_REAL_SHIFT_SOLVER_H + +#include + +#include "GenEigsBase.h" +#include "Util/SelectionRule.h" +#include "MatOp/DenseGenRealShiftSolve.h" + +namespace Spectra { + +/// +/// \ingroup EigenSolver +/// +/// This class implements the eigen solver for general real matrices with +/// a real shift value in the **shift-and-invert mode**. The background +/// knowledge of the shift-and-invert mode can be found in the documentation +/// of the SymEigsShiftSolver class. +/// +/// \tparam Scalar The element type of the matrix. +/// Currently supported types are `float`, `double` and `long double`. +/// \tparam SelectionRule An enumeration value indicating the selection rule of +/// the shifted-and-inverted eigenvalues. +/// The full list of enumeration values can be found in +/// \ref Enumerations. +/// \tparam OpType The name of the matrix operation class. Users could either +/// use the wrapper classes such as DenseGenRealShiftSolve and +/// SparseGenRealShiftSolve, or define their +/// own that implements all the public member functions as in +/// DenseGenRealShiftSolve. +/// +template > +class GenEigsRealShiftSolver : public GenEigsBase +{ +private: + typedef Eigen::Index Index; + typedef std::complex Complex; + typedef Eigen::Array ComplexArray; + + const Scalar m_sigma; + + // First transform back the Ritz values, and then sort + void sort_ritzpair(int sort_rule) + { + // The eigenvalues we get from the iteration is nu = 1 / (lambda - sigma) + // So the eigenvalues of the original problem is lambda = 1 / nu + sigma + ComplexArray ritz_val_org = Scalar(1.0) / this->m_ritz_val.head(this->m_nev).array() + m_sigma; + this->m_ritz_val.head(this->m_nev) = ritz_val_org; + GenEigsBase::sort_ritzpair(sort_rule); + } + +public: + /// + /// Constructor to create a eigen solver object using the shift-and-invert mode. + /// + /// \param op Pointer to the matrix operation object. This class should implement + /// the shift-solve operation of \f$A\f$: calculating + /// \f$(A-\sigma I)^{-1}v\f$ for any vector \f$v\f$. Users could either + /// create the object from the wrapper class such as DenseGenRealShiftSolve, or + /// define their own that implements all the public member functions + /// as in DenseGenRealShiftSolve. + /// \param nev Number of eigenvalues requested. This should satisfy \f$1\le nev \le n-2\f$, + /// where \f$n\f$ is the size of matrix. + /// \param ncv Parameter that controls the convergence speed of the algorithm. + /// Typically a larger `ncv` means faster convergence, but it may + /// also result in greater memory use and more matrix operations + /// in each iteration. This parameter must satisfy \f$nev+2 \le ncv \le n\f$, + /// and is advised to take \f$ncv \ge 2\cdot nev + 1\f$. + /// \param sigma The real-valued shift. + /// + GenEigsRealShiftSolver(OpType* op, Index nev, Index ncv, Scalar sigma) : + GenEigsBase(op, NULL, nev, ncv), + m_sigma(sigma) + { + this->m_op->set_shift(m_sigma); + } +}; + +} // namespace Spectra + +#endif // GEN_EIGS_REAL_SHIFT_SOLVER_H diff --git a/gtsam/3rdparty/Spectra/GenEigsSolver.h b/gtsam/3rdparty/Spectra/GenEigsSolver.h new file mode 100644 index 000000000..3ead1dc4d --- /dev/null +++ b/gtsam/3rdparty/Spectra/GenEigsSolver.h @@ -0,0 +1,158 @@ +// Copyright (C) 2016-2019 Yixuan Qiu +// +// This Source Code Form is subject to the terms of the Mozilla +// Public License v. 2.0. If a copy of the MPL was not distributed +// with this file, You can obtain one at https://mozilla.org/MPL/2.0/. + +#ifndef GEN_EIGS_SOLVER_H +#define GEN_EIGS_SOLVER_H + +#include + +#include "GenEigsBase.h" +#include "Util/SelectionRule.h" +#include "MatOp/DenseGenMatProd.h" + +namespace Spectra { + +/// +/// \ingroup EigenSolver +/// +/// This class implements the eigen solver for general real matrices, i.e., +/// to solve \f$Ax=\lambda x\f$ for a possibly non-symmetric \f$A\f$ matrix. +/// +/// Most of the background information documented in the SymEigsSolver class +/// also applies to the GenEigsSolver class here, except that the eigenvalues +/// and eigenvectors of a general matrix can now be complex-valued. +/// +/// \tparam Scalar The element type of the matrix. +/// Currently supported types are `float`, `double` and `long double`. +/// \tparam SelectionRule An enumeration value indicating the selection rule of +/// the requested eigenvalues, for example `LARGEST_MAGN` +/// to retrieve eigenvalues with the largest magnitude. +/// The full list of enumeration values can be found in +/// \ref Enumerations. +/// \tparam OpType The name of the matrix operation class. Users could either +/// use the wrapper classes such as DenseGenMatProd and +/// SparseGenMatProd, or define their +/// own that implements all the public member functions as in +/// DenseGenMatProd. +/// +/// An example that illustrates the usage of GenEigsSolver is give below: +/// +/// \code{.cpp} +/// #include +/// #include +/// // is implicitly included +/// #include +/// +/// using namespace Spectra; +/// +/// int main() +/// { +/// // We are going to calculate the eigenvalues of M +/// Eigen::MatrixXd M = Eigen::MatrixXd::Random(10, 10); +/// +/// // Construct matrix operation object using the wrapper class +/// DenseGenMatProd op(M); +/// +/// // Construct eigen solver object, requesting the largest +/// // (in magnitude, or norm) three eigenvalues +/// GenEigsSolver< double, LARGEST_MAGN, DenseGenMatProd > eigs(&op, 3, 6); +/// +/// // Initialize and compute +/// eigs.init(); +/// int nconv = eigs.compute(); +/// +/// // Retrieve results +/// Eigen::VectorXcd evalues; +/// if(eigs.info() == SUCCESSFUL) +/// evalues = eigs.eigenvalues(); +/// +/// std::cout << "Eigenvalues found:\n" << evalues << std::endl; +/// +/// return 0; +/// } +/// \endcode +/// +/// And also an example for sparse matrices: +/// +/// \code{.cpp} +/// #include +/// #include +/// #include +/// #include +/// #include +/// +/// using namespace Spectra; +/// +/// int main() +/// { +/// // A band matrix with 1 on the main diagonal, 2 on the below-main subdiagonal, +/// // and 3 on the above-main subdiagonal +/// const int n = 10; +/// Eigen::SparseMatrix M(n, n); +/// M.reserve(Eigen::VectorXi::Constant(n, 3)); +/// for(int i = 0; i < n; i++) +/// { +/// M.insert(i, i) = 1.0; +/// if(i > 0) +/// M.insert(i - 1, i) = 3.0; +/// if(i < n - 1) +/// M.insert(i + 1, i) = 2.0; +/// } +/// +/// // Construct matrix operation object using the wrapper class SparseGenMatProd +/// SparseGenMatProd op(M); +/// +/// // Construct eigen solver object, requesting the largest three eigenvalues +/// GenEigsSolver< double, LARGEST_MAGN, SparseGenMatProd > eigs(&op, 3, 6); +/// +/// // Initialize and compute +/// eigs.init(); +/// int nconv = eigs.compute(); +/// +/// // Retrieve results +/// Eigen::VectorXcd evalues; +/// if(eigs.info() == SUCCESSFUL) +/// evalues = eigs.eigenvalues(); +/// +/// std::cout << "Eigenvalues found:\n" << evalues << std::endl; +/// +/// return 0; +/// } +/// \endcode +template > +class GenEigsSolver : public GenEigsBase +{ +private: + typedef Eigen::Index Index; + +public: + /// + /// Constructor to create a solver object. + /// + /// \param op Pointer to the matrix operation object, which should implement + /// the matrix-vector multiplication operation of \f$A\f$: + /// calculating \f$Av\f$ for any vector \f$v\f$. Users could either + /// create the object from the wrapper class such as DenseGenMatProd, or + /// define their own that implements all the public member functions + /// as in DenseGenMatProd. + /// \param nev Number of eigenvalues requested. This should satisfy \f$1\le nev \le n-2\f$, + /// where \f$n\f$ is the size of matrix. + /// \param ncv Parameter that controls the convergence speed of the algorithm. + /// Typically a larger `ncv` means faster convergence, but it may + /// also result in greater memory use and more matrix operations + /// in each iteration. This parameter must satisfy \f$nev+2 \le ncv \le n\f$, + /// and is advised to take \f$ncv \ge 2\cdot nev + 1\f$. + /// + GenEigsSolver(OpType* op, Index nev, Index ncv) : + GenEigsBase(op, NULL, nev, ncv) + {} +}; + +} // namespace Spectra + +#endif // GEN_EIGS_SOLVER_H diff --git a/gtsam/3rdparty/Spectra/LinAlg/Arnoldi.h b/gtsam/3rdparty/Spectra/LinAlg/Arnoldi.h new file mode 100644 index 000000000..730ba9556 --- /dev/null +++ b/gtsam/3rdparty/Spectra/LinAlg/Arnoldi.h @@ -0,0 +1,284 @@ +// Copyright (C) 2018-2019 Yixuan Qiu +// +// This Source Code Form is subject to the terms of the Mozilla +// Public License v. 2.0. If a copy of the MPL was not distributed +// with this file, You can obtain one at https://mozilla.org/MPL/2.0/. + +#ifndef ARNOLDI_H +#define ARNOLDI_H + +#include +#include // std::sqrt +#include // std::invalid_argument +#include // std::stringstream + +#include "../MatOp/internal/ArnoldiOp.h" +#include "../Util/TypeTraits.h" +#include "../Util/SimpleRandom.h" +#include "UpperHessenbergQR.h" +#include "DoubleShiftQR.h" + +namespace Spectra { + +// Arnoldi factorization A * V = V * H + f * e' +// A: n x n +// V: n x k +// H: k x k +// f: n x 1 +// e: [0, ..., 0, 1] +// V and H are allocated of dimension m, so the maximum value of k is m +template +class Arnoldi +{ +private: + typedef Eigen::Index Index; + typedef Eigen::Matrix Matrix; + typedef Eigen::Matrix Vector; + typedef Eigen::Map MapMat; + typedef Eigen::Map MapVec; + typedef Eigen::Map MapConstMat; + typedef Eigen::Map MapConstVec; + +protected: + // clang-format off + ArnoldiOpType m_op; // Operators for the Arnoldi factorization + + const Index m_n; // dimension of A + const Index m_m; // maximum dimension of subspace V + Index m_k; // current dimension of subspace V + + Matrix m_fac_V; // V matrix in the Arnoldi factorization + Matrix m_fac_H; // H matrix in the Arnoldi factorization + Vector m_fac_f; // residual in the Arnoldi factorization + Scalar m_beta; // ||f||, B-norm of f + + const Scalar m_near_0; // a very small value, but 1.0 / m_near_0 does not overflow + // ~= 1e-307 for the "double" type + const Scalar m_eps; // the machine precision, ~= 1e-16 for the "double" type + // clang-format on + + // Given orthonormal basis functions V, find a nonzero vector f such that V'Bf = 0 + // Assume that f has been properly allocated + void expand_basis(MapConstMat& V, const Index seed, Vector& f, Scalar& fnorm) + { + using std::sqrt; + + const Scalar thresh = m_eps * sqrt(Scalar(m_n)); + Vector Vf(V.cols()); + for (Index iter = 0; iter < 5; iter++) + { + // Randomly generate a new vector and orthogonalize it against V + SimpleRandom rng(seed + 123 * iter); + f.noalias() = rng.random_vec(m_n); + // f <- f - V * V'Bf, so that f is orthogonal to V in B-norm + m_op.trans_product(V, f, Vf); + f.noalias() -= V * Vf; + // fnorm <- ||f|| + fnorm = m_op.norm(f); + + // If fnorm is too close to zero, we try a new random vector, + // otherwise return the result + if (fnorm >= thresh) + return; + } + } + +public: + Arnoldi(const ArnoldiOpType& op, Index m) : + m_op(op), m_n(op.rows()), m_m(m), m_k(0), + m_near_0(TypeTraits::min() * Scalar(10)), + m_eps(Eigen::NumTraits::epsilon()) + {} + + virtual ~Arnoldi() {} + + // Const-reference to internal structures + const Matrix& matrix_V() const { return m_fac_V; } + const Matrix& matrix_H() const { return m_fac_H; } + const Vector& vector_f() const { return m_fac_f; } + Scalar f_norm() const { return m_beta; } + Index subspace_dim() const { return m_k; } + + // Initialize with an operator and an initial vector + void init(MapConstVec& v0, Index& op_counter) + { + m_fac_V.resize(m_n, m_m); + m_fac_H.resize(m_m, m_m); + m_fac_f.resize(m_n); + m_fac_H.setZero(); + + // Verify the initial vector + const Scalar v0norm = m_op.norm(v0); + if (v0norm < m_near_0) + throw std::invalid_argument("initial residual vector cannot be zero"); + + // Points to the first column of V + MapVec v(m_fac_V.data(), m_n); + + // Normalize + v.noalias() = v0 / v0norm; + + // Compute H and f + Vector w(m_n); + m_op.perform_op(v.data(), w.data()); + op_counter++; + + m_fac_H(0, 0) = m_op.inner_product(v, w); + m_fac_f.noalias() = w - v * m_fac_H(0, 0); + + // In some cases f is zero in exact arithmetics, but due to rounding errors + // it may contain tiny fluctuations. When this happens, we force f to be zero + if (m_fac_f.cwiseAbs().maxCoeff() < m_eps) + { + m_fac_f.setZero(); + m_beta = Scalar(0); + } + else + { + m_beta = m_op.norm(m_fac_f); + } + + // Indicate that this is a step-1 factorization + m_k = 1; + } + + // Arnoldi factorization starting from step-k + virtual void factorize_from(Index from_k, Index to_m, Index& op_counter) + { + using std::sqrt; + + if (to_m <= from_k) + return; + + if (from_k > m_k) + { + std::stringstream msg; + msg << "Arnoldi: from_k (= " << from_k << ") is larger than the current subspace dimension (= " << m_k << ")"; + throw std::invalid_argument(msg.str()); + } + + const Scalar beta_thresh = m_eps * sqrt(Scalar(m_n)); + + // Pre-allocate vectors + Vector Vf(to_m); + Vector w(m_n); + + // Keep the upperleft k x k submatrix of H and set other elements to 0 + m_fac_H.rightCols(m_m - from_k).setZero(); + m_fac_H.block(from_k, 0, m_m - from_k, from_k).setZero(); + + for (Index i = from_k; i <= to_m - 1; i++) + { + bool restart = false; + // If beta = 0, then the next V is not full rank + // We need to generate a new residual vector that is orthogonal + // to the current V, which we call a restart + if (m_beta < m_near_0) + { + MapConstMat V(m_fac_V.data(), m_n, i); // The first i columns + expand_basis(V, 2 * i, m_fac_f, m_beta); + restart = true; + } + + // v <- f / ||f|| + m_fac_V.col(i).noalias() = m_fac_f / m_beta; // The (i+1)-th column + + // Note that H[i+1, i] equals to the unrestarted beta + m_fac_H(i, i - 1) = restart ? Scalar(0) : m_beta; + + // w <- A * v, v = m_fac_V.col(i) + m_op.perform_op(&m_fac_V(0, i), w.data()); + op_counter++; + + const Index i1 = i + 1; + // First i+1 columns of V + MapConstMat Vs(m_fac_V.data(), m_n, i1); + // h = m_fac_H(0:i, i) + MapVec h(&m_fac_H(0, i), i1); + // h <- V'Bw + m_op.trans_product(Vs, w, h); + + // f <- w - V * h + m_fac_f.noalias() = w - Vs * h; + m_beta = m_op.norm(m_fac_f); + + if (m_beta > Scalar(0.717) * m_op.norm(h)) + continue; + + // f/||f|| is going to be the next column of V, so we need to test + // whether V'B(f/||f||) ~= 0 + m_op.trans_product(Vs, m_fac_f, Vf.head(i1)); + Scalar ortho_err = Vf.head(i1).cwiseAbs().maxCoeff(); + // If not, iteratively correct the residual + int count = 0; + while (count < 5 && ortho_err > m_eps * m_beta) + { + // There is an edge case: when beta=||f|| is close to zero, f mostly consists + // of noises of rounding errors, so the test [ortho_err < eps * beta] is very + // likely to fail. In particular, if beta=0, then the test is ensured to fail. + // Hence when this happens, we force f to be zero, and then restart in the + // next iteration. + if (m_beta < beta_thresh) + { + m_fac_f.setZero(); + m_beta = Scalar(0); + break; + } + + // f <- f - V * Vf + m_fac_f.noalias() -= Vs * Vf.head(i1); + // h <- h + Vf + h.noalias() += Vf.head(i1); + // beta <- ||f|| + m_beta = m_op.norm(m_fac_f); + + m_op.trans_product(Vs, m_fac_f, Vf.head(i1)); + ortho_err = Vf.head(i1).cwiseAbs().maxCoeff(); + count++; + } + } + + // Indicate that this is a step-m factorization + m_k = to_m; + } + + // Apply H -> Q'HQ, where Q is from a double shift QR decomposition + void compress_H(const DoubleShiftQR& decomp) + { + decomp.matrix_QtHQ(m_fac_H); + m_k -= 2; + } + + // Apply H -> Q'HQ, where Q is from an upper Hessenberg QR decomposition + void compress_H(const UpperHessenbergQR& decomp) + { + decomp.matrix_QtHQ(m_fac_H); + m_k--; + } + + // Apply V -> VQ and compute the new f. + // Should be called after compress_H(), since m_k is updated there. + // Only need to update the first k+1 columns of V + // The first (m - k + i) elements of the i-th column of Q are non-zero, + // and the rest are zero + void compress_V(const Matrix& Q) + { + Matrix Vs(m_n, m_k + 1); + for (Index i = 0; i < m_k; i++) + { + const Index nnz = m_m - m_k + i + 1; + MapConstVec q(&Q(0, i), nnz); + Vs.col(i).noalias() = m_fac_V.leftCols(nnz) * q; + } + Vs.col(m_k).noalias() = m_fac_V * Q.col(m_k); + m_fac_V.leftCols(m_k + 1).noalias() = Vs; + + Vector fk = m_fac_f * Q(m_m - 1, m_k - 1) + m_fac_V.col(m_k) * m_fac_H(m_k, m_k - 1); + m_fac_f.swap(fk); + m_beta = m_op.norm(m_fac_f); + } +}; + +} // namespace Spectra + +#endif // ARNOLDI_H diff --git a/gtsam/3rdparty/Spectra/LinAlg/BKLDLT.h b/gtsam/3rdparty/Spectra/LinAlg/BKLDLT.h new file mode 100644 index 000000000..2345e0fda --- /dev/null +++ b/gtsam/3rdparty/Spectra/LinAlg/BKLDLT.h @@ -0,0 +1,530 @@ +// Copyright (C) 2019 Yixuan Qiu +// +// This Source Code Form is subject to the terms of the Mozilla +// Public License v. 2.0. If a copy of the MPL was not distributed +// with this file, You can obtain one at https://mozilla.org/MPL/2.0/. + +#ifndef BK_LDLT_H +#define BK_LDLT_H + +#include +#include +#include + +#include "../Util/CompInfo.h" + +namespace Spectra { + +// Bunch-Kaufman LDLT decomposition +// References: +// 1. Bunch, J. R., & Kaufman, L. (1977). Some stable methods for calculating inertia and solving symmetric linear systems. +// Mathematics of computation, 31(137), 163-179. +// 2. Golub, G. H., & Van Loan, C. F. (2012). Matrix computations (Vol. 3). JHU press. Section 4.4. +// 3. Bunch-Parlett diagonal pivoting +// 4. Ashcraft, C., Grimes, R. G., & Lewis, J. G. (1998). Accurate symmetric indefinite linear equation solvers. +// SIAM Journal on Matrix Analysis and Applications, 20(2), 513-561. +template +class BKLDLT +{ +private: + typedef Eigen::Index Index; + typedef Eigen::Matrix Matrix; + typedef Eigen::Matrix Vector; + typedef Eigen::Map MapVec; + typedef Eigen::Map MapConstVec; + + typedef Eigen::Matrix IntVector; + typedef Eigen::Ref GenericVector; + typedef Eigen::Ref GenericMatrix; + typedef const Eigen::Ref ConstGenericMatrix; + typedef const Eigen::Ref ConstGenericVector; + + Index m_n; + Vector m_data; // storage for a lower-triangular matrix + std::vector m_colptr; // pointers to columns + IntVector m_perm; // [-2, -1, 3, 1, 4, 5]: 0 <-> 2, 1 <-> 1, 2 <-> 3, 3 <-> 1, 4 <-> 4, 5 <-> 5 + std::vector > m_permc; // compressed version of m_perm: [(0, 2), (2, 3), (3, 1)] + + bool m_computed; + int m_info; + + // Access to elements + // Pointer to the k-th column + Scalar* col_pointer(Index k) { return m_colptr[k]; } + // A[i, j] -> m_colptr[j][i - j], i >= j + Scalar& coeff(Index i, Index j) { return m_colptr[j][i - j]; } + const Scalar& coeff(Index i, Index j) const { return m_colptr[j][i - j]; } + // A[i, i] -> m_colptr[i][0] + Scalar& diag_coeff(Index i) { return m_colptr[i][0]; } + const Scalar& diag_coeff(Index i) const { return m_colptr[i][0]; } + + // Compute column pointers + void compute_pointer() + { + m_colptr.clear(); + m_colptr.reserve(m_n); + Scalar* head = m_data.data(); + + for (Index i = 0; i < m_n; i++) + { + m_colptr.push_back(head); + head += (m_n - i); + } + } + + // Copy mat - shift * I to m_data + void copy_data(ConstGenericMatrix& mat, int uplo, const Scalar& shift) + { + if (uplo == Eigen::Lower) + { + for (Index j = 0; j < m_n; j++) + { + const Scalar* begin = &mat.coeffRef(j, j); + const Index len = m_n - j; + std::copy(begin, begin + len, col_pointer(j)); + diag_coeff(j) -= shift; + } + } + else + { + Scalar* dest = m_data.data(); + for (Index i = 0; i < m_n; i++) + { + for (Index j = i; j < m_n; j++, dest++) + { + *dest = mat.coeff(i, j); + } + diag_coeff(i) -= shift; + } + } + } + + // Compute compressed permutations + void compress_permutation() + { + for (Index i = 0; i < m_n; i++) + { + // Recover the permutation action + const Index perm = (m_perm[i] >= 0) ? (m_perm[i]) : (-m_perm[i] - 1); + if (perm != i) + m_permc.push_back(std::make_pair(i, perm)); + } + } + + // Working on the A[k:end, k:end] submatrix + // Exchange k <-> r + // Assume r >= k + void pivoting_1x1(Index k, Index r) + { + // No permutation + if (k == r) + { + m_perm[k] = r; + return; + } + + // A[k, k] <-> A[r, r] + std::swap(diag_coeff(k), diag_coeff(r)); + + // A[(r+1):end, k] <-> A[(r+1):end, r] + std::swap_ranges(&coeff(r + 1, k), col_pointer(k + 1), &coeff(r + 1, r)); + + // A[(k+1):(r-1), k] <-> A[r, (k+1):(r-1)] + Scalar* src = &coeff(k + 1, k); + for (Index j = k + 1; j < r; j++, src++) + { + std::swap(*src, coeff(r, j)); + } + + m_perm[k] = r; + } + + // Working on the A[k:end, k:end] submatrix + // Exchange [k+1, k] <-> [r, p] + // Assume p >= k, r >= k+1 + void pivoting_2x2(Index k, Index r, Index p) + { + pivoting_1x1(k, p); + pivoting_1x1(k + 1, r); + + // A[k+1, k] <-> A[r, k] + std::swap(coeff(k + 1, k), coeff(r, k)); + + // Use negative signs to indicate a 2x2 block + // Also minus one to distinguish a negative zero from a positive zero + m_perm[k] = -m_perm[k] - 1; + m_perm[k + 1] = -m_perm[k + 1] - 1; + } + + // A[r1, c1:c2] <-> A[r2, c1:c2] + // Assume r2 >= r1 > c2 >= c1 + void interchange_rows(Index r1, Index r2, Index c1, Index c2) + { + if (r1 == r2) + return; + + for (Index j = c1; j <= c2; j++) + { + std::swap(coeff(r1, j), coeff(r2, j)); + } + } + + // lambda = |A[r, k]| = max{|A[k+1, k]|, ..., |A[end, k]|} + // Largest (in magnitude) off-diagonal element in the first column of the current reduced matrix + // r is the row index + // Assume k < end + Scalar find_lambda(Index k, Index& r) + { + using std::abs; + + const Scalar* head = col_pointer(k); // => A[k, k] + const Scalar* end = col_pointer(k + 1); + // Start with r=k+1, lambda=A[k+1, k] + r = k + 1; + Scalar lambda = abs(head[1]); + // Scan remaining elements + for (const Scalar* ptr = head + 2; ptr < end; ptr++) + { + const Scalar abs_elem = abs(*ptr); + if (lambda < abs_elem) + { + lambda = abs_elem; + r = k + (ptr - head); + } + } + + return lambda; + } + + // sigma = |A[p, r]| = max {|A[k, r]|, ..., |A[end, r]|} \ {A[r, r]} + // Largest (in magnitude) off-diagonal element in the r-th column of the current reduced matrix + // p is the row index + // Assume k < r < end + Scalar find_sigma(Index k, Index r, Index& p) + { + using std::abs; + + // First search A[r+1, r], ..., A[end, r], which has the same task as find_lambda() + // If r == end, we skip this search + Scalar sigma = Scalar(-1); + if (r < m_n - 1) + sigma = find_lambda(r, p); + + // Then search A[k, r], ..., A[r-1, r], which maps to A[r, k], ..., A[r, r-1] + for (Index j = k; j < r; j++) + { + const Scalar abs_elem = abs(coeff(r, j)); + if (sigma < abs_elem) + { + sigma = abs_elem; + p = j; + } + } + + return sigma; + } + + // Generate permutations and apply to A + // Return true if the resulting pivoting is 1x1, and false if 2x2 + bool permutate_mat(Index k, const Scalar& alpha) + { + using std::abs; + + Index r = k, p = k; + const Scalar lambda = find_lambda(k, r); + + // If lambda=0, no need to interchange + if (lambda > Scalar(0)) + { + const Scalar abs_akk = abs(diag_coeff(k)); + // If |A[k, k]| >= alpha * lambda, no need to interchange + if (abs_akk < alpha * lambda) + { + const Scalar sigma = find_sigma(k, r, p); + + // If sigma * |A[k, k]| >= alpha * lambda^2, no need to interchange + if (sigma * abs_akk < alpha * lambda * lambda) + { + if (abs_akk >= alpha * sigma) + { + // Permutation on A + pivoting_1x1(k, r); + + // Permutation on L + interchange_rows(k, r, 0, k - 1); + return true; + } + else + { + // There are two versions of permutation here + // 1. A[k+1, k] <-> A[r, k] + // 2. A[k+1, k] <-> A[r, p], where p >= k and r >= k+1 + // + // Version 1 and 2 are used by Ref[1] and Ref[2], respectively + + // Version 1 implementation + p = k; + + // Version 2 implementation + // [r, p] and [p, r] are symmetric, but we need to make sure + // p >= k and r >= k+1, so it is safe to always make r > p + // One exception is when min{r,p} == k+1, in which case we make + // r = k+1, so that only one permutation needs to be performed + /* const Index rp_min = std::min(r, p); + const Index rp_max = std::max(r, p); + if(rp_min == k + 1) + { + r = rp_min; p = rp_max; + } else { + r = rp_max; p = rp_min; + } */ + + // Right now we use Version 1 since it reduces the overhead of interchange + + // Permutation on A + pivoting_2x2(k, r, p); + // Permutation on L + interchange_rows(k, p, 0, k - 1); + interchange_rows(k + 1, r, 0, k - 1); + return false; + } + } + } + } + + return true; + } + + // E = [e11, e12] + // [e21, e22] + // Overwrite E with inv(E) + void inverse_inplace_2x2(Scalar& e11, Scalar& e21, Scalar& e22) const + { + // inv(E) = [d11, d12], d11 = e22/delta, d21 = -e21/delta, d22 = e11/delta + // [d21, d22] + const Scalar delta = e11 * e22 - e21 * e21; + std::swap(e11, e22); + e11 /= delta; + e22 /= delta; + e21 = -e21 / delta; + } + + // Return value is the status, SUCCESSFUL/NUMERICAL_ISSUE + int gaussian_elimination_1x1(Index k) + { + // D = 1 / A[k, k] + const Scalar akk = diag_coeff(k); + // Return NUMERICAL_ISSUE if not invertible + if (akk == Scalar(0)) + return NUMERICAL_ISSUE; + + diag_coeff(k) = Scalar(1) / akk; + + // B -= l * l' / A[k, k], B := A[(k+1):end, (k+1):end], l := L[(k+1):end, k] + Scalar* lptr = col_pointer(k) + 1; + const Index ldim = m_n - k - 1; + MapVec l(lptr, ldim); + for (Index j = 0; j < ldim; j++) + { + MapVec(col_pointer(j + k + 1), ldim - j).noalias() -= (lptr[j] / akk) * l.tail(ldim - j); + } + + // l /= A[k, k] + l /= akk; + + return SUCCESSFUL; + } + + // Return value is the status, SUCCESSFUL/NUMERICAL_ISSUE + int gaussian_elimination_2x2(Index k) + { + // D = inv(E) + Scalar& e11 = diag_coeff(k); + Scalar& e21 = coeff(k + 1, k); + Scalar& e22 = diag_coeff(k + 1); + // Return NUMERICAL_ISSUE if not invertible + if (e11 * e22 - e21 * e21 == Scalar(0)) + return NUMERICAL_ISSUE; + + inverse_inplace_2x2(e11, e21, e22); + + // X = l * inv(E), l := L[(k+2):end, k:(k+1)] + Scalar* l1ptr = &coeff(k + 2, k); + Scalar* l2ptr = &coeff(k + 2, k + 1); + const Index ldim = m_n - k - 2; + MapVec l1(l1ptr, ldim), l2(l2ptr, ldim); + + Eigen::Matrix X(ldim, 2); + X.col(0).noalias() = l1 * e11 + l2 * e21; + X.col(1).noalias() = l1 * e21 + l2 * e22; + + // B -= l * inv(E) * l' = X * l', B = A[(k+2):end, (k+2):end] + for (Index j = 0; j < ldim; j++) + { + MapVec(col_pointer(j + k + 2), ldim - j).noalias() -= (X.col(0).tail(ldim - j) * l1ptr[j] + X.col(1).tail(ldim - j) * l2ptr[j]); + } + + // l = X + l1.noalias() = X.col(0); + l2.noalias() = X.col(1); + + return SUCCESSFUL; + } + +public: + BKLDLT() : + m_n(0), m_computed(false), m_info(NOT_COMPUTED) + {} + + // Factorize mat - shift * I + BKLDLT(ConstGenericMatrix& mat, int uplo = Eigen::Lower, const Scalar& shift = Scalar(0)) : + m_n(mat.rows()), m_computed(false), m_info(NOT_COMPUTED) + { + compute(mat, uplo, shift); + } + + void compute(ConstGenericMatrix& mat, int uplo = Eigen::Lower, const Scalar& shift = Scalar(0)) + { + using std::abs; + + m_n = mat.rows(); + if (m_n != mat.cols()) + throw std::invalid_argument("BKLDLT: matrix must be square"); + + m_perm.setLinSpaced(m_n, 0, m_n - 1); + m_permc.clear(); + + // Copy data + m_data.resize((m_n * (m_n + 1)) / 2); + compute_pointer(); + copy_data(mat, uplo, shift); + + const Scalar alpha = (1.0 + std::sqrt(17.0)) / 8.0; + Index k = 0; + for (k = 0; k < m_n - 1; k++) + { + // 1. Interchange rows and columns of A, and save the result to m_perm + bool is_1x1 = permutate_mat(k, alpha); + + // 2. Gaussian elimination + if (is_1x1) + { + m_info = gaussian_elimination_1x1(k); + } + else + { + m_info = gaussian_elimination_2x2(k); + k++; + } + + // 3. Check status + if (m_info != SUCCESSFUL) + break; + } + // Invert the last 1x1 block if it exists + if (k == m_n - 1) + { + const Scalar akk = diag_coeff(k); + if (akk == Scalar(0)) + m_info = NUMERICAL_ISSUE; + + diag_coeff(k) = Scalar(1) / diag_coeff(k); + } + + compress_permutation(); + + m_computed = true; + } + + // Solve Ax=b + void solve_inplace(GenericVector b) const + { + if (!m_computed) + throw std::logic_error("BKLDLT: need to call compute() first"); + + // PAP' = LDL' + // 1. b -> Pb + Scalar* x = b.data(); + MapVec res(x, m_n); + Index npermc = m_permc.size(); + for (Index i = 0; i < npermc; i++) + { + std::swap(x[m_permc[i].first], x[m_permc[i].second]); + } + + // 2. Lz = Pb + // If m_perm[end] < 0, then end with m_n - 3, otherwise end with m_n - 2 + const Index end = (m_perm[m_n - 1] < 0) ? (m_n - 3) : (m_n - 2); + for (Index i = 0; i <= end; i++) + { + const Index b1size = m_n - i - 1; + const Index b2size = b1size - 1; + if (m_perm[i] >= 0) + { + MapConstVec l(&coeff(i + 1, i), b1size); + res.segment(i + 1, b1size).noalias() -= l * x[i]; + } + else + { + MapConstVec l1(&coeff(i + 2, i), b2size); + MapConstVec l2(&coeff(i + 2, i + 1), b2size); + res.segment(i + 2, b2size).noalias() -= (l1 * x[i] + l2 * x[i + 1]); + i++; + } + } + + // 3. Dw = z + for (Index i = 0; i < m_n; i++) + { + const Scalar e11 = diag_coeff(i); + if (m_perm[i] >= 0) + { + x[i] *= e11; + } + else + { + const Scalar e21 = coeff(i + 1, i), e22 = diag_coeff(i + 1); + const Scalar wi = x[i] * e11 + x[i + 1] * e21; + x[i + 1] = x[i] * e21 + x[i + 1] * e22; + x[i] = wi; + i++; + } + } + + // 4. L'y = w + // If m_perm[end] < 0, then start with m_n - 3, otherwise start with m_n - 2 + Index i = (m_perm[m_n - 1] < 0) ? (m_n - 3) : (m_n - 2); + for (; i >= 0; i--) + { + const Index ldim = m_n - i - 1; + MapConstVec l(&coeff(i + 1, i), ldim); + x[i] -= res.segment(i + 1, ldim).dot(l); + + if (m_perm[i] < 0) + { + MapConstVec l2(&coeff(i + 1, i - 1), ldim); + x[i - 1] -= res.segment(i + 1, ldim).dot(l2); + i--; + } + } + + // 5. x = P'y + for (Index i = npermc - 1; i >= 0; i--) + { + std::swap(x[m_permc[i].first], x[m_permc[i].second]); + } + } + + Vector solve(ConstGenericVector& b) const + { + Vector res = b; + solve_inplace(res); + return res; + } + + int info() const { return m_info; } +}; + +} // namespace Spectra + +#endif // BK_LDLT_H diff --git a/gtsam/3rdparty/Spectra/LinAlg/DoubleShiftQR.h b/gtsam/3rdparty/Spectra/LinAlg/DoubleShiftQR.h new file mode 100644 index 000000000..2845688b4 --- /dev/null +++ b/gtsam/3rdparty/Spectra/LinAlg/DoubleShiftQR.h @@ -0,0 +1,384 @@ +// Copyright (C) 2016-2019 Yixuan Qiu +// +// This Source Code Form is subject to the terms of the Mozilla +// Public License v. 2.0. If a copy of the MPL was not distributed +// with this file, You can obtain one at https://mozilla.org/MPL/2.0/. + +#ifndef DOUBLE_SHIFT_QR_H +#define DOUBLE_SHIFT_QR_H + +#include +#include // std::vector +#include // std::min, std::fill, std::copy +#include // std::abs, std::sqrt, std::pow +#include // std::invalid_argument, std::logic_error + +#include "../Util/TypeTraits.h" + +namespace Spectra { + +template +class DoubleShiftQR +{ +private: + typedef Eigen::Index Index; + typedef Eigen::Matrix Matrix; + typedef Eigen::Matrix Matrix3X; + typedef Eigen::Matrix Vector; + typedef Eigen::Array IntArray; + + typedef Eigen::Ref GenericMatrix; + typedef const Eigen::Ref ConstGenericMatrix; + + Index m_n; // Dimension of the matrix + Matrix m_mat_H; // A copy of the matrix to be factorized + Scalar m_shift_s; // Shift constant + Scalar m_shift_t; // Shift constant + Matrix3X m_ref_u; // Householder reflectors + IntArray m_ref_nr; // How many rows does each reflector affects + // 3 - A general reflector + // 2 - A Givens rotation + // 1 - An identity transformation + const Scalar m_near_0; // a very small value, but 1.0 / m_safe_min does not overflow + // ~= 1e-307 for the "double" type + const Scalar m_eps; // the machine precision, + // e.g. ~= 1e-16 for the "double" type + const Scalar m_eps_rel; + const Scalar m_eps_abs; + bool m_computed; // Whether matrix has been factorized + + void compute_reflector(const Scalar& x1, const Scalar& x2, const Scalar& x3, Index ind) + { + using std::abs; + + Scalar* u = &m_ref_u.coeffRef(0, ind); + unsigned char* nr = m_ref_nr.data(); + // In general case the reflector affects 3 rows + nr[ind] = 3; + Scalar x2x3 = Scalar(0); + // If x3 is zero, decrease nr by 1 + if (abs(x3) < m_near_0) + { + // If x2 is also zero, nr will be 1, and we can exit this function + if (abs(x2) < m_near_0) + { + nr[ind] = 1; + return; + } + else + { + nr[ind] = 2; + } + x2x3 = abs(x2); + } + else + { + x2x3 = Eigen::numext::hypot(x2, x3); + } + + // x1' = x1 - rho * ||x|| + // rho = -sign(x1), if x1 == 0, we choose rho = 1 + Scalar x1_new = x1 - ((x1 <= 0) - (x1 > 0)) * Eigen::numext::hypot(x1, x2x3); + Scalar x_norm = Eigen::numext::hypot(x1_new, x2x3); + // Double check the norm of new x + if (x_norm < m_near_0) + { + nr[ind] = 1; + return; + } + u[0] = x1_new / x_norm; + u[1] = x2 / x_norm; + u[2] = x3 / x_norm; + } + + void compute_reflector(const Scalar* x, Index ind) + { + compute_reflector(x[0], x[1], x[2], ind); + } + + // Update the block X = H(il:iu, il:iu) + void update_block(Index il, Index iu) + { + // Block size + const Index bsize = iu - il + 1; + + // If block size == 1, there is no need to apply reflectors + if (bsize == 1) + { + m_ref_nr.coeffRef(il) = 1; + return; + } + + const Scalar x00 = m_mat_H.coeff(il, il), + x01 = m_mat_H.coeff(il, il + 1), + x10 = m_mat_H.coeff(il + 1, il), + x11 = m_mat_H.coeff(il + 1, il + 1); + // m00 = x00 * (x00 - s) + x01 * x10 + t + const Scalar m00 = x00 * (x00 - m_shift_s) + x01 * x10 + m_shift_t; + // m10 = x10 * (x00 + x11 - s) + const Scalar m10 = x10 * (x00 + x11 - m_shift_s); + + // For block size == 2, do a Givens rotation on M = X * X - s * X + t * I + if (bsize == 2) + { + // This causes nr=2 + compute_reflector(m00, m10, 0, il); + // Apply the reflector to X + apply_PX(m_mat_H.block(il, il, 2, m_n - il), m_n, il); + apply_XP(m_mat_H.block(0, il, il + 2, 2), m_n, il); + + m_ref_nr.coeffRef(il + 1) = 1; + return; + } + + // For block size >=3, use the regular strategy + // m20 = x21 * x10 + const Scalar m20 = m_mat_H.coeff(il + 2, il + 1) * m_mat_H.coeff(il + 1, il); + compute_reflector(m00, m10, m20, il); + + // Apply the first reflector + apply_PX(m_mat_H.block(il, il, 3, m_n - il), m_n, il); + apply_XP(m_mat_H.block(0, il, il + std::min(bsize, Index(4)), 3), m_n, il); + + // Calculate the following reflectors + // If entering this loop, block size is at least 4. + for (Index i = 1; i < bsize - 2; i++) + { + compute_reflector(&m_mat_H.coeffRef(il + i, il + i - 1), il + i); + // Apply the reflector to X + apply_PX(m_mat_H.block(il + i, il + i - 1, 3, m_n - il - i + 1), m_n, il + i); + apply_XP(m_mat_H.block(0, il + i, il + std::min(bsize, Index(i + 4)), 3), m_n, il + i); + } + + // The last reflector + // This causes nr=2 + compute_reflector(m_mat_H.coeff(iu - 1, iu - 2), m_mat_H.coeff(iu, iu - 2), 0, iu - 1); + // Apply the reflector to X + apply_PX(m_mat_H.block(iu - 1, iu - 2, 2, m_n - iu + 2), m_n, iu - 1); + apply_XP(m_mat_H.block(0, iu - 1, il + bsize, 2), m_n, iu - 1); + + m_ref_nr.coeffRef(iu) = 1; + } + + // P = I - 2 * u * u' = P' + // PX = X - 2 * u * (u'X) + void apply_PX(GenericMatrix X, Index stride, Index u_ind) const + { + const Index nr = m_ref_nr.coeff(u_ind); + if (nr == 1) + return; + + const Scalar u0 = m_ref_u.coeff(0, u_ind), + u1 = m_ref_u.coeff(1, u_ind); + const Scalar u0_2 = Scalar(2) * u0, + u1_2 = Scalar(2) * u1; + + const Index nrow = X.rows(); + const Index ncol = X.cols(); + + Scalar* xptr = X.data(); + if (nr == 2 || nrow == 2) + { + for (Index i = 0; i < ncol; i++, xptr += stride) + { + const Scalar tmp = u0_2 * xptr[0] + u1_2 * xptr[1]; + xptr[0] -= tmp * u0; + xptr[1] -= tmp * u1; + } + } + else + { + const Scalar u2 = m_ref_u.coeff(2, u_ind); + const Scalar u2_2 = Scalar(2) * u2; + for (Index i = 0; i < ncol; i++, xptr += stride) + { + const Scalar tmp = u0_2 * xptr[0] + u1_2 * xptr[1] + u2_2 * xptr[2]; + xptr[0] -= tmp * u0; + xptr[1] -= tmp * u1; + xptr[2] -= tmp * u2; + } + } + } + + // x is a pointer to a vector + // Px = x - 2 * dot(x, u) * u + void apply_PX(Scalar* x, Index u_ind) const + { + const Index nr = m_ref_nr.coeff(u_ind); + if (nr == 1) + return; + + const Scalar u0 = m_ref_u.coeff(0, u_ind), + u1 = m_ref_u.coeff(1, u_ind), + u2 = m_ref_u.coeff(2, u_ind); + + // When the reflector only contains two elements, u2 has been set to zero + const bool nr_is_2 = (nr == 2); + const Scalar dot2 = Scalar(2) * (x[0] * u0 + x[1] * u1 + (nr_is_2 ? 0 : (x[2] * u2))); + x[0] -= dot2 * u0; + x[1] -= dot2 * u1; + if (!nr_is_2) + x[2] -= dot2 * u2; + } + + // XP = X - 2 * (X * u) * u' + void apply_XP(GenericMatrix X, Index stride, Index u_ind) const + { + const Index nr = m_ref_nr.coeff(u_ind); + if (nr == 1) + return; + + const Scalar u0 = m_ref_u.coeff(0, u_ind), + u1 = m_ref_u.coeff(1, u_ind); + const Scalar u0_2 = Scalar(2) * u0, + u1_2 = Scalar(2) * u1; + + const int nrow = X.rows(); + const int ncol = X.cols(); + Scalar *X0 = X.data(), *X1 = X0 + stride; // X0 => X.col(0), X1 => X.col(1) + + if (nr == 2 || ncol == 2) + { + // tmp = 2 * u0 * X0 + 2 * u1 * X1 + // X0 => X0 - u0 * tmp + // X1 => X1 - u1 * tmp + for (Index i = 0; i < nrow; i++) + { + const Scalar tmp = u0_2 * X0[i] + u1_2 * X1[i]; + X0[i] -= tmp * u0; + X1[i] -= tmp * u1; + } + } + else + { + Scalar* X2 = X1 + stride; // X2 => X.col(2) + const Scalar u2 = m_ref_u.coeff(2, u_ind); + const Scalar u2_2 = Scalar(2) * u2; + for (Index i = 0; i < nrow; i++) + { + const Scalar tmp = u0_2 * X0[i] + u1_2 * X1[i] + u2_2 * X2[i]; + X0[i] -= tmp * u0; + X1[i] -= tmp * u1; + X2[i] -= tmp * u2; + } + } + } + +public: + DoubleShiftQR(Index size) : + m_n(size), + m_near_0(TypeTraits::min() * Scalar(10)), + m_eps(Eigen::NumTraits::epsilon()), + m_eps_rel(m_eps), + m_eps_abs(m_near_0 * (m_n / m_eps)), + m_computed(false) + {} + + DoubleShiftQR(ConstGenericMatrix& mat, const Scalar& s, const Scalar& t) : + m_n(mat.rows()), + m_mat_H(m_n, m_n), + m_shift_s(s), + m_shift_t(t), + m_ref_u(3, m_n), + m_ref_nr(m_n), + m_near_0(TypeTraits::min() * Scalar(10)), + m_eps(Eigen::NumTraits::epsilon()), + m_eps_rel(m_eps), + m_eps_abs(m_near_0 * (m_n / m_eps)), + m_computed(false) + { + compute(mat, s, t); + } + + void compute(ConstGenericMatrix& mat, const Scalar& s, const Scalar& t) + { + using std::abs; + + m_n = mat.rows(); + if (m_n != mat.cols()) + throw std::invalid_argument("DoubleShiftQR: matrix must be square"); + + m_mat_H.resize(m_n, m_n); + m_shift_s = s; + m_shift_t = t; + m_ref_u.resize(3, m_n); + m_ref_nr.resize(m_n); + + // Make a copy of mat + std::copy(mat.data(), mat.data() + mat.size(), m_mat_H.data()); + + // Obtain the indices of zero elements in the subdiagonal, + // so that H can be divided into several blocks + std::vector zero_ind; + zero_ind.reserve(m_n - 1); + zero_ind.push_back(0); + Scalar* Hii = m_mat_H.data(); + for (Index i = 0; i < m_n - 2; i++, Hii += (m_n + 1)) + { + // Hii[1] => m_mat_H(i + 1, i) + const Scalar h = abs(Hii[1]); + if (h <= 0 || h <= m_eps_rel * (abs(Hii[0]) + abs(Hii[m_n + 1]))) + { + Hii[1] = 0; + zero_ind.push_back(i + 1); + } + // Make sure m_mat_H is upper Hessenberg + // Zero the elements below m_mat_H(i + 1, i) + std::fill(Hii + 2, Hii + m_n - i, Scalar(0)); + } + zero_ind.push_back(m_n); + + for (std::vector::size_type i = 0; i < zero_ind.size() - 1; i++) + { + const Index start = zero_ind[i]; + const Index end = zero_ind[i + 1] - 1; + // Compute refelctors and update each block + update_block(start, end); + } + + m_computed = true; + } + + void matrix_QtHQ(Matrix& dest) const + { + if (!m_computed) + throw std::logic_error("DoubleShiftQR: need to call compute() first"); + + dest.noalias() = m_mat_H; + } + + // Q = P0 * P1 * ... + // Q'y = P_{n-2} * ... * P1 * P0 * y + void apply_QtY(Vector& y) const + { + if (!m_computed) + throw std::logic_error("DoubleShiftQR: need to call compute() first"); + + Scalar* y_ptr = y.data(); + const Index n1 = m_n - 1; + for (Index i = 0; i < n1; i++, y_ptr++) + { + apply_PX(y_ptr, i); + } + } + + // Q = P0 * P1 * ... + // YQ = Y * P0 * P1 * ... + void apply_YQ(GenericMatrix Y) const + { + if (!m_computed) + throw std::logic_error("DoubleShiftQR: need to call compute() first"); + + const Index nrow = Y.rows(); + const Index n2 = m_n - 2; + for (Index i = 0; i < n2; i++) + { + apply_XP(Y.block(0, i, nrow, 3), nrow, i); + } + apply_XP(Y.block(0, n2, nrow, 2), nrow, n2); + } +}; + +} // namespace Spectra + +#endif // DOUBLE_SHIFT_QR_H diff --git a/gtsam/3rdparty/Spectra/LinAlg/Lanczos.h b/gtsam/3rdparty/Spectra/LinAlg/Lanczos.h new file mode 100644 index 000000000..53cf52be8 --- /dev/null +++ b/gtsam/3rdparty/Spectra/LinAlg/Lanczos.h @@ -0,0 +1,167 @@ +// Copyright (C) 2018-2019 Yixuan Qiu +// +// This Source Code Form is subject to the terms of the Mozilla +// Public License v. 2.0. If a copy of the MPL was not distributed +// with this file, You can obtain one at https://mozilla.org/MPL/2.0/. + +#ifndef LANCZOS_H +#define LANCZOS_H + +#include +#include // std::sqrt +#include // std::invalid_argument +#include // std::stringstream + +#include "Arnoldi.h" + +namespace Spectra { + +// Lanczos factorization A * V = V * H + f * e' +// A: n x n +// V: n x k +// H: k x k +// f: n x 1 +// e: [0, ..., 0, 1] +// V and H are allocated of dimension m, so the maximum value of k is m +template +class Lanczos : public Arnoldi +{ +private: + typedef Eigen::Index Index; + typedef Eigen::Matrix Matrix; + typedef Eigen::Matrix Vector; + typedef Eigen::Map MapMat; + typedef Eigen::Map MapVec; + typedef Eigen::Map MapConstMat; + typedef Eigen::Map MapConstVec; + + using Arnoldi::m_op; + using Arnoldi::m_n; + using Arnoldi::m_m; + using Arnoldi::m_k; + using Arnoldi::m_fac_V; + using Arnoldi::m_fac_H; + using Arnoldi::m_fac_f; + using Arnoldi::m_beta; + using Arnoldi::m_near_0; + using Arnoldi::m_eps; + +public: + Lanczos(const ArnoldiOpType& op, Index m) : + Arnoldi(op, m) + {} + + // Lanczos factorization starting from step-k + void factorize_from(Index from_k, Index to_m, Index& op_counter) + { + using std::sqrt; + + if (to_m <= from_k) + return; + + if (from_k > m_k) + { + std::stringstream msg; + msg << "Lanczos: from_k (= " << from_k << ") is larger than the current subspace dimension (= " << m_k << ")"; + throw std::invalid_argument(msg.str()); + } + + const Scalar beta_thresh = m_eps * sqrt(Scalar(m_n)); + + // Pre-allocate vectors + Vector Vf(to_m); + Vector w(m_n); + + // Keep the upperleft k x k submatrix of H and set other elements to 0 + m_fac_H.rightCols(m_m - from_k).setZero(); + m_fac_H.block(from_k, 0, m_m - from_k, from_k).setZero(); + + for (Index i = from_k; i <= to_m - 1; i++) + { + bool restart = false; + // If beta = 0, then the next V is not full rank + // We need to generate a new residual vector that is orthogonal + // to the current V, which we call a restart + if (m_beta < m_near_0) + { + MapConstMat V(m_fac_V.data(), m_n, i); // The first i columns + this->expand_basis(V, 2 * i, m_fac_f, m_beta); + restart = true; + } + + // v <- f / ||f|| + MapVec v(&m_fac_V(0, i), m_n); // The (i+1)-th column + v.noalias() = m_fac_f / m_beta; + + // Note that H[i+1, i] equals to the unrestarted beta + m_fac_H(i, i - 1) = restart ? Scalar(0) : m_beta; + + // w <- A * v + m_op.perform_op(v.data(), w.data()); + op_counter++; + + // H[i+1, i+1] = = v'Bw + m_fac_H(i - 1, i) = m_fac_H(i, i - 1); // Due to symmetry + m_fac_H(i, i) = m_op.inner_product(v, w); + + // f <- w - V * V'Bw = w - H[i+1, i] * V{i} - H[i+1, i+1] * V{i+1} + // If restarting, we know that H[i+1, i] = 0 + if (restart) + m_fac_f.noalias() = w - m_fac_H(i, i) * v; + else + m_fac_f.noalias() = w - m_fac_H(i, i - 1) * m_fac_V.col(i - 1) - m_fac_H(i, i) * v; + + m_beta = m_op.norm(m_fac_f); + + // f/||f|| is going to be the next column of V, so we need to test + // whether V'B(f/||f||) ~= 0 + const Index i1 = i + 1; + MapMat Vs(m_fac_V.data(), m_n, i1); // The first (i+1) columns + m_op.trans_product(Vs, m_fac_f, Vf.head(i1)); + Scalar ortho_err = Vf.head(i1).cwiseAbs().maxCoeff(); + // If not, iteratively correct the residual + int count = 0; + while (count < 5 && ortho_err > m_eps * m_beta) + { + // There is an edge case: when beta=||f|| is close to zero, f mostly consists + // of noises of rounding errors, so the test [ortho_err < eps * beta] is very + // likely to fail. In particular, if beta=0, then the test is ensured to fail. + // Hence when this happens, we force f to be zero, and then restart in the + // next iteration. + if (m_beta < beta_thresh) + { + m_fac_f.setZero(); + m_beta = Scalar(0); + break; + } + + // f <- f - V * Vf + m_fac_f.noalias() -= Vs * Vf.head(i1); + // h <- h + Vf + m_fac_H(i - 1, i) += Vf[i - 1]; + m_fac_H(i, i - 1) = m_fac_H(i - 1, i); + m_fac_H(i, i) += Vf[i]; + // beta <- ||f|| + m_beta = m_op.norm(m_fac_f); + + m_op.trans_product(Vs, m_fac_f, Vf.head(i1)); + ortho_err = Vf.head(i1).cwiseAbs().maxCoeff(); + count++; + } + } + + // Indicate that this is a step-m factorization + m_k = to_m; + } + + // Apply H -> Q'HQ, where Q is from a tridiagonal QR decomposition + void compress_H(const TridiagQR& decomp) + { + decomp.matrix_QtHQ(m_fac_H); + m_k--; + } +}; + +} // namespace Spectra + +#endif // LANCZOS_H diff --git a/gtsam/3rdparty/Spectra/LinAlg/TridiagEigen.h b/gtsam/3rdparty/Spectra/LinAlg/TridiagEigen.h new file mode 100644 index 000000000..122e0e551 --- /dev/null +++ b/gtsam/3rdparty/Spectra/LinAlg/TridiagEigen.h @@ -0,0 +1,219 @@ +// The code was adapted from Eigen/src/Eigenvaleus/SelfAdjointEigenSolver.h +// +// Copyright (C) 2008-2010 Gael Guennebaud +// Copyright (C) 2010 Jitse Niesen +// Copyright (C) 2016-2019 Yixuan Qiu +// +// This Source Code Form is subject to the terms of the Mozilla +// Public License v. 2.0. If a copy of the MPL was not distributed +// with this file, You can obtain one at https://mozilla.org/MPL/2.0/. + +#ifndef TRIDIAG_EIGEN_H +#define TRIDIAG_EIGEN_H + +#include +#include +#include + +#include "../Util/TypeTraits.h" + +namespace Spectra { + +template +class TridiagEigen +{ +private: + typedef Eigen::Index Index; + // For convenience in adapting the tridiagonal_qr_step() function + typedef Scalar RealScalar; + + typedef Eigen::Matrix Matrix; + typedef Eigen::Matrix Vector; + + typedef Eigen::Ref GenericMatrix; + typedef const Eigen::Ref ConstGenericMatrix; + + Index m_n; + Vector m_main_diag; // Main diagonal elements of the matrix + Vector m_sub_diag; // Sub-diagonal elements of the matrix + Matrix m_evecs; // To store eigenvectors + + bool m_computed; + const Scalar m_near_0; // a very small value, ~= 1e-307 for the "double" type + + // Adapted from Eigen/src/Eigenvaleus/SelfAdjointEigenSolver.h + static void tridiagonal_qr_step(RealScalar* diag, + RealScalar* subdiag, Index start, + Index end, Scalar* matrixQ, + Index n) + { + using std::abs; + + RealScalar td = (diag[end - 1] - diag[end]) * RealScalar(0.5); + RealScalar e = subdiag[end - 1]; + // Note that thanks to scaling, e^2 or td^2 cannot overflow, however they can still + // underflow thus leading to inf/NaN values when using the following commented code: + // RealScalar e2 = numext::abs2(subdiag[end-1]); + // RealScalar mu = diag[end] - e2 / (td + (td>0 ? 1 : -1) * sqrt(td*td + e2)); + // This explain the following, somewhat more complicated, version: + RealScalar mu = diag[end]; + if (td == Scalar(0)) + mu -= abs(e); + else + { + RealScalar e2 = Eigen::numext::abs2(subdiag[end - 1]); + RealScalar h = Eigen::numext::hypot(td, e); + if (e2 == RealScalar(0)) + mu -= (e / (td + (td > RealScalar(0) ? RealScalar(1) : RealScalar(-1)))) * (e / h); + else + mu -= e2 / (td + (td > RealScalar(0) ? h : -h)); + } + + RealScalar x = diag[start] - mu; + RealScalar z = subdiag[start]; + Eigen::Map q(matrixQ, n, n); + for (Index k = start; k < end; ++k) + { + Eigen::JacobiRotation rot; + rot.makeGivens(x, z); + + const RealScalar s = rot.s(); + const RealScalar c = rot.c(); + + // do T = G' T G + RealScalar sdk = s * diag[k] + c * subdiag[k]; + RealScalar dkp1 = s * subdiag[k] + c * diag[k + 1]; + + diag[k] = c * (c * diag[k] - s * subdiag[k]) - s * (c * subdiag[k] - s * diag[k + 1]); + diag[k + 1] = s * sdk + c * dkp1; + subdiag[k] = c * sdk - s * dkp1; + + if (k > start) + subdiag[k - 1] = c * subdiag[k - 1] - s * z; + + x = subdiag[k]; + + if (k < end - 1) + { + z = -s * subdiag[k + 1]; + subdiag[k + 1] = c * subdiag[k + 1]; + } + + // apply the givens rotation to the unit matrix Q = Q * G + if (matrixQ) + q.applyOnTheRight(k, k + 1, rot); + } + } + +public: + TridiagEigen() : + m_n(0), m_computed(false), + m_near_0(TypeTraits::min() * Scalar(10)) + {} + + TridiagEigen(ConstGenericMatrix& mat) : + m_n(mat.rows()), m_computed(false), + m_near_0(TypeTraits::min() * Scalar(10)) + { + compute(mat); + } + + void compute(ConstGenericMatrix& mat) + { + using std::abs; + + m_n = mat.rows(); + if (m_n != mat.cols()) + throw std::invalid_argument("TridiagEigen: matrix must be square"); + + m_main_diag.resize(m_n); + m_sub_diag.resize(m_n - 1); + m_evecs.resize(m_n, m_n); + m_evecs.setIdentity(); + + // Scale matrix to improve stability + const Scalar scale = std::max(mat.diagonal().cwiseAbs().maxCoeff(), + mat.diagonal(-1).cwiseAbs().maxCoeff()); + // If scale=0, mat is a zero matrix, so we can early stop + if (scale < m_near_0) + { + // m_main_diag contains eigenvalues + m_main_diag.setZero(); + // m_evecs has been set identity + // m_evecs.setIdentity(); + m_computed = true; + return; + } + m_main_diag.noalias() = mat.diagonal() / scale; + m_sub_diag.noalias() = mat.diagonal(-1) / scale; + + Scalar* diag = m_main_diag.data(); + Scalar* subdiag = m_sub_diag.data(); + + Index end = m_n - 1; + Index start = 0; + Index iter = 0; // total number of iterations + int info = 0; // 0 for success, 1 for failure + + const Scalar considerAsZero = TypeTraits::min(); + const Scalar precision = Scalar(2) * Eigen::NumTraits::epsilon(); + + while (end > 0) + { + for (Index i = start; i < end; i++) + if (abs(subdiag[i]) <= considerAsZero || + abs(subdiag[i]) <= (abs(diag[i]) + abs(diag[i + 1])) * precision) + subdiag[i] = 0; + + // find the largest unreduced block + while (end > 0 && subdiag[end - 1] == Scalar(0)) + end--; + + if (end <= 0) + break; + + // if we spent too many iterations, we give up + iter++; + if (iter > 30 * m_n) + { + info = 1; + break; + } + + start = end - 1; + while (start > 0 && subdiag[start - 1] != Scalar(0)) + start--; + + tridiagonal_qr_step(diag, subdiag, start, end, m_evecs.data(), m_n); + } + + if (info > 0) + throw std::runtime_error("TridiagEigen: eigen decomposition failed"); + + // Scale eigenvalues back + m_main_diag *= scale; + + m_computed = true; + } + + const Vector& eigenvalues() const + { + if (!m_computed) + throw std::logic_error("TridiagEigen: need to call compute() first"); + + // After calling compute(), main_diag will contain the eigenvalues. + return m_main_diag; + } + + const Matrix& eigenvectors() const + { + if (!m_computed) + throw std::logic_error("TridiagEigen: need to call compute() first"); + + return m_evecs; + } +}; + +} // namespace Spectra + +#endif // TRIDIAG_EIGEN_H diff --git a/gtsam/3rdparty/Spectra/LinAlg/UpperHessenbergEigen.h b/gtsam/3rdparty/Spectra/LinAlg/UpperHessenbergEigen.h new file mode 100644 index 000000000..4865e9db8 --- /dev/null +++ b/gtsam/3rdparty/Spectra/LinAlg/UpperHessenbergEigen.h @@ -0,0 +1,319 @@ +// The code was adapted from Eigen/src/Eigenvaleus/EigenSolver.h +// +// Copyright (C) 2008 Gael Guennebaud +// Copyright (C) 2010,2012 Jitse Niesen +// Copyright (C) 2016-2019 Yixuan Qiu +// +// This Source Code Form is subject to the terms of the Mozilla +// Public License v. 2.0. If a copy of the MPL was not distributed +// with this file, You can obtain one at https://mozilla.org/MPL/2.0/. + +#ifndef UPPER_HESSENBERG_EIGEN_H +#define UPPER_HESSENBERG_EIGEN_H + +#include +#include +#include + +namespace Spectra { + +template +class UpperHessenbergEigen +{ +private: + typedef Eigen::Index Index; + typedef Eigen::Matrix Matrix; + typedef Eigen::Matrix Vector; + + typedef Eigen::Ref GenericMatrix; + typedef const Eigen::Ref ConstGenericMatrix; + + typedef std::complex Complex; + typedef Eigen::Matrix ComplexMatrix; + typedef Eigen::Matrix ComplexVector; + + Index m_n; // Size of the matrix + Eigen::RealSchur m_realSchur; // Schur decomposition solver + Matrix m_matT; // Schur T matrix + Matrix m_eivec; // Storing eigenvectors + ComplexVector m_eivalues; // Eigenvalues + + bool m_computed; + + void doComputeEigenvectors() + { + using std::abs; + + const Index size = m_eivec.cols(); + const Scalar eps = Eigen::NumTraits::epsilon(); + + // inefficient! this is already computed in RealSchur + Scalar norm(0); + for (Index j = 0; j < size; ++j) + { + norm += m_matT.row(j).segment((std::max)(j - 1, Index(0)), size - (std::max)(j - 1, Index(0))).cwiseAbs().sum(); + } + + // Backsubstitute to find vectors of upper triangular form + if (norm == Scalar(0)) + return; + + for (Index n = size - 1; n >= 0; n--) + { + Scalar p = m_eivalues.coeff(n).real(); + Scalar q = m_eivalues.coeff(n).imag(); + + // Scalar vector + if (q == Scalar(0)) + { + Scalar lastr(0), lastw(0); + Index l = n; + + m_matT.coeffRef(n, n) = Scalar(1); + for (Index i = n - 1; i >= 0; i--) + { + Scalar w = m_matT.coeff(i, i) - p; + Scalar r = m_matT.row(i).segment(l, n - l + 1).dot(m_matT.col(n).segment(l, n - l + 1)); + + if (m_eivalues.coeff(i).imag() < Scalar(0)) + { + lastw = w; + lastr = r; + } + else + { + l = i; + if (m_eivalues.coeff(i).imag() == Scalar(0)) + { + if (w != Scalar(0)) + m_matT.coeffRef(i, n) = -r / w; + else + m_matT.coeffRef(i, n) = -r / (eps * norm); + } + else // Solve real equations + { + Scalar x = m_matT.coeff(i, i + 1); + Scalar y = m_matT.coeff(i + 1, i); + Scalar denom = (m_eivalues.coeff(i).real() - p) * (m_eivalues.coeff(i).real() - p) + m_eivalues.coeff(i).imag() * m_eivalues.coeff(i).imag(); + Scalar t = (x * lastr - lastw * r) / denom; + m_matT.coeffRef(i, n) = t; + if (abs(x) > abs(lastw)) + m_matT.coeffRef(i + 1, n) = (-r - w * t) / x; + else + m_matT.coeffRef(i + 1, n) = (-lastr - y * t) / lastw; + } + + // Overflow control + Scalar t = abs(m_matT.coeff(i, n)); + if ((eps * t) * t > Scalar(1)) + m_matT.col(n).tail(size - i) /= t; + } + } + } + else if (q < Scalar(0) && n > 0) + { // Complex vector + Scalar lastra(0), lastsa(0), lastw(0); + Index l = n - 1; + + // Last vector component imaginary so matrix is triangular + if (abs(m_matT.coeff(n, n - 1)) > abs(m_matT.coeff(n - 1, n))) + { + m_matT.coeffRef(n - 1, n - 1) = q / m_matT.coeff(n, n - 1); + m_matT.coeffRef(n - 1, n) = -(m_matT.coeff(n, n) - p) / m_matT.coeff(n, n - 1); + } + else + { + Complex cc = Complex(Scalar(0), -m_matT.coeff(n - 1, n)) / Complex(m_matT.coeff(n - 1, n - 1) - p, q); + m_matT.coeffRef(n - 1, n - 1) = Eigen::numext::real(cc); + m_matT.coeffRef(n - 1, n) = Eigen::numext::imag(cc); + } + m_matT.coeffRef(n, n - 1) = Scalar(0); + m_matT.coeffRef(n, n) = Scalar(1); + for (Index i = n - 2; i >= 0; i--) + { + Scalar ra = m_matT.row(i).segment(l, n - l + 1).dot(m_matT.col(n - 1).segment(l, n - l + 1)); + Scalar sa = m_matT.row(i).segment(l, n - l + 1).dot(m_matT.col(n).segment(l, n - l + 1)); + Scalar w = m_matT.coeff(i, i) - p; + + if (m_eivalues.coeff(i).imag() < Scalar(0)) + { + lastw = w; + lastra = ra; + lastsa = sa; + } + else + { + l = i; + if (m_eivalues.coeff(i).imag() == Scalar(0)) + { + Complex cc = Complex(-ra, -sa) / Complex(w, q); + m_matT.coeffRef(i, n - 1) = Eigen::numext::real(cc); + m_matT.coeffRef(i, n) = Eigen::numext::imag(cc); + } + else + { + // Solve complex equations + Scalar x = m_matT.coeff(i, i + 1); + Scalar y = m_matT.coeff(i + 1, i); + Scalar vr = (m_eivalues.coeff(i).real() - p) * (m_eivalues.coeff(i).real() - p) + m_eivalues.coeff(i).imag() * m_eivalues.coeff(i).imag() - q * q; + Scalar vi = (m_eivalues.coeff(i).real() - p) * Scalar(2) * q; + if ((vr == Scalar(0)) && (vi == Scalar(0))) + vr = eps * norm * (abs(w) + abs(q) + abs(x) + abs(y) + abs(lastw)); + + Complex cc = Complex(x * lastra - lastw * ra + q * sa, x * lastsa - lastw * sa - q * ra) / Complex(vr, vi); + m_matT.coeffRef(i, n - 1) = Eigen::numext::real(cc); + m_matT.coeffRef(i, n) = Eigen::numext::imag(cc); + if (abs(x) > (abs(lastw) + abs(q))) + { + m_matT.coeffRef(i + 1, n - 1) = (-ra - w * m_matT.coeff(i, n - 1) + q * m_matT.coeff(i, n)) / x; + m_matT.coeffRef(i + 1, n) = (-sa - w * m_matT.coeff(i, n) - q * m_matT.coeff(i, n - 1)) / x; + } + else + { + cc = Complex(-lastra - y * m_matT.coeff(i, n - 1), -lastsa - y * m_matT.coeff(i, n)) / Complex(lastw, q); + m_matT.coeffRef(i + 1, n - 1) = Eigen::numext::real(cc); + m_matT.coeffRef(i + 1, n) = Eigen::numext::imag(cc); + } + } + + // Overflow control + Scalar t = std::max(abs(m_matT.coeff(i, n - 1)), abs(m_matT.coeff(i, n))); + if ((eps * t) * t > Scalar(1)) + m_matT.block(i, n - 1, size - i, 2) /= t; + } + } + + // We handled a pair of complex conjugate eigenvalues, so need to skip them both + n--; + } + } + + // Back transformation to get eigenvectors of original matrix + Vector m_tmp(size); + for (Index j = size - 1; j >= 0; j--) + { + m_tmp.noalias() = m_eivec.leftCols(j + 1) * m_matT.col(j).segment(0, j + 1); + m_eivec.col(j) = m_tmp; + } + } + +public: + UpperHessenbergEigen() : + m_n(0), m_computed(false) + {} + + UpperHessenbergEigen(ConstGenericMatrix& mat) : + m_n(mat.rows()), m_computed(false) + { + compute(mat); + } + + void compute(ConstGenericMatrix& mat) + { + using std::abs; + using std::sqrt; + + if (mat.rows() != mat.cols()) + throw std::invalid_argument("UpperHessenbergEigen: matrix must be square"); + + m_n = mat.rows(); + // Scale matrix prior to the Schur decomposition + const Scalar scale = mat.cwiseAbs().maxCoeff(); + + // Reduce to real Schur form + Matrix Q = Matrix::Identity(m_n, m_n); + m_realSchur.computeFromHessenberg(mat / scale, Q, true); + if (m_realSchur.info() != Eigen::Success) + throw std::runtime_error("UpperHessenbergEigen: eigen decomposition failed"); + + m_matT = m_realSchur.matrixT(); + m_eivec = m_realSchur.matrixU(); + + // Compute eigenvalues from matT + m_eivalues.resize(m_n); + Index i = 0; + while (i < m_n) + { + // Real eigenvalue + if (i == m_n - 1 || m_matT.coeff(i + 1, i) == Scalar(0)) + { + m_eivalues.coeffRef(i) = m_matT.coeff(i, i); + ++i; + } + else // Complex eigenvalues + { + Scalar p = Scalar(0.5) * (m_matT.coeff(i, i) - m_matT.coeff(i + 1, i + 1)); + Scalar z; + // Compute z = sqrt(abs(p * p + m_matT.coeff(i+1, i) * m_matT.coeff(i, i+1))); + // without overflow + { + Scalar t0 = m_matT.coeff(i + 1, i); + Scalar t1 = m_matT.coeff(i, i + 1); + Scalar maxval = std::max(abs(p), std::max(abs(t0), abs(t1))); + t0 /= maxval; + t1 /= maxval; + Scalar p0 = p / maxval; + z = maxval * sqrt(abs(p0 * p0 + t0 * t1)); + } + m_eivalues.coeffRef(i) = Complex(m_matT.coeff(i + 1, i + 1) + p, z); + m_eivalues.coeffRef(i + 1) = Complex(m_matT.coeff(i + 1, i + 1) + p, -z); + i += 2; + } + } + + // Compute eigenvectors + doComputeEigenvectors(); + + // Scale eigenvalues back + m_eivalues *= scale; + + m_computed = true; + } + + const ComplexVector& eigenvalues() const + { + if (!m_computed) + throw std::logic_error("UpperHessenbergEigen: need to call compute() first"); + + return m_eivalues; + } + + ComplexMatrix eigenvectors() + { + using std::abs; + + if (!m_computed) + throw std::logic_error("UpperHessenbergEigen: need to call compute() first"); + + Index n = m_eivec.cols(); + ComplexMatrix matV(n, n); + for (Index j = 0; j < n; ++j) + { + // imaginary part of real eigenvalue is already set to exact zero + if (Eigen::numext::imag(m_eivalues.coeff(j)) == Scalar(0) || j + 1 == n) + { + // we have a real eigen value + matV.col(j) = m_eivec.col(j).template cast(); + matV.col(j).normalize(); + } + else + { + // we have a pair of complex eigen values + for (Index i = 0; i < n; ++i) + { + matV.coeffRef(i, j) = Complex(m_eivec.coeff(i, j), m_eivec.coeff(i, j + 1)); + matV.coeffRef(i, j + 1) = Complex(m_eivec.coeff(i, j), -m_eivec.coeff(i, j + 1)); + } + matV.col(j).normalize(); + matV.col(j + 1).normalize(); + ++j; + } + } + + return matV; + } +}; + +} // namespace Spectra + +#endif // UPPER_HESSENBERG_EIGEN_H diff --git a/gtsam/3rdparty/Spectra/LinAlg/UpperHessenbergQR.h b/gtsam/3rdparty/Spectra/LinAlg/UpperHessenbergQR.h new file mode 100644 index 000000000..5778f11dc --- /dev/null +++ b/gtsam/3rdparty/Spectra/LinAlg/UpperHessenbergQR.h @@ -0,0 +1,670 @@ +// Copyright (C) 2016-2019 Yixuan Qiu +// +// This Source Code Form is subject to the terms of the Mozilla +// Public License v. 2.0. If a copy of the MPL was not distributed +// with this file, You can obtain one at https://mozilla.org/MPL/2.0/. + +#ifndef UPPER_HESSENBERG_QR_H +#define UPPER_HESSENBERG_QR_H + +#include +#include // std::sqrt +#include // std::fill, std::copy +#include // std::logic_error + +namespace Spectra { + +/// +/// \defgroup Internals Internal Classes +/// +/// Classes for internal use. May be useful to developers. +/// + +/// +/// \ingroup Internals +/// @{ +/// + +/// +/// \defgroup LinearAlgebra Linear Algebra +/// +/// A number of classes for linear algebra operations. +/// + +/// +/// \ingroup LinearAlgebra +/// +/// Perform the QR decomposition of an upper Hessenberg matrix. +/// +/// \tparam Scalar The element type of the matrix. +/// Currently supported types are `float`, `double` and `long double`. +/// +template +class UpperHessenbergQR +{ +private: + typedef Eigen::Index Index; + typedef Eigen::Matrix Matrix; + typedef Eigen::Matrix Vector; + typedef Eigen::Matrix RowVector; + typedef Eigen::Array Array; + + typedef Eigen::Ref GenericMatrix; + typedef const Eigen::Ref ConstGenericMatrix; + + Matrix m_mat_T; + +protected: + Index m_n; + // Gi = [ cos[i] sin[i]] + // [-sin[i] cos[i]] + // Q = G1 * G2 * ... * G_{n-1} + Scalar m_shift; + Array m_rot_cos; + Array m_rot_sin; + bool m_computed; + + // Given x and y, compute 1) r = sqrt(x^2 + y^2), 2) c = x / r, 3) s = -y / r + // If both x and y are zero, set c = 1 and s = 0 + // We must implement it in a numerically stable way + static void compute_rotation(const Scalar& x, const Scalar& y, Scalar& r, Scalar& c, Scalar& s) + { + using std::sqrt; + + const Scalar xsign = (x > Scalar(0)) - (x < Scalar(0)); + const Scalar ysign = (y > Scalar(0)) - (y < Scalar(0)); + const Scalar xabs = x * xsign; + const Scalar yabs = y * ysign; + if (xabs > yabs) + { + // In this case xabs != 0 + const Scalar ratio = yabs / xabs; // so that 0 <= ratio < 1 + const Scalar common = sqrt(Scalar(1) + ratio * ratio); + c = xsign / common; + r = xabs * common; + s = -y / r; + } + else + { + if (yabs == Scalar(0)) + { + r = Scalar(0); + c = Scalar(1); + s = Scalar(0); + return; + } + const Scalar ratio = xabs / yabs; // so that 0 <= ratio <= 1 + const Scalar common = sqrt(Scalar(1) + ratio * ratio); + s = -ysign / common; + r = yabs * common; + c = x / r; + } + } + +public: + /// + /// Constructor to preallocate memory. Computation can + /// be performed later by calling the compute() method. + /// + UpperHessenbergQR(Index size) : + m_n(size), + m_rot_cos(m_n - 1), + m_rot_sin(m_n - 1), + m_computed(false) + {} + + /// + /// Constructor to create an object that performs and stores the + /// QR decomposition of an upper Hessenberg matrix `mat`, with an + /// optional shift: \f$H-sI=QR\f$. Here \f$H\f$ stands for the matrix + /// `mat`, and \f$s\f$ is the shift. + /// + /// \param mat Matrix type can be `Eigen::Matrix` (e.g. + /// `Eigen::MatrixXd` and `Eigen::MatrixXf`), or its mapped version + /// (e.g. `Eigen::Map`). + /// Only the upper triangular and the lower subdiagonal parts of + /// the matrix are used. + /// + UpperHessenbergQR(ConstGenericMatrix& mat, const Scalar& shift = Scalar(0)) : + m_n(mat.rows()), + m_shift(shift), + m_rot_cos(m_n - 1), + m_rot_sin(m_n - 1), + m_computed(false) + { + compute(mat, shift); + } + + /// + /// Virtual destructor. + /// + virtual ~UpperHessenbergQR(){}; + + /// + /// Conduct the QR factorization of an upper Hessenberg matrix with + /// an optional shift. + /// + /// \param mat Matrix type can be `Eigen::Matrix` (e.g. + /// `Eigen::MatrixXd` and `Eigen::MatrixXf`), or its mapped version + /// (e.g. `Eigen::Map`). + /// Only the upper triangular and the lower subdiagonal parts of + /// the matrix are used. + /// + virtual void compute(ConstGenericMatrix& mat, const Scalar& shift = Scalar(0)) + { + m_n = mat.rows(); + if (m_n != mat.cols()) + throw std::invalid_argument("UpperHessenbergQR: matrix must be square"); + + m_shift = shift; + m_mat_T.resize(m_n, m_n); + m_rot_cos.resize(m_n - 1); + m_rot_sin.resize(m_n - 1); + + // Make a copy of mat - s * I + std::copy(mat.data(), mat.data() + mat.size(), m_mat_T.data()); + m_mat_T.diagonal().array() -= m_shift; + + Scalar xi, xj, r, c, s; + Scalar *Tii, *ptr; + const Index n1 = m_n - 1; + for (Index i = 0; i < n1; i++) + { + Tii = &m_mat_T.coeffRef(i, i); + + // Make sure mat_T is upper Hessenberg + // Zero the elements below mat_T(i + 1, i) + std::fill(Tii + 2, Tii + m_n - i, Scalar(0)); + + xi = Tii[0]; // mat_T(i, i) + xj = Tii[1]; // mat_T(i + 1, i) + compute_rotation(xi, xj, r, c, s); + m_rot_cos[i] = c; + m_rot_sin[i] = s; + + // For a complete QR decomposition, + // we first obtain the rotation matrix + // G = [ cos sin] + // [-sin cos] + // and then do T[i:(i + 1), i:(n - 1)] = G' * T[i:(i + 1), i:(n - 1)] + + // Gt << c, -s, s, c; + // m_mat_T.block(i, i, 2, m_n - i) = Gt * m_mat_T.block(i, i, 2, m_n - i); + Tii[0] = r; // m_mat_T(i, i) => r + Tii[1] = 0; // m_mat_T(i + 1, i) => 0 + ptr = Tii + m_n; // m_mat_T(i, k), k = i+1, i+2, ..., n-1 + for (Index j = i + 1; j < m_n; j++, ptr += m_n) + { + Scalar tmp = ptr[0]; + ptr[0] = c * tmp - s * ptr[1]; + ptr[1] = s * tmp + c * ptr[1]; + } + + // If we do not need to calculate the R matrix, then + // only the cos and sin sequences are required. + // In such case we only update T[i + 1, (i + 1):(n - 1)] + // m_mat_T.block(i + 1, i + 1, 1, m_n - i - 1) *= c; + // m_mat_T.block(i + 1, i + 1, 1, m_n - i - 1) += s * mat_T.block(i, i + 1, 1, m_n - i - 1); + } + + m_computed = true; + } + + /// + /// Return the \f$R\f$ matrix in the QR decomposition, which is an + /// upper triangular matrix. + /// + /// \return Returned matrix type will be `Eigen::Matrix`, depending on + /// the template parameter `Scalar` defined. + /// + virtual Matrix matrix_R() const + { + if (!m_computed) + throw std::logic_error("UpperHessenbergQR: need to call compute() first"); + + return m_mat_T; + } + + /// + /// Overwrite `dest` with \f$Q'HQ = RQ + sI\f$, where \f$H\f$ is the input matrix `mat`, + /// and \f$s\f$ is the shift. The result is an upper Hessenberg matrix. + /// + /// \param mat The matrix to be overwritten, whose type should be `Eigen::Matrix`, + /// depending on the template parameter `Scalar` defined. + /// + virtual void matrix_QtHQ(Matrix& dest) const + { + if (!m_computed) + throw std::logic_error("UpperHessenbergQR: need to call compute() first"); + + // Make a copy of the R matrix + dest.resize(m_n, m_n); + std::copy(m_mat_T.data(), m_mat_T.data() + m_mat_T.size(), dest.data()); + + // Compute the RQ matrix + const Index n1 = m_n - 1; + for (Index i = 0; i < n1; i++) + { + const Scalar c = m_rot_cos.coeff(i); + const Scalar s = m_rot_sin.coeff(i); + // RQ[, i:(i + 1)] = RQ[, i:(i + 1)] * Gi + // Gi = [ cos[i] sin[i]] + // [-sin[i] cos[i]] + Scalar *Yi, *Yi1; + Yi = &dest.coeffRef(0, i); + Yi1 = Yi + m_n; // RQ(0, i + 1) + const Index i2 = i + 2; + for (Index j = 0; j < i2; j++) + { + const Scalar tmp = Yi[j]; + Yi[j] = c * tmp - s * Yi1[j]; + Yi1[j] = s * tmp + c * Yi1[j]; + } + + /* Vector dest = RQ.block(0, i, i + 2, 1); + dest.block(0, i, i + 2, 1) = c * Yi - s * dest.block(0, i + 1, i + 2, 1); + dest.block(0, i + 1, i + 2, 1) = s * Yi + c * dest.block(0, i + 1, i + 2, 1); */ + } + + // Add the shift to the diagonal + dest.diagonal().array() += m_shift; + } + + /// + /// Apply the \f$Q\f$ matrix to a vector \f$y\f$. + /// + /// \param Y A vector that will be overwritten by the matrix product \f$Qy\f$. + /// + /// Vector type can be `Eigen::Vector`, depending on + /// the template parameter `Scalar` defined. + /// + // Y -> QY = G1 * G2 * ... * Y + void apply_QY(Vector& Y) const + { + if (!m_computed) + throw std::logic_error("UpperHessenbergQR: need to call compute() first"); + + for (Index i = m_n - 2; i >= 0; i--) + { + const Scalar c = m_rot_cos.coeff(i); + const Scalar s = m_rot_sin.coeff(i); + // Y[i:(i + 1)] = Gi * Y[i:(i + 1)] + // Gi = [ cos[i] sin[i]] + // [-sin[i] cos[i]] + const Scalar tmp = Y[i]; + Y[i] = c * tmp + s * Y[i + 1]; + Y[i + 1] = -s * tmp + c * Y[i + 1]; + } + } + + /// + /// Apply the \f$Q\f$ matrix to a vector \f$y\f$. + /// + /// \param Y A vector that will be overwritten by the matrix product \f$Q'y\f$. + /// + /// Vector type can be `Eigen::Vector`, depending on + /// the template parameter `Scalar` defined. + /// + // Y -> Q'Y = G_{n-1}' * ... * G2' * G1' * Y + void apply_QtY(Vector& Y) const + { + if (!m_computed) + throw std::logic_error("UpperHessenbergQR: need to call compute() first"); + + const Index n1 = m_n - 1; + for (Index i = 0; i < n1; i++) + { + const Scalar c = m_rot_cos.coeff(i); + const Scalar s = m_rot_sin.coeff(i); + // Y[i:(i + 1)] = Gi' * Y[i:(i + 1)] + // Gi = [ cos[i] sin[i]] + // [-sin[i] cos[i]] + const Scalar tmp = Y[i]; + Y[i] = c * tmp - s * Y[i + 1]; + Y[i + 1] = s * tmp + c * Y[i + 1]; + } + } + + /// + /// Apply the \f$Q\f$ matrix to another matrix \f$Y\f$. + /// + /// \param Y A matrix that will be overwritten by the matrix product \f$QY\f$. + /// + /// Matrix type can be `Eigen::Matrix` (e.g. + /// `Eigen::MatrixXd` and `Eigen::MatrixXf`), or its mapped version + /// (e.g. `Eigen::Map`). + /// + // Y -> QY = G1 * G2 * ... * Y + void apply_QY(GenericMatrix Y) const + { + if (!m_computed) + throw std::logic_error("UpperHessenbergQR: need to call compute() first"); + + RowVector Yi(Y.cols()), Yi1(Y.cols()); + for (Index i = m_n - 2; i >= 0; i--) + { + const Scalar c = m_rot_cos.coeff(i); + const Scalar s = m_rot_sin.coeff(i); + // Y[i:(i + 1), ] = Gi * Y[i:(i + 1), ] + // Gi = [ cos[i] sin[i]] + // [-sin[i] cos[i]] + Yi.noalias() = Y.row(i); + Yi1.noalias() = Y.row(i + 1); + Y.row(i) = c * Yi + s * Yi1; + Y.row(i + 1) = -s * Yi + c * Yi1; + } + } + + /// + /// Apply the \f$Q\f$ matrix to another matrix \f$Y\f$. + /// + /// \param Y A matrix that will be overwritten by the matrix product \f$Q'Y\f$. + /// + /// Matrix type can be `Eigen::Matrix` (e.g. + /// `Eigen::MatrixXd` and `Eigen::MatrixXf`), or its mapped version + /// (e.g. `Eigen::Map`). + /// + // Y -> Q'Y = G_{n-1}' * ... * G2' * G1' * Y + void apply_QtY(GenericMatrix Y) const + { + if (!m_computed) + throw std::logic_error("UpperHessenbergQR: need to call compute() first"); + + RowVector Yi(Y.cols()), Yi1(Y.cols()); + const Index n1 = m_n - 1; + for (Index i = 0; i < n1; i++) + { + const Scalar c = m_rot_cos.coeff(i); + const Scalar s = m_rot_sin.coeff(i); + // Y[i:(i + 1), ] = Gi' * Y[i:(i + 1), ] + // Gi = [ cos[i] sin[i]] + // [-sin[i] cos[i]] + Yi.noalias() = Y.row(i); + Yi1.noalias() = Y.row(i + 1); + Y.row(i) = c * Yi - s * Yi1; + Y.row(i + 1) = s * Yi + c * Yi1; + } + } + + /// + /// Apply the \f$Q\f$ matrix to another matrix \f$Y\f$. + /// + /// \param Y A matrix that will be overwritten by the matrix product \f$YQ\f$. + /// + /// Matrix type can be `Eigen::Matrix` (e.g. + /// `Eigen::MatrixXd` and `Eigen::MatrixXf`), or its mapped version + /// (e.g. `Eigen::Map`). + /// + // Y -> YQ = Y * G1 * G2 * ... + void apply_YQ(GenericMatrix Y) const + { + if (!m_computed) + throw std::logic_error("UpperHessenbergQR: need to call compute() first"); + + /*Vector Yi(Y.rows()); + for(Index i = 0; i < m_n - 1; i++) + { + const Scalar c = m_rot_cos.coeff(i); + const Scalar s = m_rot_sin.coeff(i); + // Y[, i:(i + 1)] = Y[, i:(i + 1)] * Gi + // Gi = [ cos[i] sin[i]] + // [-sin[i] cos[i]] + Yi.noalias() = Y.col(i); + Y.col(i) = c * Yi - s * Y.col(i + 1); + Y.col(i + 1) = s * Yi + c * Y.col(i + 1); + }*/ + Scalar *Y_col_i, *Y_col_i1; + const Index n1 = m_n - 1; + const Index nrow = Y.rows(); + for (Index i = 0; i < n1; i++) + { + const Scalar c = m_rot_cos.coeff(i); + const Scalar s = m_rot_sin.coeff(i); + + Y_col_i = &Y.coeffRef(0, i); + Y_col_i1 = &Y.coeffRef(0, i + 1); + for (Index j = 0; j < nrow; j++) + { + Scalar tmp = Y_col_i[j]; + Y_col_i[j] = c * tmp - s * Y_col_i1[j]; + Y_col_i1[j] = s * tmp + c * Y_col_i1[j]; + } + } + } + + /// + /// Apply the \f$Q\f$ matrix to another matrix \f$Y\f$. + /// + /// \param Y A matrix that will be overwritten by the matrix product \f$YQ'\f$. + /// + /// Matrix type can be `Eigen::Matrix` (e.g. + /// `Eigen::MatrixXd` and `Eigen::MatrixXf`), or its mapped version + /// (e.g. `Eigen::Map`). + /// + // Y -> YQ' = Y * G_{n-1}' * ... * G2' * G1' + void apply_YQt(GenericMatrix Y) const + { + if (!m_computed) + throw std::logic_error("UpperHessenbergQR: need to call compute() first"); + + Vector Yi(Y.rows()); + for (Index i = m_n - 2; i >= 0; i--) + { + const Scalar c = m_rot_cos.coeff(i); + const Scalar s = m_rot_sin.coeff(i); + // Y[, i:(i + 1)] = Y[, i:(i + 1)] * Gi' + // Gi = [ cos[i] sin[i]] + // [-sin[i] cos[i]] + Yi.noalias() = Y.col(i); + Y.col(i) = c * Yi + s * Y.col(i + 1); + Y.col(i + 1) = -s * Yi + c * Y.col(i + 1); + } + } +}; + +/// +/// \ingroup LinearAlgebra +/// +/// Perform the QR decomposition of a tridiagonal matrix, a special +/// case of upper Hessenberg matrices. +/// +/// \tparam Scalar The element type of the matrix. +/// Currently supported types are `float`, `double` and `long double`. +/// +template +class TridiagQR : public UpperHessenbergQR +{ +private: + typedef Eigen::Matrix Matrix; + typedef Eigen::Matrix Vector; + typedef const Eigen::Ref ConstGenericMatrix; + + typedef typename Matrix::Index Index; + + Vector m_T_diag; // diagonal elements of T + Vector m_T_lsub; // lower subdiagonal of T + Vector m_T_usub; // upper subdiagonal of T + Vector m_T_usub2; // 2nd upper subdiagonal of T + +public: + /// + /// Constructor to preallocate memory. Computation can + /// be performed later by calling the compute() method. + /// + TridiagQR(Index size) : + UpperHessenbergQR(size) + {} + + /// + /// Constructor to create an object that performs and stores the + /// QR decomposition of an upper Hessenberg matrix `mat`, with an + /// optional shift: \f$H-sI=QR\f$. Here \f$H\f$ stands for the matrix + /// `mat`, and \f$s\f$ is the shift. + /// + /// \param mat Matrix type can be `Eigen::Matrix` (e.g. + /// `Eigen::MatrixXd` and `Eigen::MatrixXf`), or its mapped version + /// (e.g. `Eigen::Map`). + /// Only the major- and sub- diagonal parts of + /// the matrix are used. + /// + TridiagQR(ConstGenericMatrix& mat, const Scalar& shift = Scalar(0)) : + UpperHessenbergQR(mat.rows()) + { + this->compute(mat, shift); + } + + /// + /// Conduct the QR factorization of a tridiagonal matrix with an + /// optional shift. + /// + /// \param mat Matrix type can be `Eigen::Matrix` (e.g. + /// `Eigen::MatrixXd` and `Eigen::MatrixXf`), or its mapped version + /// (e.g. `Eigen::Map`). + /// Only the major- and sub- diagonal parts of + /// the matrix are used. + /// + void compute(ConstGenericMatrix& mat, const Scalar& shift = Scalar(0)) + { + this->m_n = mat.rows(); + if (this->m_n != mat.cols()) + throw std::invalid_argument("TridiagQR: matrix must be square"); + + this->m_shift = shift; + m_T_diag.resize(this->m_n); + m_T_lsub.resize(this->m_n - 1); + m_T_usub.resize(this->m_n - 1); + m_T_usub2.resize(this->m_n - 2); + this->m_rot_cos.resize(this->m_n - 1); + this->m_rot_sin.resize(this->m_n - 1); + + m_T_diag.array() = mat.diagonal().array() - this->m_shift; + m_T_lsub.noalias() = mat.diagonal(-1); + m_T_usub.noalias() = m_T_lsub; + + // A number of pointers to avoid repeated address calculation + Scalar *c = this->m_rot_cos.data(), // pointer to the cosine vector + *s = this->m_rot_sin.data(), // pointer to the sine vector + r; + const Index n1 = this->m_n - 1; + for (Index i = 0; i < n1; i++) + { + // diag[i] == T[i, i] + // lsub[i] == T[i + 1, i] + // r = sqrt(T[i, i]^2 + T[i + 1, i]^2) + // c = T[i, i] / r, s = -T[i + 1, i] / r + this->compute_rotation(m_T_diag.coeff(i), m_T_lsub.coeff(i), r, *c, *s); + + // For a complete QR decomposition, + // we first obtain the rotation matrix + // G = [ cos sin] + // [-sin cos] + // and then do T[i:(i + 1), i:(i + 2)] = G' * T[i:(i + 1), i:(i + 2)] + + // Update T[i, i] and T[i + 1, i] + // The updated value of T[i, i] is known to be r + // The updated value of T[i + 1, i] is known to be 0 + m_T_diag.coeffRef(i) = r; + m_T_lsub.coeffRef(i) = Scalar(0); + // Update T[i, i + 1] and T[i + 1, i + 1] + // usub[i] == T[i, i + 1] + // diag[i + 1] == T[i + 1, i + 1] + const Scalar tmp = m_T_usub.coeff(i); + m_T_usub.coeffRef(i) = (*c) * tmp - (*s) * m_T_diag.coeff(i + 1); + m_T_diag.coeffRef(i + 1) = (*s) * tmp + (*c) * m_T_diag.coeff(i + 1); + // Update T[i, i + 2] and T[i + 1, i + 2] + // usub2[i] == T[i, i + 2] + // usub[i + 1] == T[i + 1, i + 2] + if (i < n1 - 1) + { + m_T_usub2.coeffRef(i) = -(*s) * m_T_usub.coeff(i + 1); + m_T_usub.coeffRef(i + 1) *= (*c); + } + + c++; + s++; + + // If we do not need to calculate the R matrix, then + // only the cos and sin sequences are required. + // In such case we only update T[i + 1, (i + 1):(i + 2)] + // T[i + 1, i + 1] = c * T[i + 1, i + 1] + s * T[i, i + 1]; + // T[i + 1, i + 2] *= c; + } + + this->m_computed = true; + } + + /// + /// Return the \f$R\f$ matrix in the QR decomposition, which is an + /// upper triangular matrix. + /// + /// \return Returned matrix type will be `Eigen::Matrix`, depending on + /// the template parameter `Scalar` defined. + /// + Matrix matrix_R() const + { + if (!this->m_computed) + throw std::logic_error("TridiagQR: need to call compute() first"); + + Matrix R = Matrix::Zero(this->m_n, this->m_n); + R.diagonal().noalias() = m_T_diag; + R.diagonal(1).noalias() = m_T_usub; + R.diagonal(2).noalias() = m_T_usub2; + + return R; + } + + /// + /// Overwrite `dest` with \f$Q'HQ = RQ + sI\f$, where \f$H\f$ is the input matrix `mat`, + /// and \f$s\f$ is the shift. The result is a tridiagonal matrix. + /// + /// \param mat The matrix to be overwritten, whose type should be `Eigen::Matrix`, + /// depending on the template parameter `Scalar` defined. + /// + void matrix_QtHQ(Matrix& dest) const + { + if (!this->m_computed) + throw std::logic_error("TridiagQR: need to call compute() first"); + + // Make a copy of the R matrix + dest.resize(this->m_n, this->m_n); + dest.setZero(); + dest.diagonal().noalias() = m_T_diag; + // The upper diagonal refers to m_T_usub + // The 2nd upper subdiagonal will be zero in RQ + + // Compute the RQ matrix + // [m11 m12] points to RQ[i:(i+1), i:(i+1)] + // [0 m22] + // + // Gi = [ cos[i] sin[i]] + // [-sin[i] cos[i]] + const Index n1 = this->m_n - 1; + for (Index i = 0; i < n1; i++) + { + const Scalar c = this->m_rot_cos.coeff(i); + const Scalar s = this->m_rot_sin.coeff(i); + const Scalar m11 = dest.coeff(i, i), + m12 = m_T_usub.coeff(i), + m22 = m_T_diag.coeff(i + 1); + + // Update the diagonal and the lower subdiagonal of dest + dest.coeffRef(i, i) = c * m11 - s * m12; + dest.coeffRef(i + 1, i) = -s * m22; + dest.coeffRef(i + 1, i + 1) = c * m22; + } + + // Copy the lower subdiagonal to upper subdiagonal + dest.diagonal(1).noalias() = dest.diagonal(-1); + + // Add the shift to the diagonal + dest.diagonal().array() += this->m_shift; + } +}; + +/// +/// @} +/// + +} // namespace Spectra + +#endif // UPPER_HESSENBERG_QR_H diff --git a/gtsam/3rdparty/Spectra/MatOp/DenseCholesky.h b/gtsam/3rdparty/Spectra/MatOp/DenseCholesky.h new file mode 100644 index 000000000..c41cae729 --- /dev/null +++ b/gtsam/3rdparty/Spectra/MatOp/DenseCholesky.h @@ -0,0 +1,108 @@ +// Copyright (C) 2016-2019 Yixuan Qiu +// +// This Source Code Form is subject to the terms of the Mozilla +// Public License v. 2.0. If a copy of the MPL was not distributed +// with this file, You can obtain one at https://mozilla.org/MPL/2.0/. + +#ifndef DENSE_CHOLESKY_H +#define DENSE_CHOLESKY_H + +#include +#include +#include +#include "../Util/CompInfo.h" + +namespace Spectra { + +/// +/// \ingroup MatOp +/// +/// This class defines the operations related to Cholesky decomposition on a +/// positive definite matrix, \f$B=LL'\f$, where \f$L\f$ is a lower triangular +/// matrix. It is mainly used in the SymGEigsSolver generalized eigen solver +/// in the Cholesky decomposition mode. +/// +template +class DenseCholesky +{ +private: + typedef Eigen::Index Index; + typedef Eigen::Matrix Matrix; + typedef Eigen::Matrix Vector; + typedef Eigen::Map MapConstMat; + typedef Eigen::Map MapConstVec; + typedef Eigen::Map MapVec; + typedef const Eigen::Ref ConstGenericMatrix; + + const Index m_n; + Eigen::LLT m_decomp; + int m_info; // status of the decomposition + +public: + /// + /// Constructor to create the matrix operation object. + /// + /// \param mat An **Eigen** matrix object, whose type can be + /// `Eigen::Matrix` (e.g. `Eigen::MatrixXd` and + /// `Eigen::MatrixXf`), or its mapped version + /// (e.g. `Eigen::Map`). + /// + DenseCholesky(ConstGenericMatrix& mat) : + m_n(mat.rows()), m_info(NOT_COMPUTED) + { + if (mat.rows() != mat.cols()) + throw std::invalid_argument("DenseCholesky: matrix must be square"); + + m_decomp.compute(mat); + m_info = (m_decomp.info() == Eigen::Success) ? + SUCCESSFUL : + NUMERICAL_ISSUE; + } + + /// + /// Returns the number of rows of the underlying matrix. + /// + Index rows() const { return m_n; } + /// + /// Returns the number of columns of the underlying matrix. + /// + Index cols() const { return m_n; } + + /// + /// Returns the status of the computation. + /// The full list of enumeration values can be found in \ref Enumerations. + /// + int info() const { return m_info; } + + /// + /// Performs the lower triangular solving operation \f$y=L^{-1}x\f$. + /// + /// \param x_in Pointer to the \f$x\f$ vector. + /// \param y_out Pointer to the \f$y\f$ vector. + /// + // y_out = inv(L) * x_in + void lower_triangular_solve(const Scalar* x_in, Scalar* y_out) const + { + MapConstVec x(x_in, m_n); + MapVec y(y_out, m_n); + y.noalias() = m_decomp.matrixL().solve(x); + } + + /// + /// Performs the upper triangular solving operation \f$y=(L')^{-1}x\f$. + /// + /// \param x_in Pointer to the \f$x\f$ vector. + /// \param y_out Pointer to the \f$y\f$ vector. + /// + // y_out = inv(L') * x_in + void upper_triangular_solve(const Scalar* x_in, Scalar* y_out) const + { + MapConstVec x(x_in, m_n); + MapVec y(y_out, m_n); + y.noalias() = m_decomp.matrixU().solve(x); + } +}; + +} // namespace Spectra + +#endif // DENSE_CHOLESKY_H diff --git a/gtsam/3rdparty/Spectra/MatOp/DenseGenComplexShiftSolve.h b/gtsam/3rdparty/Spectra/MatOp/DenseGenComplexShiftSolve.h new file mode 100644 index 000000000..02ad32f8f --- /dev/null +++ b/gtsam/3rdparty/Spectra/MatOp/DenseGenComplexShiftSolve.h @@ -0,0 +1,102 @@ +// Copyright (C) 2016-2019 Yixuan Qiu +// +// This Source Code Form is subject to the terms of the Mozilla +// Public License v. 2.0. If a copy of the MPL was not distributed +// with this file, You can obtain one at https://mozilla.org/MPL/2.0/. + +#ifndef DENSE_GEN_COMPLEX_SHIFT_SOLVE_H +#define DENSE_GEN_COMPLEX_SHIFT_SOLVE_H + +#include +#include +#include + +namespace Spectra { + +/// +/// \ingroup MatOp +/// +/// This class defines the complex shift-solve operation on a general real matrix \f$A\f$, +/// i.e., calculating \f$y=\mathrm{Re}\{(A-\sigma I)^{-1}x\}\f$ for any complex-valued +/// \f$\sigma\f$ and real-valued vector \f$x\f$. It is mainly used in the +/// GenEigsComplexShiftSolver eigen solver. +/// +template +class DenseGenComplexShiftSolve +{ +private: + typedef Eigen::Index Index; + typedef Eigen::Matrix Matrix; + typedef Eigen::Matrix Vector; + typedef Eigen::Map MapConstVec; + typedef Eigen::Map MapVec; + typedef const Eigen::Ref ConstGenericMatrix; + + typedef std::complex Complex; + typedef Eigen::Matrix ComplexMatrix; + typedef Eigen::Matrix ComplexVector; + + typedef Eigen::PartialPivLU ComplexSolver; + + ConstGenericMatrix m_mat; + const Index m_n; + ComplexSolver m_solver; + ComplexVector m_x_cache; + +public: + /// + /// Constructor to create the matrix operation object. + /// + /// \param mat An **Eigen** matrix object, whose type can be + /// `Eigen::Matrix` (e.g. `Eigen::MatrixXd` and + /// `Eigen::MatrixXf`), or its mapped version + /// (e.g. `Eigen::Map`). + /// + DenseGenComplexShiftSolve(ConstGenericMatrix& mat) : + m_mat(mat), m_n(mat.rows()) + { + if (mat.rows() != mat.cols()) + throw std::invalid_argument("DenseGenComplexShiftSolve: matrix must be square"); + } + + /// + /// Return the number of rows of the underlying matrix. + /// + Index rows() const { return m_n; } + /// + /// Return the number of columns of the underlying matrix. + /// + Index cols() const { return m_n; } + + /// + /// Set the complex shift \f$\sigma\f$. + /// + /// \param sigmar Real part of \f$\sigma\f$. + /// \param sigmai Imaginary part of \f$\sigma\f$. + /// + void set_shift(Scalar sigmar, Scalar sigmai) + { + m_solver.compute(m_mat.template cast() - Complex(sigmar, sigmai) * ComplexMatrix::Identity(m_n, m_n)); + m_x_cache.resize(m_n); + m_x_cache.setZero(); + } + + /// + /// Perform the complex shift-solve operation + /// \f$y=\mathrm{Re}\{(A-\sigma I)^{-1}x\}\f$. + /// + /// \param x_in Pointer to the \f$x\f$ vector. + /// \param y_out Pointer to the \f$y\f$ vector. + /// + // y_out = Re( inv(A - sigma * I) * x_in ) + void perform_op(const Scalar* x_in, Scalar* y_out) + { + m_x_cache.real() = MapConstVec(x_in, m_n); + MapVec y(y_out, m_n); + y.noalias() = m_solver.solve(m_x_cache).real(); + } +}; + +} // namespace Spectra + +#endif // DENSE_GEN_COMPLEX_SHIFT_SOLVE_H diff --git a/gtsam/3rdparty/Spectra/MatOp/DenseGenMatProd.h b/gtsam/3rdparty/Spectra/MatOp/DenseGenMatProd.h new file mode 100644 index 000000000..c4ade80a3 --- /dev/null +++ b/gtsam/3rdparty/Spectra/MatOp/DenseGenMatProd.h @@ -0,0 +1,80 @@ +// Copyright (C) 2016-2019 Yixuan Qiu +// +// This Source Code Form is subject to the terms of the Mozilla +// Public License v. 2.0. If a copy of the MPL was not distributed +// with this file, You can obtain one at https://mozilla.org/MPL/2.0/. + +#ifndef DENSE_GEN_MAT_PROD_H +#define DENSE_GEN_MAT_PROD_H + +#include + +namespace Spectra { + +/// +/// \defgroup MatOp Matrix Operations +/// +/// Define matrix operations on existing matrix objects +/// + +/// +/// \ingroup MatOp +/// +/// This class defines the matrix-vector multiplication operation on a +/// general real matrix \f$A\f$, i.e., calculating \f$y=Ax\f$ for any vector +/// \f$x\f$. It is mainly used in the GenEigsSolver and +/// SymEigsSolver eigen solvers. +/// +template +class DenseGenMatProd +{ +private: + typedef Eigen::Index Index; + typedef Eigen::Matrix Matrix; + typedef Eigen::Matrix Vector; + typedef Eigen::Map MapConstVec; + typedef Eigen::Map MapVec; + typedef const Eigen::Ref ConstGenericMatrix; + + ConstGenericMatrix m_mat; + +public: + /// + /// Constructor to create the matrix operation object. + /// + /// \param mat An **Eigen** matrix object, whose type can be + /// `Eigen::Matrix` (e.g. `Eigen::MatrixXd` and + /// `Eigen::MatrixXf`), or its mapped version + /// (e.g. `Eigen::Map`). + /// + DenseGenMatProd(ConstGenericMatrix& mat) : + m_mat(mat) + {} + + /// + /// Return the number of rows of the underlying matrix. + /// + Index rows() const { return m_mat.rows(); } + /// + /// Return the number of columns of the underlying matrix. + /// + Index cols() const { return m_mat.cols(); } + + /// + /// Perform the matrix-vector multiplication operation \f$y=Ax\f$. + /// + /// \param x_in Pointer to the \f$x\f$ vector. + /// \param y_out Pointer to the \f$y\f$ vector. + /// + // y_out = A * x_in + void perform_op(const Scalar* x_in, Scalar* y_out) const + { + MapConstVec x(x_in, m_mat.cols()); + MapVec y(y_out, m_mat.rows()); + y.noalias() = m_mat * x; + } +}; + +} // namespace Spectra + +#endif // DENSE_GEN_MAT_PROD_H diff --git a/gtsam/3rdparty/Spectra/MatOp/DenseGenRealShiftSolve.h b/gtsam/3rdparty/Spectra/MatOp/DenseGenRealShiftSolve.h new file mode 100644 index 000000000..9c93ecc7a --- /dev/null +++ b/gtsam/3rdparty/Spectra/MatOp/DenseGenRealShiftSolve.h @@ -0,0 +1,88 @@ +// Copyright (C) 2016-2019 Yixuan Qiu +// +// This Source Code Form is subject to the terms of the Mozilla +// Public License v. 2.0. If a copy of the MPL was not distributed +// with this file, You can obtain one at https://mozilla.org/MPL/2.0/. + +#ifndef DENSE_GEN_REAL_SHIFT_SOLVE_H +#define DENSE_GEN_REAL_SHIFT_SOLVE_H + +#include +#include +#include + +namespace Spectra { + +/// +/// \ingroup MatOp +/// +/// This class defines the shift-solve operation on a general real matrix \f$A\f$, +/// i.e., calculating \f$y=(A-\sigma I)^{-1}x\f$ for any real \f$\sigma\f$ and +/// vector \f$x\f$. It is mainly used in the GenEigsRealShiftSolver eigen solver. +/// +template +class DenseGenRealShiftSolve +{ +private: + typedef Eigen::Index Index; + typedef Eigen::Matrix Matrix; + typedef Eigen::Matrix Vector; + typedef Eigen::Map MapConstVec; + typedef Eigen::Map MapVec; + typedef const Eigen::Ref ConstGenericMatrix; + + ConstGenericMatrix m_mat; + const Index m_n; + Eigen::PartialPivLU m_solver; + +public: + /// + /// Constructor to create the matrix operation object. + /// + /// \param mat An **Eigen** matrix object, whose type can be + /// `Eigen::Matrix` (e.g. `Eigen::MatrixXd` and + /// `Eigen::MatrixXf`), or its mapped version + /// (e.g. `Eigen::Map`). + /// + DenseGenRealShiftSolve(ConstGenericMatrix& mat) : + m_mat(mat), m_n(mat.rows()) + { + if (mat.rows() != mat.cols()) + throw std::invalid_argument("DenseGenRealShiftSolve: matrix must be square"); + } + + /// + /// Return the number of rows of the underlying matrix. + /// + Index rows() const { return m_n; } + /// + /// Return the number of columns of the underlying matrix. + /// + Index cols() const { return m_n; } + + /// + /// Set the real shift \f$\sigma\f$. + /// + void set_shift(Scalar sigma) + { + m_solver.compute(m_mat - sigma * Matrix::Identity(m_n, m_n)); + } + + /// + /// Perform the shift-solve operation \f$y=(A-\sigma I)^{-1}x\f$. + /// + /// \param x_in Pointer to the \f$x\f$ vector. + /// \param y_out Pointer to the \f$y\f$ vector. + /// + // y_out = inv(A - sigma * I) * x_in + void perform_op(const Scalar* x_in, Scalar* y_out) const + { + MapConstVec x(x_in, m_n); + MapVec y(y_out, m_n); + y.noalias() = m_solver.solve(x); + } +}; + +} // namespace Spectra + +#endif // DENSE_GEN_REAL_SHIFT_SOLVE_H diff --git a/gtsam/3rdparty/Spectra/MatOp/DenseSymMatProd.h b/gtsam/3rdparty/Spectra/MatOp/DenseSymMatProd.h new file mode 100644 index 000000000..76c792686 --- /dev/null +++ b/gtsam/3rdparty/Spectra/MatOp/DenseSymMatProd.h @@ -0,0 +1,73 @@ +// Copyright (C) 2016-2019 Yixuan Qiu +// +// This Source Code Form is subject to the terms of the Mozilla +// Public License v. 2.0. If a copy of the MPL was not distributed +// with this file, You can obtain one at https://mozilla.org/MPL/2.0/. + +#ifndef DENSE_SYM_MAT_PROD_H +#define DENSE_SYM_MAT_PROD_H + +#include + +namespace Spectra { + +/// +/// \ingroup MatOp +/// +/// This class defines the matrix-vector multiplication operation on a +/// symmetric real matrix \f$A\f$, i.e., calculating \f$y=Ax\f$ for any vector +/// \f$x\f$. It is mainly used in the SymEigsSolver eigen solver. +/// +template +class DenseSymMatProd +{ +private: + typedef Eigen::Index Index; + typedef Eigen::Matrix Matrix; + typedef Eigen::Matrix Vector; + typedef Eigen::Map MapConstVec; + typedef Eigen::Map MapVec; + typedef const Eigen::Ref ConstGenericMatrix; + + ConstGenericMatrix m_mat; + +public: + /// + /// Constructor to create the matrix operation object. + /// + /// \param mat An **Eigen** matrix object, whose type can be + /// `Eigen::Matrix` (e.g. `Eigen::MatrixXd` and + /// `Eigen::MatrixXf`), or its mapped version + /// (e.g. `Eigen::Map`). + /// + DenseSymMatProd(ConstGenericMatrix& mat) : + m_mat(mat) + {} + + /// + /// Return the number of rows of the underlying matrix. + /// + Index rows() const { return m_mat.rows(); } + /// + /// Return the number of columns of the underlying matrix. + /// + Index cols() const { return m_mat.cols(); } + + /// + /// Perform the matrix-vector multiplication operation \f$y=Ax\f$. + /// + /// \param x_in Pointer to the \f$x\f$ vector. + /// \param y_out Pointer to the \f$y\f$ vector. + /// + // y_out = A * x_in + void perform_op(const Scalar* x_in, Scalar* y_out) const + { + MapConstVec x(x_in, m_mat.cols()); + MapVec y(y_out, m_mat.rows()); + y.noalias() = m_mat.template selfadjointView() * x; + } +}; + +} // namespace Spectra + +#endif // DENSE_SYM_MAT_PROD_H diff --git a/gtsam/3rdparty/Spectra/MatOp/DenseSymShiftSolve.h b/gtsam/3rdparty/Spectra/MatOp/DenseSymShiftSolve.h new file mode 100644 index 000000000..620aa9413 --- /dev/null +++ b/gtsam/3rdparty/Spectra/MatOp/DenseSymShiftSolve.h @@ -0,0 +1,92 @@ +// Copyright (C) 2016-2019 Yixuan Qiu +// +// This Source Code Form is subject to the terms of the Mozilla +// Public License v. 2.0. If a copy of the MPL was not distributed +// with this file, You can obtain one at https://mozilla.org/MPL/2.0/. + +#ifndef DENSE_SYM_SHIFT_SOLVE_H +#define DENSE_SYM_SHIFT_SOLVE_H + +#include +#include + +#include "../LinAlg/BKLDLT.h" +#include "../Util/CompInfo.h" + +namespace Spectra { + +/// +/// \ingroup MatOp +/// +/// This class defines the shift-solve operation on a real symmetric matrix \f$A\f$, +/// i.e., calculating \f$y=(A-\sigma I)^{-1}x\f$ for any real \f$\sigma\f$ and +/// vector \f$x\f$. It is mainly used in the SymEigsShiftSolver eigen solver. +/// +template +class DenseSymShiftSolve +{ +private: + typedef Eigen::Index Index; + typedef Eigen::Matrix Matrix; + typedef Eigen::Matrix Vector; + typedef Eigen::Map MapConstVec; + typedef Eigen::Map MapVec; + typedef const Eigen::Ref ConstGenericMatrix; + + ConstGenericMatrix m_mat; + const int m_n; + BKLDLT m_solver; + +public: + /// + /// Constructor to create the matrix operation object. + /// + /// \param mat An **Eigen** matrix object, whose type can be + /// `Eigen::Matrix` (e.g. `Eigen::MatrixXd` and + /// `Eigen::MatrixXf`), or its mapped version + /// (e.g. `Eigen::Map`). + /// + DenseSymShiftSolve(ConstGenericMatrix& mat) : + m_mat(mat), m_n(mat.rows()) + { + if (mat.rows() != mat.cols()) + throw std::invalid_argument("DenseSymShiftSolve: matrix must be square"); + } + + /// + /// Return the number of rows of the underlying matrix. + /// + Index rows() const { return m_n; } + /// + /// Return the number of columns of the underlying matrix. + /// + Index cols() const { return m_n; } + + /// + /// Set the real shift \f$\sigma\f$. + /// + void set_shift(Scalar sigma) + { + m_solver.compute(m_mat, Uplo, sigma); + if (m_solver.info() != SUCCESSFUL) + throw std::invalid_argument("DenseSymShiftSolve: factorization failed with the given shift"); + } + + /// + /// Perform the shift-solve operation \f$y=(A-\sigma I)^{-1}x\f$. + /// + /// \param x_in Pointer to the \f$x\f$ vector. + /// \param y_out Pointer to the \f$y\f$ vector. + /// + // y_out = inv(A - sigma * I) * x_in + void perform_op(const Scalar* x_in, Scalar* y_out) const + { + MapConstVec x(x_in, m_n); + MapVec y(y_out, m_n); + y.noalias() = m_solver.solve(x); + } +}; + +} // namespace Spectra + +#endif // DENSE_SYM_SHIFT_SOLVE_H diff --git a/gtsam/3rdparty/Spectra/MatOp/SparseCholesky.h b/gtsam/3rdparty/Spectra/MatOp/SparseCholesky.h new file mode 100644 index 000000000..a73efc389 --- /dev/null +++ b/gtsam/3rdparty/Spectra/MatOp/SparseCholesky.h @@ -0,0 +1,109 @@ +// Copyright (C) 2016-2019 Yixuan Qiu +// +// This Source Code Form is subject to the terms of the Mozilla +// Public License v. 2.0. If a copy of the MPL was not distributed +// with this file, You can obtain one at https://mozilla.org/MPL/2.0/. + +#ifndef SPARSE_CHOLESKY_H +#define SPARSE_CHOLESKY_H + +#include +#include +#include +#include +#include "../Util/CompInfo.h" + +namespace Spectra { + +/// +/// \ingroup MatOp +/// +/// This class defines the operations related to Cholesky decomposition on a +/// sparse positive definite matrix, \f$B=LL'\f$, where \f$L\f$ is a lower triangular +/// matrix. It is mainly used in the SymGEigsSolver generalized eigen solver +/// in the Cholesky decomposition mode. +/// +template +class SparseCholesky +{ +private: + typedef Eigen::Index Index; + typedef Eigen::Matrix Vector; + typedef Eigen::Map MapConstVec; + typedef Eigen::Map MapVec; + typedef Eigen::SparseMatrix SparseMatrix; + typedef const Eigen::Ref ConstGenericSparseMatrix; + + const Index m_n; + Eigen::SimplicialLLT m_decomp; + int m_info; // status of the decomposition + +public: + /// + /// Constructor to create the matrix operation object. + /// + /// \param mat An **Eigen** sparse matrix object, whose type can be + /// `Eigen::SparseMatrix` or its mapped version + /// `Eigen::Map >`. + /// + SparseCholesky(ConstGenericSparseMatrix& mat) : + m_n(mat.rows()) + { + if (mat.rows() != mat.cols()) + throw std::invalid_argument("SparseCholesky: matrix must be square"); + + m_decomp.compute(mat); + m_info = (m_decomp.info() == Eigen::Success) ? + SUCCESSFUL : + NUMERICAL_ISSUE; + } + + /// + /// Returns the number of rows of the underlying matrix. + /// + Index rows() const { return m_n; } + /// + /// Returns the number of columns of the underlying matrix. + /// + Index cols() const { return m_n; } + + /// + /// Returns the status of the computation. + /// The full list of enumeration values can be found in \ref Enumerations. + /// + int info() const { return m_info; } + + /// + /// Performs the lower triangular solving operation \f$y=L^{-1}x\f$. + /// + /// \param x_in Pointer to the \f$x\f$ vector. + /// \param y_out Pointer to the \f$y\f$ vector. + /// + // y_out = inv(L) * x_in + void lower_triangular_solve(const Scalar* x_in, Scalar* y_out) const + { + MapConstVec x(x_in, m_n); + MapVec y(y_out, m_n); + y.noalias() = m_decomp.permutationP() * x; + m_decomp.matrixL().solveInPlace(y); + } + + /// + /// Performs the upper triangular solving operation \f$y=(L')^{-1}x\f$. + /// + /// \param x_in Pointer to the \f$x\f$ vector. + /// \param y_out Pointer to the \f$y\f$ vector. + /// + // y_out = inv(L') * x_in + void upper_triangular_solve(const Scalar* x_in, Scalar* y_out) const + { + MapConstVec x(x_in, m_n); + MapVec y(y_out, m_n); + y.noalias() = m_decomp.matrixU().solve(x); + y = m_decomp.permutationPinv() * y; + } +}; + +} // namespace Spectra + +#endif // SPARSE_CHOLESKY_H diff --git a/gtsam/3rdparty/Spectra/MatOp/SparseGenMatProd.h b/gtsam/3rdparty/Spectra/MatOp/SparseGenMatProd.h new file mode 100644 index 000000000..0cc1f6674 --- /dev/null +++ b/gtsam/3rdparty/Spectra/MatOp/SparseGenMatProd.h @@ -0,0 +1,74 @@ +// Copyright (C) 2016-2019 Yixuan Qiu +// +// This Source Code Form is subject to the terms of the Mozilla +// Public License v. 2.0. If a copy of the MPL was not distributed +// with this file, You can obtain one at https://mozilla.org/MPL/2.0/. + +#ifndef SPARSE_GEN_MAT_PROD_H +#define SPARSE_GEN_MAT_PROD_H + +#include +#include + +namespace Spectra { + +/// +/// \ingroup MatOp +/// +/// This class defines the matrix-vector multiplication operation on a +/// sparse real matrix \f$A\f$, i.e., calculating \f$y=Ax\f$ for any vector +/// \f$x\f$. It is mainly used in the GenEigsSolver and SymEigsSolver +/// eigen solvers. +/// +template +class SparseGenMatProd +{ +private: + typedef Eigen::Index Index; + typedef Eigen::Matrix Vector; + typedef Eigen::Map MapConstVec; + typedef Eigen::Map MapVec; + typedef Eigen::SparseMatrix SparseMatrix; + typedef const Eigen::Ref ConstGenericSparseMatrix; + + ConstGenericSparseMatrix m_mat; + +public: + /// + /// Constructor to create the matrix operation object. + /// + /// \param mat An **Eigen** sparse matrix object, whose type can be + /// `Eigen::SparseMatrix` or its mapped version + /// `Eigen::Map >`. + /// + SparseGenMatProd(ConstGenericSparseMatrix& mat) : + m_mat(mat) + {} + + /// + /// Return the number of rows of the underlying matrix. + /// + Index rows() const { return m_mat.rows(); } + /// + /// Return the number of columns of the underlying matrix. + /// + Index cols() const { return m_mat.cols(); } + + /// + /// Perform the matrix-vector multiplication operation \f$y=Ax\f$. + /// + /// \param x_in Pointer to the \f$x\f$ vector. + /// \param y_out Pointer to the \f$y\f$ vector. + /// + // y_out = A * x_in + void perform_op(const Scalar* x_in, Scalar* y_out) const + { + MapConstVec x(x_in, m_mat.cols()); + MapVec y(y_out, m_mat.rows()); + y.noalias() = m_mat * x; + } +}; + +} // namespace Spectra + +#endif // SPARSE_GEN_MAT_PROD_H diff --git a/gtsam/3rdparty/Spectra/MatOp/SparseGenRealShiftSolve.h b/gtsam/3rdparty/Spectra/MatOp/SparseGenRealShiftSolve.h new file mode 100644 index 000000000..fc6e3c508 --- /dev/null +++ b/gtsam/3rdparty/Spectra/MatOp/SparseGenRealShiftSolve.h @@ -0,0 +1,93 @@ +// Copyright (C) 2016-2019 Yixuan Qiu +// +// This Source Code Form is subject to the terms of the Mozilla +// Public License v. 2.0. If a copy of the MPL was not distributed +// with this file, You can obtain one at https://mozilla.org/MPL/2.0/. + +#ifndef SPARSE_GEN_REAL_SHIFT_SOLVE_H +#define SPARSE_GEN_REAL_SHIFT_SOLVE_H + +#include +#include +#include +#include + +namespace Spectra { + +/// +/// \ingroup MatOp +/// +/// This class defines the shift-solve operation on a sparse real matrix \f$A\f$, +/// i.e., calculating \f$y=(A-\sigma I)^{-1}x\f$ for any real \f$\sigma\f$ and +/// vector \f$x\f$. It is mainly used in the GenEigsRealShiftSolver eigen solver. +/// +template +class SparseGenRealShiftSolve +{ +private: + typedef Eigen::Index Index; + typedef Eigen::Matrix Vector; + typedef Eigen::Map MapConstVec; + typedef Eigen::Map MapVec; + typedef Eigen::SparseMatrix SparseMatrix; + typedef const Eigen::Ref ConstGenericSparseMatrix; + + ConstGenericSparseMatrix m_mat; + const int m_n; + Eigen::SparseLU m_solver; + +public: + /// + /// Constructor to create the matrix operation object. + /// + /// \param mat An **Eigen** sparse matrix object, whose type can be + /// `Eigen::SparseMatrix` or its mapped version + /// `Eigen::Map >`. + /// + SparseGenRealShiftSolve(ConstGenericSparseMatrix& mat) : + m_mat(mat), m_n(mat.rows()) + { + if (mat.rows() != mat.cols()) + throw std::invalid_argument("SparseGenRealShiftSolve: matrix must be square"); + } + + /// + /// Return the number of rows of the underlying matrix. + /// + Index rows() const { return m_n; } + /// + /// Return the number of columns of the underlying matrix. + /// + Index cols() const { return m_n; } + + /// + /// Set the real shift \f$\sigma\f$. + /// + void set_shift(Scalar sigma) + { + SparseMatrix I(m_n, m_n); + I.setIdentity(); + + m_solver.compute(m_mat - sigma * I); + if (m_solver.info() != Eigen::Success) + throw std::invalid_argument("SparseGenRealShiftSolve: factorization failed with the given shift"); + } + + /// + /// Perform the shift-solve operation \f$y=(A-\sigma I)^{-1}x\f$. + /// + /// \param x_in Pointer to the \f$x\f$ vector. + /// \param y_out Pointer to the \f$y\f$ vector. + /// + // y_out = inv(A - sigma * I) * x_in + void perform_op(const Scalar* x_in, Scalar* y_out) const + { + MapConstVec x(x_in, m_n); + MapVec y(y_out, m_n); + y.noalias() = m_solver.solve(x); + } +}; + +} // namespace Spectra + +#endif // SPARSE_GEN_REAL_SHIFT_SOLVE_H diff --git a/gtsam/3rdparty/Spectra/MatOp/SparseRegularInverse.h b/gtsam/3rdparty/Spectra/MatOp/SparseRegularInverse.h new file mode 100644 index 000000000..3abd0c177 --- /dev/null +++ b/gtsam/3rdparty/Spectra/MatOp/SparseRegularInverse.h @@ -0,0 +1,100 @@ +// Copyright (C) 2017-2019 Yixuan Qiu +// +// This Source Code Form is subject to the terms of the Mozilla +// Public License v. 2.0. If a copy of the MPL was not distributed +// with this file, You can obtain one at https://mozilla.org/MPL/2.0/. + +#ifndef SPARSE_REGULAR_INVERSE_H +#define SPARSE_REGULAR_INVERSE_H + +#include +#include +#include +#include + +namespace Spectra { + +/// +/// \ingroup MatOp +/// +/// This class defines matrix operations required by the generalized eigen solver +/// in the regular inverse mode. For a sparse and positive definite matrix \f$B\f$, +/// it implements the matrix-vector product \f$y=Bx\f$ and the linear equation +/// solving operation \f$y=B^{-1}x\f$. +/// +/// This class is intended to be used with the SymGEigsSolver generalized eigen solver +/// in the regular inverse mode. +/// +template +class SparseRegularInverse +{ +private: + typedef Eigen::Index Index; + typedef Eigen::Matrix Vector; + typedef Eigen::Map MapConstVec; + typedef Eigen::Map MapVec; + typedef Eigen::SparseMatrix SparseMatrix; + typedef const Eigen::Ref ConstGenericSparseMatrix; + + ConstGenericSparseMatrix m_mat; + const int m_n; + Eigen::ConjugateGradient m_cg; + +public: + /// + /// Constructor to create the matrix operation object. + /// + /// \param mat An **Eigen** sparse matrix object, whose type can be + /// `Eigen::SparseMatrix` or its mapped version + /// `Eigen::Map >`. + /// + SparseRegularInverse(ConstGenericSparseMatrix& mat) : + m_mat(mat), m_n(mat.rows()) + { + if (mat.rows() != mat.cols()) + throw std::invalid_argument("SparseRegularInverse: matrix must be square"); + + m_cg.compute(mat); + } + + /// + /// Return the number of rows of the underlying matrix. + /// + Index rows() const { return m_n; } + /// + /// Return the number of columns of the underlying matrix. + /// + Index cols() const { return m_n; } + + /// + /// Perform the solving operation \f$y=B^{-1}x\f$. + /// + /// \param x_in Pointer to the \f$x\f$ vector. + /// \param y_out Pointer to the \f$y\f$ vector. + /// + // y_out = inv(B) * x_in + void solve(const Scalar* x_in, Scalar* y_out) const + { + MapConstVec x(x_in, m_n); + MapVec y(y_out, m_n); + y.noalias() = m_cg.solve(x); + } + + /// + /// Perform the matrix-vector multiplication operation \f$y=Bx\f$. + /// + /// \param x_in Pointer to the \f$x\f$ vector. + /// \param y_out Pointer to the \f$y\f$ vector. + /// + // y_out = B * x_in + void mat_prod(const Scalar* x_in, Scalar* y_out) const + { + MapConstVec x(x_in, m_n); + MapVec y(y_out, m_n); + y.noalias() = m_mat.template selfadjointView() * x; + } +}; + +} // namespace Spectra + +#endif // SPARSE_REGULAR_INVERSE_H diff --git a/gtsam/3rdparty/Spectra/MatOp/SparseSymMatProd.h b/gtsam/3rdparty/Spectra/MatOp/SparseSymMatProd.h new file mode 100644 index 000000000..2dd8799eb --- /dev/null +++ b/gtsam/3rdparty/Spectra/MatOp/SparseSymMatProd.h @@ -0,0 +1,73 @@ +// Copyright (C) 2016-2019 Yixuan Qiu +// +// This Source Code Form is subject to the terms of the Mozilla +// Public License v. 2.0. If a copy of the MPL was not distributed +// with this file, You can obtain one at https://mozilla.org/MPL/2.0/. + +#ifndef SPARSE_SYM_MAT_PROD_H +#define SPARSE_SYM_MAT_PROD_H + +#include +#include + +namespace Spectra { + +/// +/// \ingroup MatOp +/// +/// This class defines the matrix-vector multiplication operation on a +/// sparse real symmetric matrix \f$A\f$, i.e., calculating \f$y=Ax\f$ for any vector +/// \f$x\f$. It is mainly used in the SymEigsSolver eigen solver. +/// +template +class SparseSymMatProd +{ +private: + typedef Eigen::Index Index; + typedef Eigen::Matrix Vector; + typedef Eigen::Map MapConstVec; + typedef Eigen::Map MapVec; + typedef Eigen::SparseMatrix SparseMatrix; + typedef const Eigen::Ref ConstGenericSparseMatrix; + + ConstGenericSparseMatrix m_mat; + +public: + /// + /// Constructor to create the matrix operation object. + /// + /// \param mat An **Eigen** sparse matrix object, whose type can be + /// `Eigen::SparseMatrix` or its mapped version + /// `Eigen::Map >`. + /// + SparseSymMatProd(ConstGenericSparseMatrix& mat) : + m_mat(mat) + {} + + /// + /// Return the number of rows of the underlying matrix. + /// + Index rows() const { return m_mat.rows(); } + /// + /// Return the number of columns of the underlying matrix. + /// + Index cols() const { return m_mat.cols(); } + + /// + /// Perform the matrix-vector multiplication operation \f$y=Ax\f$. + /// + /// \param x_in Pointer to the \f$x\f$ vector. + /// \param y_out Pointer to the \f$y\f$ vector. + /// + // y_out = A * x_in + void perform_op(const Scalar* x_in, Scalar* y_out) const + { + MapConstVec x(x_in, m_mat.cols()); + MapVec y(y_out, m_mat.rows()); + y.noalias() = m_mat.template selfadjointView() * x; + } +}; + +} // namespace Spectra + +#endif // SPARSE_SYM_MAT_PROD_H diff --git a/gtsam/3rdparty/Spectra/MatOp/SparseSymShiftSolve.h b/gtsam/3rdparty/Spectra/MatOp/SparseSymShiftSolve.h new file mode 100644 index 000000000..674c6ac52 --- /dev/null +++ b/gtsam/3rdparty/Spectra/MatOp/SparseSymShiftSolve.h @@ -0,0 +1,95 @@ +// Copyright (C) 2016-2019 Yixuan Qiu +// +// This Source Code Form is subject to the terms of the Mozilla +// Public License v. 2.0. If a copy of the MPL was not distributed +// with this file, You can obtain one at https://mozilla.org/MPL/2.0/. + +#ifndef SPARSE_SYM_SHIFT_SOLVE_H +#define SPARSE_SYM_SHIFT_SOLVE_H + +#include +#include +#include +#include + +namespace Spectra { + +/// +/// \ingroup MatOp +/// +/// This class defines the shift-solve operation on a sparse real symmetric matrix \f$A\f$, +/// i.e., calculating \f$y=(A-\sigma I)^{-1}x\f$ for any real \f$\sigma\f$ and +/// vector \f$x\f$. It is mainly used in the SymEigsShiftSolver eigen solver. +/// +template +class SparseSymShiftSolve +{ +private: + typedef Eigen::Index Index; + typedef Eigen::Matrix Vector; + typedef Eigen::Map MapConstVec; + typedef Eigen::Map MapVec; + typedef Eigen::SparseMatrix SparseMatrix; + typedef const Eigen::Ref ConstGenericSparseMatrix; + + ConstGenericSparseMatrix m_mat; + const int m_n; + Eigen::SparseLU m_solver; + +public: + /// + /// Constructor to create the matrix operation object. + /// + /// \param mat An **Eigen** sparse matrix object, whose type can be + /// `Eigen::SparseMatrix` or its mapped version + /// `Eigen::Map >`. + /// + SparseSymShiftSolve(ConstGenericSparseMatrix& mat) : + m_mat(mat), m_n(mat.rows()) + { + if (mat.rows() != mat.cols()) + throw std::invalid_argument("SparseSymShiftSolve: matrix must be square"); + } + + /// + /// Return the number of rows of the underlying matrix. + /// + Index rows() const { return m_n; } + /// + /// Return the number of columns of the underlying matrix. + /// + Index cols() const { return m_n; } + + /// + /// Set the real shift \f$\sigma\f$. + /// + void set_shift(Scalar sigma) + { + SparseMatrix mat = m_mat.template selfadjointView(); + SparseMatrix identity(m_n, m_n); + identity.setIdentity(); + mat = mat - sigma * identity; + m_solver.isSymmetric(true); + m_solver.compute(mat); + if (m_solver.info() != Eigen::Success) + throw std::invalid_argument("SparseSymShiftSolve: factorization failed with the given shift"); + } + + /// + /// Perform the shift-solve operation \f$y=(A-\sigma I)^{-1}x\f$. + /// + /// \param x_in Pointer to the \f$x\f$ vector. + /// \param y_out Pointer to the \f$y\f$ vector. + /// + // y_out = inv(A - sigma * I) * x_in + void perform_op(const Scalar* x_in, Scalar* y_out) const + { + MapConstVec x(x_in, m_n); + MapVec y(y_out, m_n); + y.noalias() = m_solver.solve(x); + } +}; + +} // namespace Spectra + +#endif // SPARSE_SYM_SHIFT_SOLVE_H diff --git a/gtsam/3rdparty/Spectra/MatOp/internal/ArnoldiOp.h b/gtsam/3rdparty/Spectra/MatOp/internal/ArnoldiOp.h new file mode 100644 index 000000000..68654aafd --- /dev/null +++ b/gtsam/3rdparty/Spectra/MatOp/internal/ArnoldiOp.h @@ -0,0 +1,150 @@ +// Copyright (C) 2018-2019 Yixuan Qiu +// +// This Source Code Form is subject to the terms of the Mozilla +// Public License v. 2.0. If a copy of the MPL was not distributed +// with this file, You can obtain one at https://mozilla.org/MPL/2.0/. + +#ifndef ARNOLDI_OP_H +#define ARNOLDI_OP_H + +#include +#include // std::sqrt + +namespace Spectra { + +/// +/// \ingroup Internals +/// @{ +/// + +/// +/// \defgroup Operators Operators +/// +/// Different types of operators. +/// + +/// +/// \ingroup Operators +/// +/// Operators used in the Arnoldi factorization. +/// +template +class ArnoldiOp +{ +private: + typedef Eigen::Index Index; + typedef Eigen::Matrix Vector; + + OpType& m_op; + BOpType& m_Bop; + Vector m_cache; + +public: + ArnoldiOp(OpType* op, BOpType* Bop) : + m_op(*op), m_Bop(*Bop), m_cache(op->rows()) + {} + + inline Index rows() const { return m_op.rows(); } + + // In generalized eigenvalue problem Ax=lambda*Bx, define the inner product to be = x'By. + // For regular eigenvalue problems, it is the usual inner product = x'y + + // Compute = x'By + // x and y are two vectors + template + Scalar inner_product(const Arg1& x, const Arg2& y) + { + m_Bop.mat_prod(y.data(), m_cache.data()); + return x.dot(m_cache); + } + + // Compute res = = X'By + // X is a matrix, y is a vector, res is a vector + template + void trans_product(const Arg1& x, const Arg2& y, Eigen::Ref res) + { + m_Bop.mat_prod(y.data(), m_cache.data()); + res.noalias() = x.transpose() * m_cache; + } + + // B-norm of a vector, ||x||_B = sqrt(x'Bx) + template + Scalar norm(const Arg& x) + { + using std::sqrt; + return sqrt(inner_product(x, x)); + } + + // The "A" operator to generate the Krylov subspace + inline void perform_op(const Scalar* x_in, Scalar* y_out) + { + m_op.perform_op(x_in, y_out); + } +}; + +/// +/// \ingroup Operators +/// +/// Placeholder for the B-operator when \f$B = I\f$. +/// +class IdentityBOp +{}; + +/// +/// \ingroup Operators +/// +/// Partial specialization for the case \f$B = I\f$. +/// +template +class ArnoldiOp +{ +private: + typedef Eigen::Index Index; + typedef Eigen::Matrix Vector; + + OpType& m_op; + +public: + ArnoldiOp(OpType* op, IdentityBOp* /*Bop*/) : + m_op(*op) + {} + + inline Index rows() const { return m_op.rows(); } + + // Compute = x'y + // x and y are two vectors + template + Scalar inner_product(const Arg1& x, const Arg2& y) const + { + return x.dot(y); + } + + // Compute res = = X'y + // X is a matrix, y is a vector, res is a vector + template + void trans_product(const Arg1& x, const Arg2& y, Eigen::Ref res) const + { + res.noalias() = x.transpose() * y; + } + + // B-norm of a vector. For regular eigenvalue problems it is simply the L2 norm + template + Scalar norm(const Arg& x) + { + return x.norm(); + } + + // The "A" operator to generate the Krylov subspace + inline void perform_op(const Scalar* x_in, Scalar* y_out) + { + m_op.perform_op(x_in, y_out); + } +}; + +/// +/// @} +/// + +} // namespace Spectra + +#endif // ARNOLDI_OP_H diff --git a/gtsam/3rdparty/Spectra/MatOp/internal/SymGEigsCholeskyOp.h b/gtsam/3rdparty/Spectra/MatOp/internal/SymGEigsCholeskyOp.h new file mode 100644 index 000000000..fa9958352 --- /dev/null +++ b/gtsam/3rdparty/Spectra/MatOp/internal/SymGEigsCholeskyOp.h @@ -0,0 +1,75 @@ +// Copyright (C) 2016-2019 Yixuan Qiu +// +// This Source Code Form is subject to the terms of the Mozilla +// Public License v. 2.0. If a copy of the MPL was not distributed +// with this file, You can obtain one at https://mozilla.org/MPL/2.0/. + +#ifndef SYM_GEIGS_CHOLESKY_OP_H +#define SYM_GEIGS_CHOLESKY_OP_H + +#include +#include "../DenseSymMatProd.h" +#include "../DenseCholesky.h" + +namespace Spectra { + +/// +/// \ingroup Operators +/// +/// This class defines the matrix operation for generalized eigen solver in the +/// Cholesky decomposition mode. It calculates \f$y=L^{-1}A(L')^{-1}x\f$ for any +/// vector \f$x\f$, where \f$L\f$ is the Cholesky decomposition of \f$B\f$. +/// This class is intended for internal use. +/// +template , + typename BOpType = DenseCholesky > +class SymGEigsCholeskyOp +{ +private: + typedef Eigen::Index Index; + typedef Eigen::Matrix Matrix; + typedef Eigen::Matrix Vector; + + OpType& m_op; + BOpType& m_Bop; + Vector m_cache; // temporary working space + +public: + /// + /// Constructor to create the matrix operation object. + /// + /// \param op Pointer to the \f$A\f$ matrix operation object. + /// \param Bop Pointer to the \f$B\f$ matrix operation object. + /// + SymGEigsCholeskyOp(OpType& op, BOpType& Bop) : + m_op(op), m_Bop(Bop), m_cache(op.rows()) + {} + + /// + /// Return the number of rows of the underlying matrix. + /// + Index rows() const { return m_Bop.rows(); } + /// + /// Return the number of columns of the underlying matrix. + /// + Index cols() const { return m_Bop.rows(); } + + /// + /// Perform the matrix operation \f$y=L^{-1}A(L')^{-1}x\f$. + /// + /// \param x_in Pointer to the \f$x\f$ vector. + /// \param y_out Pointer to the \f$y\f$ vector. + /// + // y_out = inv(L) * A * inv(L') * x_in + void perform_op(const Scalar* x_in, Scalar* y_out) + { + m_Bop.upper_triangular_solve(x_in, y_out); + m_op.perform_op(y_out, m_cache.data()); + m_Bop.lower_triangular_solve(m_cache.data(), y_out); + } +}; + +} // namespace Spectra + +#endif // SYM_GEIGS_CHOLESKY_OP_H diff --git a/gtsam/3rdparty/Spectra/MatOp/internal/SymGEigsRegInvOp.h b/gtsam/3rdparty/Spectra/MatOp/internal/SymGEigsRegInvOp.h new file mode 100644 index 000000000..514269c7f --- /dev/null +++ b/gtsam/3rdparty/Spectra/MatOp/internal/SymGEigsRegInvOp.h @@ -0,0 +1,72 @@ +// Copyright (C) 2017-2019 Yixuan Qiu +// +// This Source Code Form is subject to the terms of the Mozilla +// Public License v. 2.0. If a copy of the MPL was not distributed +// with this file, You can obtain one at https://mozilla.org/MPL/2.0/. + +#ifndef SYM_GEIGS_REG_INV_OP_H +#define SYM_GEIGS_REG_INV_OP_H + +#include +#include "../SparseSymMatProd.h" +#include "../SparseRegularInverse.h" + +namespace Spectra { + +/// +/// \ingroup Operators +/// +/// This class defines the matrix operation for generalized eigen solver in the +/// regular inverse mode. This class is intended for internal use. +/// +template , + typename BOpType = SparseRegularInverse > +class SymGEigsRegInvOp +{ +private: + typedef Eigen::Index Index; + typedef Eigen::Matrix Matrix; + typedef Eigen::Matrix Vector; + + OpType& m_op; + BOpType& m_Bop; + Vector m_cache; // temporary working space + +public: + /// + /// Constructor to create the matrix operation object. + /// + /// \param op Pointer to the \f$A\f$ matrix operation object. + /// \param Bop Pointer to the \f$B\f$ matrix operation object. + /// + SymGEigsRegInvOp(OpType& op, BOpType& Bop) : + m_op(op), m_Bop(Bop), m_cache(op.rows()) + {} + + /// + /// Return the number of rows of the underlying matrix. + /// + Index rows() const { return m_Bop.rows(); } + /// + /// Return the number of columns of the underlying matrix. + /// + Index cols() const { return m_Bop.rows(); } + + /// + /// Perform the matrix operation \f$y=B^{-1}Ax\f$. + /// + /// \param x_in Pointer to the \f$x\f$ vector. + /// \param y_out Pointer to the \f$y\f$ vector. + /// + // y_out = inv(B) * A * x_in + void perform_op(const Scalar* x_in, Scalar* y_out) + { + m_op.perform_op(x_in, m_cache.data()); + m_Bop.solve(m_cache.data(), y_out); + } +}; + +} // namespace Spectra + +#endif // SYM_GEIGS_REG_INV_OP_H diff --git a/gtsam/3rdparty/Spectra/SymEigsBase.h b/gtsam/3rdparty/Spectra/SymEigsBase.h new file mode 100644 index 000000000..9601425d5 --- /dev/null +++ b/gtsam/3rdparty/Spectra/SymEigsBase.h @@ -0,0 +1,448 @@ +// Copyright (C) 2018-2019 Yixuan Qiu +// +// This Source Code Form is subject to the terms of the Mozilla +// Public License v. 2.0. If a copy of the MPL was not distributed +// with this file, You can obtain one at https://mozilla.org/MPL/2.0/. + +#ifndef SYM_EIGS_BASE_H +#define SYM_EIGS_BASE_H + +#include +#include // std::vector +#include // std::abs, std::pow, std::sqrt +#include // std::min, std::copy +#include // std::invalid_argument + +#include "Util/TypeTraits.h" +#include "Util/SelectionRule.h" +#include "Util/CompInfo.h" +#include "Util/SimpleRandom.h" +#include "MatOp/internal/ArnoldiOp.h" +#include "LinAlg/UpperHessenbergQR.h" +#include "LinAlg/TridiagEigen.h" +#include "LinAlg/Lanczos.h" + +namespace Spectra { + +/// +/// \defgroup EigenSolver Eigen Solvers +/// +/// Eigen solvers for different types of problems. +/// + +/// +/// \ingroup EigenSolver +/// +/// This is the base class for symmetric eigen solvers, mainly for internal use. +/// It is kept here to provide the documentation for member functions of concrete eigen solvers +/// such as SymEigsSolver and SymEigsShiftSolver. +/// +template +class SymEigsBase +{ +private: + typedef Eigen::Index Index; + typedef Eigen::Matrix Matrix; + typedef Eigen::Matrix Vector; + typedef Eigen::Array Array; + typedef Eigen::Array BoolArray; + typedef Eigen::Map MapMat; + typedef Eigen::Map MapVec; + typedef Eigen::Map MapConstVec; + + typedef ArnoldiOp ArnoldiOpType; + typedef Lanczos LanczosFac; + +protected: + // clang-format off + OpType* m_op; // object to conduct matrix operation, + // e.g. matrix-vector product + const Index m_n; // dimension of matrix A + const Index m_nev; // number of eigenvalues requested + const Index m_ncv; // dimension of Krylov subspace in the Lanczos method + Index m_nmatop; // number of matrix operations called + Index m_niter; // number of restarting iterations + + LanczosFac m_fac; // Lanczos factorization + Vector m_ritz_val; // Ritz values + +private: + Matrix m_ritz_vec; // Ritz vectors + Vector m_ritz_est; // last row of m_ritz_vec, also called the Ritz estimates + BoolArray m_ritz_conv; // indicator of the convergence of Ritz values + int m_info; // status of the computation + + const Scalar m_near_0; // a very small value, but 1.0 / m_near_0 does not overflow + // ~= 1e-307 for the "double" type + const Scalar m_eps; // the machine precision, ~= 1e-16 for the "double" type + const Scalar m_eps23; // m_eps^(2/3), used to test the convergence + // clang-format on + + // Implicitly restarted Lanczos factorization + void restart(Index k) + { + if (k >= m_ncv) + return; + + TridiagQR decomp(m_ncv); + Matrix Q = Matrix::Identity(m_ncv, m_ncv); + + for (Index i = k; i < m_ncv; i++) + { + // QR decomposition of H-mu*I, mu is the shift + decomp.compute(m_fac.matrix_H(), m_ritz_val[i]); + + // Q -> Q * Qi + decomp.apply_YQ(Q); + // H -> Q'HQ + // Since QR = H - mu * I, we have H = QR + mu * I + // and therefore Q'HQ = RQ + mu * I + m_fac.compress_H(decomp); + } + + m_fac.compress_V(Q); + m_fac.factorize_from(k, m_ncv, m_nmatop); + + retrieve_ritzpair(); + } + + // Calculates the number of converged Ritz values + Index num_converged(Scalar tol) + { + // thresh = tol * max(m_eps23, abs(theta)), theta for Ritz value + Array thresh = tol * m_ritz_val.head(m_nev).array().abs().max(m_eps23); + Array resid = m_ritz_est.head(m_nev).array().abs() * m_fac.f_norm(); + // Converged "wanted" Ritz values + m_ritz_conv = (resid < thresh); + + return m_ritz_conv.cast().sum(); + } + + // Returns the adjusted nev for restarting + Index nev_adjusted(Index nconv) + { + using std::abs; + + Index nev_new = m_nev; + for (Index i = m_nev; i < m_ncv; i++) + if (abs(m_ritz_est[i]) < m_near_0) + nev_new++; + + // Adjust nev_new, according to dsaup2.f line 677~684 in ARPACK + nev_new += std::min(nconv, (m_ncv - nev_new) / 2); + if (nev_new == 1 && m_ncv >= 6) + nev_new = m_ncv / 2; + else if (nev_new == 1 && m_ncv > 2) + nev_new = 2; + + if (nev_new > m_ncv - 1) + nev_new = m_ncv - 1; + + return nev_new; + } + + // Retrieves and sorts Ritz values and Ritz vectors + void retrieve_ritzpair() + { + TridiagEigen decomp(m_fac.matrix_H()); + const Vector& evals = decomp.eigenvalues(); + const Matrix& evecs = decomp.eigenvectors(); + + SortEigenvalue sorting(evals.data(), evals.size()); + std::vector ind = sorting.index(); + + // For BOTH_ENDS, the eigenvalues are sorted according + // to the LARGEST_ALGE rule, so we need to move those smallest + // values to the left + // The order would be + // Largest => Smallest => 2nd largest => 2nd smallest => ... + // We keep this order since the first k values will always be + // the wanted collection, no matter k is nev_updated (used in restart()) + // or is nev (used in sort_ritzpair()) + if (SelectionRule == BOTH_ENDS) + { + std::vector ind_copy(ind); + for (Index i = 0; i < m_ncv; i++) + { + // If i is even, pick values from the left (large values) + // If i is odd, pick values from the right (small values) + if (i % 2 == 0) + ind[i] = ind_copy[i / 2]; + else + ind[i] = ind_copy[m_ncv - 1 - i / 2]; + } + } + + // Copy the Ritz values and vectors to m_ritz_val and m_ritz_vec, respectively + for (Index i = 0; i < m_ncv; i++) + { + m_ritz_val[i] = evals[ind[i]]; + m_ritz_est[i] = evecs(m_ncv - 1, ind[i]); + } + for (Index i = 0; i < m_nev; i++) + { + m_ritz_vec.col(i).noalias() = evecs.col(ind[i]); + } + } + +protected: + // Sorts the first nev Ritz pairs in the specified order + // This is used to return the final results + virtual void sort_ritzpair(int sort_rule) + { + // First make sure that we have a valid index vector + SortEigenvalue sorting(m_ritz_val.data(), m_nev); + std::vector ind = sorting.index(); + + switch (sort_rule) + { + case LARGEST_ALGE: + break; + case LARGEST_MAGN: + { + SortEigenvalue sorting(m_ritz_val.data(), m_nev); + ind = sorting.index(); + break; + } + case SMALLEST_ALGE: + { + SortEigenvalue sorting(m_ritz_val.data(), m_nev); + ind = sorting.index(); + break; + } + case SMALLEST_MAGN: + { + SortEigenvalue sorting(m_ritz_val.data(), m_nev); + ind = sorting.index(); + break; + } + default: + throw std::invalid_argument("unsupported sorting rule"); + } + + Vector new_ritz_val(m_ncv); + Matrix new_ritz_vec(m_ncv, m_nev); + BoolArray new_ritz_conv(m_nev); + + for (Index i = 0; i < m_nev; i++) + { + new_ritz_val[i] = m_ritz_val[ind[i]]; + new_ritz_vec.col(i).noalias() = m_ritz_vec.col(ind[i]); + new_ritz_conv[i] = m_ritz_conv[ind[i]]; + } + + m_ritz_val.swap(new_ritz_val); + m_ritz_vec.swap(new_ritz_vec); + m_ritz_conv.swap(new_ritz_conv); + } + +public: + /// \cond + + SymEigsBase(OpType* op, BOpType* Bop, Index nev, Index ncv) : + m_op(op), + m_n(m_op->rows()), + m_nev(nev), + m_ncv(ncv > m_n ? m_n : ncv), + m_nmatop(0), + m_niter(0), + m_fac(ArnoldiOpType(op, Bop), m_ncv), + m_info(NOT_COMPUTED), + m_near_0(TypeTraits::min() * Scalar(10)), + m_eps(Eigen::NumTraits::epsilon()), + m_eps23(Eigen::numext::pow(m_eps, Scalar(2.0) / 3)) + { + if (nev < 1 || nev > m_n - 1) + throw std::invalid_argument("nev must satisfy 1 <= nev <= n - 1, n is the size of matrix"); + + if (ncv <= nev || ncv > m_n) + throw std::invalid_argument("ncv must satisfy nev < ncv <= n, n is the size of matrix"); + } + + /// + /// Virtual destructor + /// + virtual ~SymEigsBase() {} + + /// \endcond + + /// + /// Initializes the solver by providing an initial residual vector. + /// + /// \param init_resid Pointer to the initial residual vector. + /// + /// **Spectra** (and also **ARPACK**) uses an iterative algorithm + /// to find eigenvalues. This function allows the user to provide the initial + /// residual vector. + /// + void init(const Scalar* init_resid) + { + // Reset all matrices/vectors to zero + m_ritz_val.resize(m_ncv); + m_ritz_vec.resize(m_ncv, m_nev); + m_ritz_est.resize(m_ncv); + m_ritz_conv.resize(m_nev); + + m_ritz_val.setZero(); + m_ritz_vec.setZero(); + m_ritz_est.setZero(); + m_ritz_conv.setZero(); + + m_nmatop = 0; + m_niter = 0; + + // Initialize the Lanczos factorization + MapConstVec v0(init_resid, m_n); + m_fac.init(v0, m_nmatop); + } + + /// + /// Initializes the solver by providing a random initial residual vector. + /// + /// This overloaded function generates a random initial residual vector + /// (with a fixed random seed) for the algorithm. Elements in the vector + /// follow independent Uniform(-0.5, 0.5) distribution. + /// + void init() + { + SimpleRandom rng(0); + Vector init_resid = rng.random_vec(m_n); + init(init_resid.data()); + } + + /// + /// Conducts the major computation procedure. + /// + /// \param maxit Maximum number of iterations allowed in the algorithm. + /// \param tol Precision parameter for the calculated eigenvalues. + /// \param sort_rule Rule to sort the eigenvalues and eigenvectors. + /// Supported values are + /// `Spectra::LARGEST_ALGE`, `Spectra::LARGEST_MAGN`, + /// `Spectra::SMALLEST_ALGE` and `Spectra::SMALLEST_MAGN`, + /// for example `LARGEST_ALGE` indicates that largest eigenvalues + /// come first. Note that this argument is only used to + /// **sort** the final result, and the **selection** rule + /// (e.g. selecting the largest or smallest eigenvalues in the + /// full spectrum) is specified by the template parameter + /// `SelectionRule` of SymEigsSolver. + /// + /// \return Number of converged eigenvalues. + /// + Index compute(Index maxit = 1000, Scalar tol = 1e-10, int sort_rule = LARGEST_ALGE) + { + // The m-step Lanczos factorization + m_fac.factorize_from(1, m_ncv, m_nmatop); + retrieve_ritzpair(); + // Restarting + Index i, nconv = 0, nev_adj; + for (i = 0; i < maxit; i++) + { + nconv = num_converged(tol); + if (nconv >= m_nev) + break; + + nev_adj = nev_adjusted(nconv); + restart(nev_adj); + } + // Sorting results + sort_ritzpair(sort_rule); + + m_niter += i + 1; + m_info = (nconv >= m_nev) ? SUCCESSFUL : NOT_CONVERGING; + + return std::min(m_nev, nconv); + } + + /// + /// Returns the status of the computation. + /// The full list of enumeration values can be found in \ref Enumerations. + /// + int info() const { return m_info; } + + /// + /// Returns the number of iterations used in the computation. + /// + Index num_iterations() const { return m_niter; } + + /// + /// Returns the number of matrix operations used in the computation. + /// + Index num_operations() const { return m_nmatop; } + + /// + /// Returns the converged eigenvalues. + /// + /// \return A vector containing the eigenvalues. + /// Returned vector type will be `Eigen::Vector`, depending on + /// the template parameter `Scalar` defined. + /// + Vector eigenvalues() const + { + const Index nconv = m_ritz_conv.cast().sum(); + Vector res(nconv); + + if (!nconv) + return res; + + Index j = 0; + for (Index i = 0; i < m_nev; i++) + { + if (m_ritz_conv[i]) + { + res[j] = m_ritz_val[i]; + j++; + } + } + + return res; + } + + /// + /// Returns the eigenvectors associated with the converged eigenvalues. + /// + /// \param nvec The number of eigenvectors to return. + /// + /// \return A matrix containing the eigenvectors. + /// Returned matrix type will be `Eigen::Matrix`, + /// depending on the template parameter `Scalar` defined. + /// + virtual Matrix eigenvectors(Index nvec) const + { + const Index nconv = m_ritz_conv.cast().sum(); + nvec = std::min(nvec, nconv); + Matrix res(m_n, nvec); + + if (!nvec) + return res; + + Matrix ritz_vec_conv(m_ncv, nvec); + Index j = 0; + for (Index i = 0; i < m_nev && j < nvec; i++) + { + if (m_ritz_conv[i]) + { + ritz_vec_conv.col(j).noalias() = m_ritz_vec.col(i); + j++; + } + } + + res.noalias() = m_fac.matrix_V() * ritz_vec_conv; + + return res; + } + + /// + /// Returns all converged eigenvectors. + /// + virtual Matrix eigenvectors() const + { + return eigenvectors(m_nev); + } +}; + +} // namespace Spectra + +#endif // SYM_EIGS_BASE_H diff --git a/gtsam/3rdparty/Spectra/SymEigsShiftSolver.h b/gtsam/3rdparty/Spectra/SymEigsShiftSolver.h new file mode 100644 index 000000000..e2b410cb1 --- /dev/null +++ b/gtsam/3rdparty/Spectra/SymEigsShiftSolver.h @@ -0,0 +1,203 @@ +// Copyright (C) 2016-2019 Yixuan Qiu +// +// This Source Code Form is subject to the terms of the Mozilla +// Public License v. 2.0. If a copy of the MPL was not distributed +// with this file, You can obtain one at https://mozilla.org/MPL/2.0/. + +#ifndef SYM_EIGS_SHIFT_SOLVER_H +#define SYM_EIGS_SHIFT_SOLVER_H + +#include + +#include "SymEigsBase.h" +#include "Util/SelectionRule.h" +#include "MatOp/DenseSymShiftSolve.h" + +namespace Spectra { + +/// +/// \ingroup EigenSolver +/// +/// This class implements the eigen solver for real symmetric matrices using +/// the **shift-and-invert mode**. The background information of the symmetric +/// eigen solver is documented in the SymEigsSolver class. Here we focus on +/// explaining the shift-and-invert mode. +/// +/// The shift-and-invert mode is based on the following fact: +/// If \f$\lambda\f$ and \f$x\f$ are a pair of eigenvalue and eigenvector of +/// matrix \f$A\f$, such that \f$Ax=\lambda x\f$, then for any \f$\sigma\f$, +/// we have +/// \f[(A-\sigma I)^{-1}x=\nu x\f] +/// where +/// \f[\nu=\frac{1}{\lambda-\sigma}\f] +/// which indicates that \f$(\nu, x)\f$ is an eigenpair of the matrix +/// \f$(A-\sigma I)^{-1}\f$. +/// +/// Therefore, if we pass the matrix operation \f$(A-\sigma I)^{-1}y\f$ +/// (rather than \f$Ay\f$) to the eigen solver, then we would get the desired +/// values of \f$\nu\f$, and \f$\lambda\f$ can also be easily obtained by noting +/// that \f$\lambda=\sigma+\nu^{-1}\f$. +/// +/// The reason why we need this type of manipulation is that +/// the algorithm of **Spectra** (and also **ARPACK**) +/// is good at finding eigenvalues with large magnitude, but may fail in looking +/// for eigenvalues that are close to zero. However, if we really need them, we +/// can set \f$\sigma=0\f$, find the largest eigenvalues of \f$A^{-1}\f$, and then +/// transform back to \f$\lambda\f$, since in this case largest values of \f$\nu\f$ +/// implies smallest values of \f$\lambda\f$. +/// +/// To summarize, in the shift-and-invert mode, the selection rule will apply to +/// \f$\nu=1/(\lambda-\sigma)\f$ rather than \f$\lambda\f$. So a selection rule +/// of `LARGEST_MAGN` combined with shift \f$\sigma\f$ will find eigenvalues of +/// \f$A\f$ that are closest to \f$\sigma\f$. But note that the eigenvalues() +/// method will always return the eigenvalues in the original problem (i.e., +/// returning \f$\lambda\f$ rather than \f$\nu\f$), and eigenvectors are the +/// same for both the original problem and the shifted-and-inverted problem. +/// +/// \tparam Scalar The element type of the matrix. +/// Currently supported types are `float`, `double` and `long double`. +/// \tparam SelectionRule An enumeration value indicating the selection rule of +/// the shifted-and-inverted eigenvalues. +/// The full list of enumeration values can be found in +/// \ref Enumerations. +/// \tparam OpType The name of the matrix operation class. Users could either +/// use the wrapper classes such as DenseSymShiftSolve and +/// SparseSymShiftSolve, or define their +/// own that implements all the public member functions as in +/// DenseSymShiftSolve. +/// +/// Below is an example that illustrates the use of the shift-and-invert mode: +/// +/// \code{.cpp} +/// #include +/// #include +/// // is implicitly included +/// #include +/// +/// using namespace Spectra; +/// +/// int main() +/// { +/// // A size-10 diagonal matrix with elements 1, 2, ..., 10 +/// Eigen::MatrixXd M = Eigen::MatrixXd::Zero(10, 10); +/// for(int i = 0; i < M.rows(); i++) +/// M(i, i) = i + 1; +/// +/// // Construct matrix operation object using the wrapper class +/// DenseSymShiftSolve op(M); +/// +/// // Construct eigen solver object with shift 0 +/// // This will find eigenvalues that are closest to 0 +/// SymEigsShiftSolver< double, LARGEST_MAGN, +/// DenseSymShiftSolve > eigs(&op, 3, 6, 0.0); +/// +/// eigs.init(); +/// eigs.compute(); +/// if(eigs.info() == SUCCESSFUL) +/// { +/// Eigen::VectorXd evalues = eigs.eigenvalues(); +/// // Will get (3.0, 2.0, 1.0) +/// std::cout << "Eigenvalues found:\n" << evalues << std::endl; +/// } +/// +/// return 0; +/// } +/// \endcode +/// +/// Also an example for user-supplied matrix shift-solve operation class: +/// +/// \code{.cpp} +/// #include +/// #include +/// #include +/// +/// using namespace Spectra; +/// +/// // M = diag(1, 2, ..., 10) +/// class MyDiagonalTenShiftSolve +/// { +/// private: +/// double sigma_; +/// public: +/// int rows() { return 10; } +/// int cols() { return 10; } +/// void set_shift(double sigma) { sigma_ = sigma; } +/// // y_out = inv(A - sigma * I) * x_in +/// // inv(A - sigma * I) = diag(1/(1-sigma), 1/(2-sigma), ...) +/// void perform_op(double *x_in, double *y_out) +/// { +/// for(int i = 0; i < rows(); i++) +/// { +/// y_out[i] = x_in[i] / (i + 1 - sigma_); +/// } +/// } +/// }; +/// +/// int main() +/// { +/// MyDiagonalTenShiftSolve op; +/// // Find three eigenvalues that are closest to 3.14 +/// SymEigsShiftSolver eigs(&op, 3, 6, 3.14); +/// eigs.init(); +/// eigs.compute(); +/// if(eigs.info() == SUCCESSFUL) +/// { +/// Eigen::VectorXd evalues = eigs.eigenvalues(); +/// // Will get (4.0, 3.0, 2.0) +/// std::cout << "Eigenvalues found:\n" << evalues << std::endl; +/// } +/// +/// return 0; +/// } +/// \endcode +/// +template > +class SymEigsShiftSolver : public SymEigsBase +{ +private: + typedef Eigen::Index Index; + typedef Eigen::Array Array; + + const Scalar m_sigma; + + // First transform back the Ritz values, and then sort + void sort_ritzpair(int sort_rule) + { + Array m_ritz_val_org = Scalar(1.0) / this->m_ritz_val.head(this->m_nev).array() + m_sigma; + this->m_ritz_val.head(this->m_nev) = m_ritz_val_org; + SymEigsBase::sort_ritzpair(sort_rule); + } + +public: + /// + /// Constructor to create a eigen solver object using the shift-and-invert mode. + /// + /// \param op Pointer to the matrix operation object, which should implement + /// the shift-solve operation of \f$A\f$: calculating + /// \f$(A-\sigma I)^{-1}v\f$ for any vector \f$v\f$. Users could either + /// create the object from the wrapper class such as DenseSymShiftSolve, or + /// define their own that implements all the public member functions + /// as in DenseSymShiftSolve. + /// \param nev Number of eigenvalues requested. This should satisfy \f$1\le nev \le n-1\f$, + /// where \f$n\f$ is the size of matrix. + /// \param ncv Parameter that controls the convergence speed of the algorithm. + /// Typically a larger `ncv_` means faster convergence, but it may + /// also result in greater memory use and more matrix operations + /// in each iteration. This parameter must satisfy \f$nev < ncv \le n\f$, + /// and is advised to take \f$ncv \ge 2\cdot nev\f$. + /// \param sigma The value of the shift. + /// + SymEigsShiftSolver(OpType* op, Index nev, Index ncv, Scalar sigma) : + SymEigsBase(op, NULL, nev, ncv), + m_sigma(sigma) + { + this->m_op->set_shift(m_sigma); + } +}; + +} // namespace Spectra + +#endif // SYM_EIGS_SHIFT_SOLVER_H diff --git a/gtsam/3rdparty/Spectra/SymEigsSolver.h b/gtsam/3rdparty/Spectra/SymEigsSolver.h new file mode 100644 index 000000000..404df1e52 --- /dev/null +++ b/gtsam/3rdparty/Spectra/SymEigsSolver.h @@ -0,0 +1,171 @@ +// Copyright (C) 2016-2019 Yixuan Qiu +// +// This Source Code Form is subject to the terms of the Mozilla +// Public License v. 2.0. If a copy of the MPL was not distributed +// with this file, You can obtain one at https://mozilla.org/MPL/2.0/. + +#ifndef SYM_EIGS_SOLVER_H +#define SYM_EIGS_SOLVER_H + +#include + +#include "SymEigsBase.h" +#include "Util/SelectionRule.h" +#include "MatOp/DenseSymMatProd.h" + +namespace Spectra { + +/// +/// \ingroup EigenSolver +/// +/// This class implements the eigen solver for real symmetric matrices, i.e., +/// to solve \f$Ax=\lambda x\f$ where \f$A\f$ is symmetric. +/// +/// **Spectra** is designed to calculate a specified number (\f$k\f$) +/// of eigenvalues of a large square matrix (\f$A\f$). Usually \f$k\f$ is much +/// less than the size of the matrix (\f$n\f$), so that only a few eigenvalues +/// and eigenvectors are computed. +/// +/// Rather than providing the whole \f$A\f$ matrix, the algorithm only requires +/// the matrix-vector multiplication operation of \f$A\f$. Therefore, users of +/// this solver need to supply a class that computes the result of \f$Av\f$ +/// for any given vector \f$v\f$. The name of this class should be given to +/// the template parameter `OpType`, and instance of this class passed to +/// the constructor of SymEigsSolver. +/// +/// If the matrix \f$A\f$ is already stored as a matrix object in **Eigen**, +/// for example `Eigen::MatrixXd`, then there is an easy way to construct such +/// matrix operation class, by using the built-in wrapper class DenseSymMatProd +/// which wraps an existing matrix object in **Eigen**. This is also the +/// default template parameter for SymEigsSolver. For sparse matrices, the +/// wrapper class SparseSymMatProd can be used similarly. +/// +/// If the users need to define their own matrix-vector multiplication operation +/// class, it should implement all the public member functions as in DenseSymMatProd. +/// +/// \tparam Scalar The element type of the matrix. +/// Currently supported types are `float`, `double` and `long double`. +/// \tparam SelectionRule An enumeration value indicating the selection rule of +/// the requested eigenvalues, for example `LARGEST_MAGN` +/// to retrieve eigenvalues with the largest magnitude. +/// The full list of enumeration values can be found in +/// \ref Enumerations. +/// \tparam OpType The name of the matrix operation class. Users could either +/// use the wrapper classes such as DenseSymMatProd and +/// SparseSymMatProd, or define their +/// own that implements all the public member functions as in +/// DenseSymMatProd. +/// +/// Below is an example that demonstrates the usage of this class. +/// +/// \code{.cpp} +/// #include +/// #include +/// // is implicitly included +/// #include +/// +/// using namespace Spectra; +/// +/// int main() +/// { +/// // We are going to calculate the eigenvalues of M +/// Eigen::MatrixXd A = Eigen::MatrixXd::Random(10, 10); +/// Eigen::MatrixXd M = A + A.transpose(); +/// +/// // Construct matrix operation object using the wrapper class DenseSymMatProd +/// DenseSymMatProd op(M); +/// +/// // Construct eigen solver object, requesting the largest three eigenvalues +/// SymEigsSolver< double, LARGEST_ALGE, DenseSymMatProd > eigs(&op, 3, 6); +/// +/// // Initialize and compute +/// eigs.init(); +/// int nconv = eigs.compute(); +/// +/// // Retrieve results +/// Eigen::VectorXd evalues; +/// if(eigs.info() == SUCCESSFUL) +/// evalues = eigs.eigenvalues(); +/// +/// std::cout << "Eigenvalues found:\n" << evalues << std::endl; +/// +/// return 0; +/// } +/// \endcode +/// +/// And here is an example for user-supplied matrix operation class. +/// +/// \code{.cpp} +/// #include +/// #include +/// #include +/// +/// using namespace Spectra; +/// +/// // M = diag(1, 2, ..., 10) +/// class MyDiagonalTen +/// { +/// public: +/// int rows() { return 10; } +/// int cols() { return 10; } +/// // y_out = M * x_in +/// void perform_op(double *x_in, double *y_out) +/// { +/// for(int i = 0; i < rows(); i++) +/// { +/// y_out[i] = x_in[i] * (i + 1); +/// } +/// } +/// }; +/// +/// int main() +/// { +/// MyDiagonalTen op; +/// SymEigsSolver eigs(&op, 3, 6); +/// eigs.init(); +/// eigs.compute(); +/// if(eigs.info() == SUCCESSFUL) +/// { +/// Eigen::VectorXd evalues = eigs.eigenvalues(); +/// // Will get (10, 9, 8) +/// std::cout << "Eigenvalues found:\n" << evalues << std::endl; +/// } +/// +/// return 0; +/// } +/// \endcode +/// +template > +class SymEigsSolver : public SymEigsBase +{ +private: + typedef Eigen::Index Index; + +public: + /// + /// Constructor to create a solver object. + /// + /// \param op Pointer to the matrix operation object, which should implement + /// the matrix-vector multiplication operation of \f$A\f$: + /// calculating \f$Av\f$ for any vector \f$v\f$. Users could either + /// create the object from the wrapper class such as DenseSymMatProd, or + /// define their own that implements all the public member functions + /// as in DenseSymMatProd. + /// \param nev Number of eigenvalues requested. This should satisfy \f$1\le nev \le n-1\f$, + /// where \f$n\f$ is the size of matrix. + /// \param ncv Parameter that controls the convergence speed of the algorithm. + /// Typically a larger `ncv` means faster convergence, but it may + /// also result in greater memory use and more matrix operations + /// in each iteration. This parameter must satisfy \f$nev < ncv \le n\f$, + /// and is advised to take \f$ncv \ge 2\cdot nev\f$. + /// + SymEigsSolver(OpType* op, Index nev, Index ncv) : + SymEigsBase(op, NULL, nev, ncv) + {} +}; + +} // namespace Spectra + +#endif // SYM_EIGS_SOLVER_H diff --git a/gtsam/3rdparty/Spectra/SymGEigsSolver.h b/gtsam/3rdparty/Spectra/SymGEigsSolver.h new file mode 100644 index 000000000..68aa37cfc --- /dev/null +++ b/gtsam/3rdparty/Spectra/SymGEigsSolver.h @@ -0,0 +1,326 @@ +// Copyright (C) 2016-2019 Yixuan Qiu +// +// This Source Code Form is subject to the terms of the Mozilla +// Public License v. 2.0. If a copy of the MPL was not distributed +// with this file, You can obtain one at https://mozilla.org/MPL/2.0/. + +#ifndef SYM_GEIGS_SOLVER_H +#define SYM_GEIGS_SOLVER_H + +#include "SymEigsBase.h" +#include "Util/GEigsMode.h" +#include "MatOp/internal/SymGEigsCholeskyOp.h" +#include "MatOp/internal/SymGEigsRegInvOp.h" + +namespace Spectra { + +/// +/// \defgroup GEigenSolver Generalized Eigen Solvers +/// +/// Generalized eigen solvers for different types of problems. +/// + +/// +/// \ingroup GEigenSolver +/// +/// This class implements the generalized eigen solver for real symmetric +/// matrices, i.e., to solve \f$Ax=\lambda Bx\f$ where \f$A\f$ is symmetric and +/// \f$B\f$ is positive definite. +/// +/// There are two modes of this solver, specified by the template parameter +/// GEigsMode. See the pages for the specialized classes for details. +/// - The Cholesky mode assumes that \f$B\f$ can be factorized using Cholesky +/// decomposition, which is the preferred mode when the decomposition is +/// available. (This can be easily done in Eigen using the dense or sparse +/// Cholesky solver.) +/// See \ref SymGEigsSolver "SymGEigsSolver (Cholesky mode)" for more details. +/// - The regular inverse mode requires the matrix-vector product \f$Bv\f$ and the +/// linear equation solving operation \f$B^{-1}v\f$. This mode should only be +/// used when the Cholesky decomposition of \f$B\f$ is hard to implement, or +/// when computing \f$B^{-1}v\f$ is much faster than the Cholesky decomposition. +/// See \ref SymGEigsSolver "SymGEigsSolver (Regular inverse mode)" for more details. + +// Empty class template +template +class SymGEigsSolver +{}; + +/// +/// \ingroup GEigenSolver +/// +/// This class implements the generalized eigen solver for real symmetric +/// matrices using Cholesky decomposition, i.e., to solve \f$Ax=\lambda Bx\f$ +/// where \f$A\f$ is symmetric and \f$B\f$ is positive definite with the Cholesky +/// decomposition \f$B=LL'\f$. +/// +/// This solver requires two matrix operation objects: one for \f$A\f$ that implements +/// the matrix multiplication \f$Av\f$, and one for \f$B\f$ that implements the lower +/// and upper triangular solving \f$L^{-1}v\f$ and \f$(L')^{-1}v\f$. +/// +/// If \f$A\f$ and \f$B\f$ are stored as Eigen matrices, then the first operation +/// can be created using the DenseSymMatProd or SparseSymMatProd classes, and +/// the second operation can be created using the DenseCholesky or SparseCholesky +/// classes. If the users need to define their own operation classes, then they +/// should implement all the public member functions as in those built-in classes. +/// +/// \tparam Scalar The element type of the matrix. +/// Currently supported types are `float`, `double` and `long double`. +/// \tparam SelectionRule An enumeration value indicating the selection rule of +/// the requested eigenvalues, for example `LARGEST_MAGN` +/// to retrieve eigenvalues with the largest magnitude. +/// The full list of enumeration values can be found in +/// \ref Enumerations. +/// \tparam OpType The name of the matrix operation class for \f$A\f$. Users could either +/// use the wrapper classes such as DenseSymMatProd and +/// SparseSymMatProd, or define their +/// own that implements all the public member functions as in +/// DenseSymMatProd. +/// \tparam BOpType The name of the matrix operation class for \f$B\f$. Users could either +/// use the wrapper classes such as DenseCholesky and +/// SparseCholesky, or define their +/// own that implements all the public member functions as in +/// DenseCholesky. +/// \tparam GEigsMode Mode of the generalized eigen solver. In this solver +/// it is Spectra::GEIGS_CHOLESKY. +/// +/// Below is an example that demonstrates the usage of this class. +/// +/// \code{.cpp} +/// #include +/// #include +/// #include +/// #include +/// #include +/// #include +/// #include +/// +/// using namespace Spectra; +/// +/// int main() +/// { +/// // We are going to solve the generalized eigenvalue problem A * x = lambda * B * x +/// const int n = 100; +/// +/// // Define the A matrix +/// Eigen::MatrixXd M = Eigen::MatrixXd::Random(n, n); +/// Eigen::MatrixXd A = M + M.transpose(); +/// +/// // Define the B matrix, a band matrix with 2 on the diagonal and 1 on the subdiagonals +/// Eigen::SparseMatrix B(n, n); +/// B.reserve(Eigen::VectorXi::Constant(n, 3)); +/// for(int i = 0; i < n; i++) +/// { +/// B.insert(i, i) = 2.0; +/// if(i > 0) +/// B.insert(i - 1, i) = 1.0; +/// if(i < n - 1) +/// B.insert(i + 1, i) = 1.0; +/// } +/// +/// // Construct matrix operation object using the wrapper classes +/// DenseSymMatProd op(A); +/// SparseCholesky Bop(B); +/// +/// // Construct generalized eigen solver object, requesting the largest three generalized eigenvalues +/// SymGEigsSolver, SparseCholesky, GEIGS_CHOLESKY> +/// geigs(&op, &Bop, 3, 6); +/// +/// // Initialize and compute +/// geigs.init(); +/// int nconv = geigs.compute(); +/// +/// // Retrieve results +/// Eigen::VectorXd evalues; +/// Eigen::MatrixXd evecs; +/// if(geigs.info() == SUCCESSFUL) +/// { +/// evalues = geigs.eigenvalues(); +/// evecs = geigs.eigenvectors(); +/// } +/// +/// std::cout << "Generalized eigenvalues found:\n" << evalues << std::endl; +/// std::cout << "Generalized eigenvectors found:\n" << evecs.topRows(10) << std::endl; +/// +/// // Verify results using the generalized eigen solver in Eigen +/// Eigen::MatrixXd Bdense = B; +/// Eigen::GeneralizedSelfAdjointEigenSolver es(A, Bdense); +/// +/// std::cout << "Generalized eigenvalues:\n" << es.eigenvalues().tail(3) << std::endl; +/// std::cout << "Generalized eigenvectors:\n" << es.eigenvectors().rightCols(3).topRows(10) << std::endl; +/// +/// return 0; +/// } +/// \endcode + +// Partial specialization for GEigsMode = GEIGS_CHOLESKY +template +class SymGEigsSolver : + public SymEigsBase, IdentityBOp> +{ +private: + typedef Eigen::Index Index; + typedef Eigen::Matrix Matrix; + typedef Eigen::Matrix Vector; + + BOpType* m_Bop; + +public: + /// + /// Constructor to create a solver object. + /// + /// \param op Pointer to the \f$A\f$ matrix operation object. It + /// should implement the matrix-vector multiplication operation of \f$A\f$: + /// calculating \f$Av\f$ for any vector \f$v\f$. Users could either + /// create the object from the wrapper classes such as DenseSymMatProd, or + /// define their own that implements all the public member functions + /// as in DenseSymMatProd. + /// \param Bop Pointer to the \f$B\f$ matrix operation object. It + /// represents a Cholesky decomposition of \f$B\f$, and should + /// implement the lower and upper triangular solving operations: + /// calculating \f$L^{-1}v\f$ and \f$(L')^{-1}v\f$ for any vector + /// \f$v\f$, where \f$LL'=B\f$. Users could either + /// create the object from the wrapper classes such as DenseCholesky, or + /// define their own that implements all the public member functions + /// as in DenseCholesky. + /// \param nev Number of eigenvalues requested. This should satisfy \f$1\le nev \le n-1\f$, + /// where \f$n\f$ is the size of matrix. + /// \param ncv Parameter that controls the convergence speed of the algorithm. + /// Typically a larger `ncv` means faster convergence, but it may + /// also result in greater memory use and more matrix operations + /// in each iteration. This parameter must satisfy \f$nev < ncv \le n\f$, + /// and is advised to take \f$ncv \ge 2\cdot nev\f$. + /// + SymGEigsSolver(OpType* op, BOpType* Bop, Index nev, Index ncv) : + SymEigsBase, IdentityBOp>( + new SymGEigsCholeskyOp(*op, *Bop), NULL, nev, ncv), + m_Bop(Bop) + {} + + /// \cond + + ~SymGEigsSolver() + { + // m_op contains the constructed SymGEigsCholeskyOp object + delete this->m_op; + } + + Matrix eigenvectors(Index nvec) const + { + Matrix res = SymEigsBase, IdentityBOp>::eigenvectors(nvec); + Vector tmp(res.rows()); + const Index nconv = res.cols(); + for (Index i = 0; i < nconv; i++) + { + m_Bop->upper_triangular_solve(&res(0, i), tmp.data()); + res.col(i).noalias() = tmp; + } + + return res; + } + + Matrix eigenvectors() const + { + return SymGEigsSolver::eigenvectors(this->m_nev); + } + + /// \endcond +}; + +/// +/// \ingroup GEigenSolver +/// +/// This class implements the generalized eigen solver for real symmetric +/// matrices in the regular inverse mode, i.e., to solve \f$Ax=\lambda Bx\f$ +/// where \f$A\f$ is symmetric, and \f$B\f$ is positive definite with the operations +/// defined below. +/// +/// This solver requires two matrix operation objects: one for \f$A\f$ that implements +/// the matrix multiplication \f$Av\f$, and one for \f$B\f$ that implements the +/// matrix-vector product \f$Bv\f$ and the linear equation solving operation \f$B^{-1}v\f$. +/// +/// If \f$A\f$ and \f$B\f$ are stored as Eigen matrices, then the first operation +/// can be created using the DenseSymMatProd or SparseSymMatProd classes, and +/// the second operation can be created using the SparseRegularInverse class. There is no +/// wrapper class for a dense \f$B\f$ matrix since in this case the Cholesky mode +/// is always preferred. If the users need to define their own operation classes, then they +/// should implement all the public member functions as in those built-in classes. +/// +/// \tparam Scalar The element type of the matrix. +/// Currently supported types are `float`, `double` and `long double`. +/// \tparam SelectionRule An enumeration value indicating the selection rule of +/// the requested eigenvalues, for example `LARGEST_MAGN` +/// to retrieve eigenvalues with the largest magnitude. +/// The full list of enumeration values can be found in +/// \ref Enumerations. +/// \tparam OpType The name of the matrix operation class for \f$A\f$. Users could either +/// use the wrapper classes such as DenseSymMatProd and +/// SparseSymMatProd, or define their +/// own that implements all the public member functions as in +/// DenseSymMatProd. +/// \tparam BOpType The name of the matrix operation class for \f$B\f$. Users could either +/// use the wrapper class SparseRegularInverse, or define their +/// own that implements all the public member functions as in +/// SparseRegularInverse. +/// \tparam GEigsMode Mode of the generalized eigen solver. In this solver +/// it is Spectra::GEIGS_REGULAR_INVERSE. +/// + +// Partial specialization for GEigsMode = GEIGS_REGULAR_INVERSE +template +class SymGEigsSolver : + public SymEigsBase, BOpType> +{ +private: + typedef Eigen::Index Index; + +public: + /// + /// Constructor to create a solver object. + /// + /// \param op Pointer to the \f$A\f$ matrix operation object. It + /// should implement the matrix-vector multiplication operation of \f$A\f$: + /// calculating \f$Av\f$ for any vector \f$v\f$. Users could either + /// create the object from the wrapper classes such as DenseSymMatProd, or + /// define their own that implements all the public member functions + /// as in DenseSymMatProd. + /// \param Bop Pointer to the \f$B\f$ matrix operation object. It should + /// implement the multiplication operation \f$Bv\f$ and the linear equation + /// solving operation \f$B^{-1}v\f$ for any vector \f$v\f$. Users could either + /// create the object from the wrapper class SparseRegularInverse, or + /// define their own that implements all the public member functions + /// as in SparseRegularInverse. + /// \param nev Number of eigenvalues requested. This should satisfy \f$1\le nev \le n-1\f$, + /// where \f$n\f$ is the size of matrix. + /// \param ncv Parameter that controls the convergence speed of the algorithm. + /// Typically a larger `ncv` means faster convergence, but it may + /// also result in greater memory use and more matrix operations + /// in each iteration. This parameter must satisfy \f$nev < ncv \le n\f$, + /// and is advised to take \f$ncv \ge 2\cdot nev\f$. + /// + SymGEigsSolver(OpType* op, BOpType* Bop, Index nev, Index ncv) : + SymEigsBase, BOpType>( + new SymGEigsRegInvOp(*op, *Bop), Bop, nev, ncv) + {} + + /// \cond + ~SymGEigsSolver() + { + // m_op contains the constructed SymGEigsRegInvOp object + delete this->m_op; + } + /// \endcond +}; + +} // namespace Spectra + +#endif // SYM_GEIGS_SOLVER_H diff --git a/gtsam/3rdparty/Spectra/Util/CompInfo.h b/gtsam/3rdparty/Spectra/Util/CompInfo.h new file mode 100644 index 000000000..07b8399a1 --- /dev/null +++ b/gtsam/3rdparty/Spectra/Util/CompInfo.h @@ -0,0 +1,35 @@ +// Copyright (C) 2016-2019 Yixuan Qiu +// +// This Source Code Form is subject to the terms of the Mozilla +// Public License v. 2.0. If a copy of the MPL was not distributed +// with this file, You can obtain one at https://mozilla.org/MPL/2.0/. + +#ifndef COMP_INFO_H +#define COMP_INFO_H + +namespace Spectra { + +/// +/// \ingroup Enumerations +/// +/// The enumeration to report the status of computation. +/// +enum COMPUTATION_INFO +{ + SUCCESSFUL = 0, ///< Computation was successful. + + NOT_COMPUTED, ///< Used in eigen solvers, indicating that computation + ///< has not been conducted. Users should call + ///< the `compute()` member function of solvers. + + NOT_CONVERGING, ///< Used in eigen solvers, indicating that some eigenvalues + ///< did not converge. The `compute()` + ///< function returns the number of converged eigenvalues. + + NUMERICAL_ISSUE ///< Used in Cholesky decomposition, indicating that the + ///< matrix is not positive definite. +}; + +} // namespace Spectra + +#endif // COMP_INFO_H diff --git a/gtsam/3rdparty/Spectra/Util/GEigsMode.h b/gtsam/3rdparty/Spectra/Util/GEigsMode.h new file mode 100644 index 000000000..a547ac0bf --- /dev/null +++ b/gtsam/3rdparty/Spectra/Util/GEigsMode.h @@ -0,0 +1,32 @@ +// Copyright (C) 2016-2019 Yixuan Qiu +// +// This Source Code Form is subject to the terms of the Mozilla +// Public License v. 2.0. If a copy of the MPL was not distributed +// with this file, You can obtain one at https://mozilla.org/MPL/2.0/. + +#ifndef GEIGS_MODE_H +#define GEIGS_MODE_H + +namespace Spectra { + +/// +/// \ingroup Enumerations +/// +/// The enumeration to specify the mode of generalized eigenvalue solver. +/// +enum GEIGS_MODE +{ + GEIGS_CHOLESKY = 0, ///< Using Cholesky decomposition to solve generalized eigenvalues. + + GEIGS_REGULAR_INVERSE, ///< Regular inverse mode for generalized eigenvalue solver. + + GEIGS_SHIFT_INVERT, ///< Shift-and-invert mode for generalized eigenvalue solver. + + GEIGS_BUCKLING, ///< Buckling mode for generalized eigenvalue solver. + + GEIGS_CAYLEY ///< Cayley transformation mode for generalized eigenvalue solver. +}; + +} // namespace Spectra + +#endif // GEIGS_MODE_H diff --git a/gtsam/3rdparty/Spectra/Util/SelectionRule.h b/gtsam/3rdparty/Spectra/Util/SelectionRule.h new file mode 100644 index 000000000..237950b4d --- /dev/null +++ b/gtsam/3rdparty/Spectra/Util/SelectionRule.h @@ -0,0 +1,275 @@ +// Copyright (C) 2016-2019 Yixuan Qiu +// +// This Source Code Form is subject to the terms of the Mozilla +// Public License v. 2.0. If a copy of the MPL was not distributed +// with this file, You can obtain one at https://mozilla.org/MPL/2.0/. + +#ifndef SELECTION_RULE_H +#define SELECTION_RULE_H + +#include // std::vector +#include // std::abs +#include // std::sort +#include // std::complex +#include // std::pair +#include // std::invalid_argument + +namespace Spectra { + +/// +/// \defgroup Enumerations +/// +/// Enumeration types for the selection rule of eigenvalues. +/// + +/// +/// \ingroup Enumerations +/// +/// The enumeration of selection rules of desired eigenvalues. +/// +enum SELECT_EIGENVALUE +{ + LARGEST_MAGN = 0, ///< Select eigenvalues with largest magnitude. Magnitude + ///< means the absolute value for real numbers and norm for + ///< complex numbers. Applies to both symmetric and general + ///< eigen solvers. + + LARGEST_REAL, ///< Select eigenvalues with largest real part. Only for general eigen solvers. + + LARGEST_IMAG, ///< Select eigenvalues with largest imaginary part (in magnitude). Only for general eigen solvers. + + LARGEST_ALGE, ///< Select eigenvalues with largest algebraic value, considering + ///< any negative sign. Only for symmetric eigen solvers. + + SMALLEST_MAGN, ///< Select eigenvalues with smallest magnitude. Applies to both symmetric and general + ///< eigen solvers. + + SMALLEST_REAL, ///< Select eigenvalues with smallest real part. Only for general eigen solvers. + + SMALLEST_IMAG, ///< Select eigenvalues with smallest imaginary part (in magnitude). Only for general eigen solvers. + + SMALLEST_ALGE, ///< Select eigenvalues with smallest algebraic value. Only for symmetric eigen solvers. + + BOTH_ENDS ///< Select eigenvalues half from each end of the spectrum. When + ///< `nev` is odd, compute more from the high end. Only for symmetric eigen solvers. +}; + +/// +/// \ingroup Enumerations +/// +/// The enumeration of selection rules of desired eigenvalues. Alias for `SELECT_EIGENVALUE`. +/// +enum SELECT_EIGENVALUE_ALIAS +{ + WHICH_LM = 0, ///< Alias for `LARGEST_MAGN` + WHICH_LR, ///< Alias for `LARGEST_REAL` + WHICH_LI, ///< Alias for `LARGEST_IMAG` + WHICH_LA, ///< Alias for `LARGEST_ALGE` + WHICH_SM, ///< Alias for `SMALLEST_MAGN` + WHICH_SR, ///< Alias for `SMALLEST_REAL` + WHICH_SI, ///< Alias for `SMALLEST_IMAG` + WHICH_SA, ///< Alias for `SMALLEST_ALGE` + WHICH_BE ///< Alias for `BOTH_ENDS` +}; + +/// \cond + +// Get the element type of a "scalar" +// ElemType => double +// ElemType< std::complex > => double +template +class ElemType +{ +public: + typedef T type; +}; + +template +class ElemType > +{ +public: + typedef T type; +}; + +// When comparing eigenvalues, we first calculate the "target" +// to sort. For example, if we want to choose the eigenvalues with +// largest magnitude, the target will be -abs(x). +// The minus sign is due to the fact that std::sort() sorts in ascending order. + +// Default target: throw an exception +template +class SortingTarget +{ +public: + static typename ElemType::type get(const Scalar& val) + { + using std::abs; + throw std::invalid_argument("incompatible selection rule"); + return -abs(val); + } +}; + +// Specialization for LARGEST_MAGN +// This covers [float, double, complex] x [LARGEST_MAGN] +template +class SortingTarget +{ +public: + static typename ElemType::type get(const Scalar& val) + { + using std::abs; + return -abs(val); + } +}; + +// Specialization for LARGEST_REAL +// This covers [complex] x [LARGEST_REAL] +template +class SortingTarget, LARGEST_REAL> +{ +public: + static RealType get(const std::complex& val) + { + return -val.real(); + } +}; + +// Specialization for LARGEST_IMAG +// This covers [complex] x [LARGEST_IMAG] +template +class SortingTarget, LARGEST_IMAG> +{ +public: + static RealType get(const std::complex& val) + { + using std::abs; + return -abs(val.imag()); + } +}; + +// Specialization for LARGEST_ALGE +// This covers [float, double] x [LARGEST_ALGE] +template +class SortingTarget +{ +public: + static Scalar get(const Scalar& val) + { + return -val; + } +}; + +// Here BOTH_ENDS is the same as LARGEST_ALGE, but +// we need some additional steps, which are done in +// SymEigsSolver.h => retrieve_ritzpair(). +// There we move the smallest values to the proper locations. +template +class SortingTarget +{ +public: + static Scalar get(const Scalar& val) + { + return -val; + } +}; + +// Specialization for SMALLEST_MAGN +// This covers [float, double, complex] x [SMALLEST_MAGN] +template +class SortingTarget +{ +public: + static typename ElemType::type get(const Scalar& val) + { + using std::abs; + return abs(val); + } +}; + +// Specialization for SMALLEST_REAL +// This covers [complex] x [SMALLEST_REAL] +template +class SortingTarget, SMALLEST_REAL> +{ +public: + static RealType get(const std::complex& val) + { + return val.real(); + } +}; + +// Specialization for SMALLEST_IMAG +// This covers [complex] x [SMALLEST_IMAG] +template +class SortingTarget, SMALLEST_IMAG> +{ +public: + static RealType get(const std::complex& val) + { + using std::abs; + return abs(val.imag()); + } +}; + +// Specialization for SMALLEST_ALGE +// This covers [float, double] x [SMALLEST_ALGE] +template +class SortingTarget +{ +public: + static Scalar get(const Scalar& val) + { + return val; + } +}; + +// Sort eigenvalues and return the order index +template +class PairComparator +{ +public: + bool operator()(const PairType& v1, const PairType& v2) + { + return v1.first < v2.first; + } +}; + +template +class SortEigenvalue +{ +private: + typedef typename ElemType::type TargetType; // Type of the sorting target, will be + // a floating number type, e.g. "double" + typedef std::pair PairType; // Type of the sorting pair, including + // the sorting target and the index + + std::vector pair_sort; + +public: + SortEigenvalue(const T* start, int size) : + pair_sort(size) + { + for (int i = 0; i < size; i++) + { + pair_sort[i].first = SortingTarget::get(start[i]); + pair_sort[i].second = i; + } + PairComparator comp; + std::sort(pair_sort.begin(), pair_sort.end(), comp); + } + + std::vector index() + { + std::vector ind(pair_sort.size()); + for (unsigned int i = 0; i < ind.size(); i++) + ind[i] = pair_sort[i].second; + + return ind; + } +}; + +/// \endcond + +} // namespace Spectra + +#endif // SELECTION_RULE_H diff --git a/gtsam/3rdparty/Spectra/Util/SimpleRandom.h b/gtsam/3rdparty/Spectra/Util/SimpleRandom.h new file mode 100644 index 000000000..83fa7c86f --- /dev/null +++ b/gtsam/3rdparty/Spectra/Util/SimpleRandom.h @@ -0,0 +1,91 @@ +// Copyright (C) 2016-2019 Yixuan Qiu +// +// This Source Code Form is subject to the terms of the Mozilla +// Public License v. 2.0. If a copy of the MPL was not distributed +// with this file, You can obtain one at https://mozilla.org/MPL/2.0/. + +#ifndef SIMPLE_RANDOM_H +#define SIMPLE_RANDOM_H + +#include + +/// \cond + +namespace Spectra { + +// We need a simple pseudo random number generator here: +// 1. It is used to generate initial and restarted residual vector. +// 2. It is not necessary to be so "random" and advanced. All we hope +// is that the residual vector is not in the space spanned by the +// current Krylov space. This should be met almost surely. +// 3. We don't want to call RNG in C++, since we actually want the +// algorithm to be deterministic. Also, calling RNG in C/C++ is not +// allowed in R packages submitted to CRAN. +// 4. The method should be as simple as possible, so an LCG is enough. +// 5. Based on public domain code by Ray Gardner +// http://stjarnhimlen.se/snippets/rg_rand.c + +template +class SimpleRandom +{ +private: + typedef Eigen::Index Index; + typedef Eigen::Matrix Vector; + + const unsigned int m_a; // multiplier + const unsigned long m_max; // 2^31 - 1 + long m_rand; + + inline long next_long_rand(long seed) + { + unsigned long lo, hi; + + lo = m_a * (long) (seed & 0xFFFF); + hi = m_a * (long) ((unsigned long) seed >> 16); + lo += (hi & 0x7FFF) << 16; + if (lo > m_max) + { + lo &= m_max; + ++lo; + } + lo += hi >> 15; + if (lo > m_max) + { + lo &= m_max; + ++lo; + } + return (long) lo; + } + +public: + SimpleRandom(unsigned long init_seed) : + m_a(16807), + m_max(2147483647L), + m_rand(init_seed ? (init_seed & m_max) : 1) + {} + + Scalar random() + { + m_rand = next_long_rand(m_rand); + return Scalar(m_rand) / Scalar(m_max) - Scalar(0.5); + } + + // Vector of random numbers of type Scalar + // Ranging from -0.5 to 0.5 + Vector random_vec(const Index len) + { + Vector res(len); + for (Index i = 0; i < len; i++) + { + m_rand = next_long_rand(m_rand); + res[i] = Scalar(m_rand) / Scalar(m_max) - Scalar(0.5); + } + return res; + } +}; + +} // namespace Spectra + +/// \endcond + +#endif // SIMPLE_RANDOM_H diff --git a/gtsam/3rdparty/Spectra/Util/TypeTraits.h b/gtsam/3rdparty/Spectra/Util/TypeTraits.h new file mode 100644 index 000000000..29288c5a6 --- /dev/null +++ b/gtsam/3rdparty/Spectra/Util/TypeTraits.h @@ -0,0 +1,71 @@ +// Copyright (C) 2018-2019 Yixuan Qiu +// +// This Source Code Form is subject to the terms of the Mozilla +// Public License v. 2.0. If a copy of the MPL was not distributed +// with this file, You can obtain one at https://mozilla.org/MPL/2.0/. + +#ifndef TYPE_TRAITS_H +#define TYPE_TRAITS_H + +#include +#include + +/// \cond + +namespace Spectra { + +// For a real value type "Scalar", we want to know its smallest +// positive value, i.e., std::numeric_limits::min(). +// However, we must take non-standard value types into account, +// so we rely on Eigen::NumTraits. +// +// Eigen::NumTraits has defined epsilon() and lowest(), but +// lowest() means negative highest(), which is a very small +// negative value. +// +// Therefore, we manually define this limit, and use eplison()^3 +// to mimic it for non-standard types. + +// Generic definition +template +struct TypeTraits +{ + static inline Scalar min() + { + return Eigen::numext::pow(Eigen::NumTraits::epsilon(), Scalar(3)); + } +}; + +// Full specialization +template <> +struct TypeTraits +{ + static inline float min() + { + return std::numeric_limits::min(); + } +}; + +template <> +struct TypeTraits +{ + static inline double min() + { + return std::numeric_limits::min(); + } +}; + +template <> +struct TypeTraits +{ + static inline long double min() + { + return std::numeric_limits::min(); + } +}; + +} // namespace Spectra + +/// \endcond + +#endif // TYPE_TRAITS_H diff --git a/gtsam/3rdparty/Spectra/contrib/LOBPCGSolver.h b/gtsam/3rdparty/Spectra/contrib/LOBPCGSolver.h new file mode 100644 index 000000000..69c4d92c0 --- /dev/null +++ b/gtsam/3rdparty/Spectra/contrib/LOBPCGSolver.h @@ -0,0 +1,552 @@ +// Written by Anna Araslanova +// Modified by Yixuan Qiu +// License: MIT + +#ifndef LOBPCG_SOLVER +#define LOBPCG_SOLVER + +#include +#include + +#include +#include +#include +#include +#include + +#include "../SymGEigsSolver.h" + +namespace Spectra { + +/// +/// \ingroup EigenSolver +/// + +/// *** METHOD +/// The class represent the LOBPCG algorithm, which was invented by Andrew Knyazev +/// Theoretical background of the procedure can be found in the articles below +/// - Knyazev, A.V., 2001. Toward the optimal preconditioned eigensolver : Locally optimal block preconditioned conjugate gradient method.SIAM journal on scientific computing, 23(2), pp.517 - 541. +/// - Knyazev, A.V., Argentati, M.E., Lashuk, I. and Ovtchinnikov, E.E., 2007. Block locally optimal preconditioned eigenvalue xolvers(BLOPEX) in HYPRE and PETSc.SIAM Journal on Scientific Computing, 29(5), pp.2224 - 2239. +/// +/// *** CONDITIONS OF USE +/// Locally Optimal Block Preconditioned Conjugate Gradient(LOBPCG) is a method for finding the M smallest eigenvalues +/// and eigenvectors of a large symmetric positive definite generalized eigenvalue problem +/// \f$Ax=\lambda Bx,\f$ +/// where \f$A_{NxN}\f$ is a symmetric matrix, \f$B\f$ is symmetric and positive - definite. \f$A and B\f$ are also assumed large and sparse +/// \f$\textit{M}\f$ should be \f$\<< textit{N}\f$ (at least \f$\textit{5M} < \textit{N} \f$) +/// +/// *** ARGUMENTS +/// Eigen::SparseMatrix A; // N*N - Ax = lambda*Bx, lrage and sparse +/// Eigen::SparseMatrix X; // N*M - initial approximations to eigenvectors (random in general case) +/// Spectra::LOBPCGSolver solver(A, X); +/// *Eigen::SparseMatrix B; // N*N - Ax = lambda*Bx, sparse, positive definite +/// solver.setConstraints(B); +/// *Eigen::SparseMatrix Y; // N*K - constraints, already found eigenvectors +/// solver.setB(B); +/// *Eigen::SparseMatrix T; // N*N - preconditioner ~ A^-1 +/// solver.setPreconditioner(T); +/// +/// *** OUTCOMES +/// solver.solve(); // compute eigenpairs // void +/// solver.info(); // state of converjance // int +/// solver.residuals(); // get residuals to evaluate biases // Eigen::Matrix +/// solver.eigenvalues(); // get eigenvalues // Eigen::Matrix +/// solver.eigenvectors(); // get eigenvectors // Eigen::Matrix +/// +/// *** EXAMPLE +/// \code{.cpp} +/// #include +/// +/// // random A +/// Matrix a; +/// a = (Matrix::Random(10, 10).array() > 0.6).cast() * Matrix::Random(10, 10).array() * 5; +/// a = Matrix((a).triangularView()) + Matrix((a).triangularView()).transpose(); +/// for (int i = 0; i < 10; i++) +/// a(i, i) = i + 0.5; +/// std::cout << a << "\n"; +/// Eigen::SparseMatrix A(a.sparseView()); +/// // random X +/// Eigen::Matrix x; +/// x = Matrix::Random(10, 2).array(); +/// Eigen::SparseMatrix X(x.sparseView()); +/// // solve Ax = lambda*x +/// Spectra::LOBPCGSolver solver(A, X); +/// solver.compute(10, 1e-4); // 10 iterations, L2_tolerance = 1e-4*N +/// std::cout << "info\n" << solver.info() << std::endl; +/// std::cout << "eigenvalues\n" << solver.eigenvalues() << std::endl; +/// std::cout << "eigenvectors\n" << solver.eigenvectors() << std::endl; +/// std::cout << "residuals\n" << solver.residuals() << std::endl; +/// \endcode +/// + +template +class LOBPCGSolver +{ +private: + typedef Eigen::Matrix Matrix; + typedef Eigen::Matrix Vector; + + typedef std::complex Complex; + typedef Eigen::Matrix ComplexMatrix; + typedef Eigen::Matrix ComplexVector; + + typedef Eigen::SparseMatrix SparseMatrix; + typedef Eigen::SparseMatrix SparseComplexMatrix; + + const int m_n; // dimension of matrix A + const int m_nev; // number of eigenvalues requested + SparseMatrix A, X; + SparseMatrix m_Y, m_B, m_preconditioner; + bool flag_with_constraints, flag_with_B, flag_with_preconditioner; + +public: + SparseMatrix m_residuals; + Matrix m_evectors; + Vector m_evalues; + int m_info; + +private: + // B-orthonormalize matrix M + int orthogonalizeInPlace(SparseMatrix& M, SparseMatrix& B, + SparseMatrix& true_BM, bool has_true_BM = false) + { + SparseMatrix BM; + + if (has_true_BM == false) + { + if (flag_with_B) + { + BM = B * M; + } + else + { + BM = M; + } + } + else + { + BM = true_BM; + } + + Eigen::SimplicialLDLT chol_MBM(M.transpose() * BM); + + if (chol_MBM.info() != SUCCESSFUL) + { + // LDLT decomposition fail + m_info = chol_MBM.info(); + return chol_MBM.info(); + } + + SparseComplexMatrix Upper_MBM = chol_MBM.matrixU().template cast(); + ComplexVector D_MBM_vec = chol_MBM.vectorD().template cast(); + + D_MBM_vec = D_MBM_vec.cwiseSqrt(); + + for (int i = 0; i < D_MBM_vec.rows(); i++) + { + D_MBM_vec(i) = Complex(1.0, 0.0) / D_MBM_vec(i); + } + + SparseComplexMatrix D_MBM_mat(D_MBM_vec.asDiagonal()); + + SparseComplexMatrix U_inv(Upper_MBM.rows(), Upper_MBM.cols()); + U_inv.setIdentity(); + Upper_MBM.template triangularView().solveInPlace(U_inv); + + SparseComplexMatrix right_product = U_inv * D_MBM_mat; + M = M * right_product.real(); + if (flag_with_B) + { + true_BM = B * M; + } + else + { + true_BM = M; + } + + return SUCCESSFUL; + } + + void applyConstraintsInPlace(SparseMatrix& X, SparseMatrix& Y, + SparseMatrix& B) + { + SparseMatrix BY; + if (flag_with_B) + { + BY = B * Y; + } + else + { + BY = Y; + } + + SparseMatrix YBY = Y.transpose() * BY; + SparseMatrix BYX = BY.transpose() * X; + + SparseMatrix YBY_XYX = (Matrix(YBY).bdcSvd(Eigen::ComputeThinU | Eigen::ComputeThinV).solve(Matrix(BYX))).sparseView(); + X = X - Y * YBY_XYX; + } + + /* + return + 'AB + CD' + */ + Matrix stack_4_matricies(Matrix A, Matrix B, + Matrix C, Matrix D) + { + Matrix result(A.rows() + C.rows(), A.cols() + B.cols()); + result.topLeftCorner(A.rows(), A.cols()) = A; + result.topRightCorner(B.rows(), B.cols()) = B; + result.bottomLeftCorner(C.rows(), C.cols()) = C; + result.bottomRightCorner(D.rows(), D.cols()) = D; + return result; + } + + Matrix stack_9_matricies(Matrix A, Matrix B, Matrix C, + Matrix D, Matrix E, Matrix F, + Matrix G, Matrix H, Matrix I) + { + Matrix result(A.rows() + D.rows() + G.rows(), A.cols() + B.cols() + C.cols()); + result.block(0, 0, A.rows(), A.cols()) = A; + result.block(0, A.cols(), B.rows(), B.cols()) = B; + result.block(0, A.cols() + B.cols(), C.rows(), C.cols()) = C; + result.block(A.rows(), 0, D.rows(), D.cols()) = D; + result.block(A.rows(), A.cols(), E.rows(), E.cols()) = E; + result.block(A.rows(), A.cols() + B.cols(), F.rows(), F.cols()) = F; + result.block(A.rows() + D.rows(), 0, G.rows(), G.cols()) = G; + result.block(A.rows() + D.rows(), A.cols(), H.rows(), H.cols()) = H; + result.block(A.rows() + D.rows(), A.cols() + B.cols(), I.rows(), I.cols()) = I; + + return result; + } + + void sort_epairs(Vector& evalues, Matrix& evectors, int SelectionRule) + { + std::function cmp; + if (SelectionRule == SMALLEST_ALGE) + cmp = std::less{}; + else + cmp = std::greater{}; + + std::map epairs(cmp); + for (int i = 0; i < m_evectors.cols(); ++i) + epairs.insert(std::make_pair(evalues(i), evectors.col(i))); + + int i = 0; + for (auto& epair : epairs) + { + evectors.col(i) = epair.second; + evalues(i) = epair.first; + i++; + } + } + + void removeColumns(SparseMatrix& matrix, std::vector& colToRemove) + { + // remove columns through matrix multiplication + SparseMatrix new_matrix(matrix.cols(), matrix.cols() - int(colToRemove.size())); + int iCol = 0; + std::vector> tripletList; + tripletList.reserve(matrix.cols() - int(colToRemove.size())); + + for (int iRow = 0; iRow < matrix.cols(); iRow++) + { + if (std::find(colToRemove.begin(), colToRemove.end(), iRow) == colToRemove.end()) + { + tripletList.push_back(Eigen::Triplet(iRow, iCol, 1)); + iCol++; + } + } + + new_matrix.setFromTriplets(tripletList.begin(), tripletList.end()); + matrix = matrix * new_matrix; + } + + int checkConvergence_getBlocksize(SparseMatrix& m_residuals, Scalar tolerance_L2, std::vector& columnsToDelete) + { + // square roots from sum of squares by column + int BlockSize = m_nev; + Scalar sum, buffer; + + for (int iCol = 0; iCol < m_nev; iCol++) + { + sum = 0; + for (int iRow = 0; iRow < m_n; iRow++) + { + buffer = m_residuals.coeff(iRow, iCol); + sum += buffer * buffer; + } + + if (sqrt(sum) < tolerance_L2) + { + BlockSize--; + columnsToDelete.push_back(iCol); + } + } + return BlockSize; + } + +public: + LOBPCGSolver(const SparseMatrix& A, const SparseMatrix X) : + m_n(A.rows()), + m_nev(X.cols()), + m_info(NOT_COMPUTED), + flag_with_constraints(false), + flag_with_B(false), + flag_with_preconditioner(false), + A(A), + X(X) + { + if (A.rows() != X.rows() || A.rows() != A.cols()) + throw std::invalid_argument("Wrong size"); + + //if (m_n < 5* m_nev) + // throw std::invalid_argument("The problem size is small compared to the block size. Use standard eigensolver"); + } + + void setConstraints(const SparseMatrix& Y) + { + m_Y = Y; + flag_with_constraints = true; + } + + void setB(const SparseMatrix& B) + { + if (B.rows() != A.rows() || B.cols() != A.cols()) + throw std::invalid_argument("Wrong size"); + m_B = B; + flag_with_B = true; + } + + void setPreconditioner(const SparseMatrix& preconditioner) + { + m_preconditioner = preconditioner; + flag_with_preconditioner = true; + } + + void compute(int maxit = 10, Scalar tol_div_n = 1e-7) + { + Scalar tolerance_L2 = tol_div_n * m_n; + int BlockSize; + int max_iter = std::min(m_n, maxit); + + SparseMatrix directions, AX, AR, BX, AD, ADD, DD, BDD, BD, XAD, RAD, DAD, XBD, RBD, BR, sparse_eVecX, sparse_eVecR, sparse_eVecD, inverse_matrix; + Matrix XAR, RAR, XBR, gramA, gramB, eVecX, eVecR, eVecD; + std::vector columnsToDelete; + + if (flag_with_constraints) + { + // Apply the constraints Y to X + applyConstraintsInPlace(X, m_Y, m_B); + } + + // Make initial vectors orthonormal + // implicit BX declaration + if (orthogonalizeInPlace(X, m_B, BX) != SUCCESSFUL) + { + max_iter = 0; + } + + AX = A * X; + // Solve the following NxN eigenvalue problem for all N eigenvalues and -vectors: + // first approximation via a dense problem + Eigen::EigenSolver eigs(Matrix(X.transpose() * AX)); + + if (eigs.info() != SUCCESSFUL) + { + m_info = eigs.info(); + max_iter = 0; + } + else + { + m_evalues = eigs.eigenvalues().real(); + m_evectors = eigs.eigenvectors().real(); + sort_epairs(m_evalues, m_evectors, SMALLEST_ALGE); + sparse_eVecX = m_evectors.sparseView(); + + X = X * sparse_eVecX; + AX = AX * sparse_eVecX; + BX = BX * sparse_eVecX; + } + + for (int iter_num = 0; iter_num < max_iter; iter_num++) + { + m_residuals.resize(m_n, m_nev); + for (int i = 0; i < m_nev; i++) + { + m_residuals.col(i) = AX.col(i) - m_evalues(i) * BX.col(i); + } + BlockSize = checkConvergence_getBlocksize(m_residuals, tolerance_L2, columnsToDelete); + + if (BlockSize == 0) + { + m_info = SUCCESSFUL; + break; + } + + // substitution of the original active mask + if (columnsToDelete.size() > 0) + { + removeColumns(m_residuals, columnsToDelete); + if (iter_num > 0) + { + removeColumns(directions, columnsToDelete); + removeColumns(AD, columnsToDelete); + removeColumns(BD, columnsToDelete); + } + columnsToDelete.clear(); // for next iteration + } + + if (flag_with_preconditioner) + { + // Apply the preconditioner to the residuals + m_residuals = m_preconditioner * m_residuals; + } + + if (flag_with_constraints) + { + // Apply the constraints Y to residuals + applyConstraintsInPlace(m_residuals, m_Y, m_B); + } + + if (orthogonalizeInPlace(m_residuals, m_B, BR) != SUCCESSFUL) + { + break; + } + AR = A * m_residuals; + + // Orthonormalize conjugate directions + if (iter_num > 0) + { + if (orthogonalizeInPlace(directions, m_B, BD, true) != SUCCESSFUL) + { + break; + } + AD = A * directions; + } + + // Perform the Rayleigh Ritz Procedure + XAR = Matrix(X.transpose() * AR); + RAR = Matrix(m_residuals.transpose() * AR); + XBR = Matrix(X.transpose() * BR); + + if (iter_num > 0) + { + XAD = X.transpose() * AD; + RAD = m_residuals.transpose() * AD; + DAD = directions.transpose() * AD; + XBD = X.transpose() * BD; + RBD = m_residuals.transpose() * BD; + + gramA = stack_9_matricies(m_evalues.asDiagonal(), XAR, XAD, XAR.transpose(), RAR, RAD, XAD.transpose(), RAD.transpose(), DAD.transpose()); + gramB = stack_9_matricies(Matrix::Identity(m_nev, m_nev), XBR, XBD, XBR.transpose(), Matrix::Identity(BlockSize, BlockSize), RBD, XBD.transpose(), RBD.transpose(), Matrix::Identity(BlockSize, BlockSize)); + } + else + { + gramA = stack_4_matricies(m_evalues.asDiagonal(), XAR, XAR.transpose(), RAR); + gramB = stack_4_matricies(Matrix::Identity(m_nev, m_nev), XBR, XBR.transpose(), Matrix::Identity(BlockSize, BlockSize)); + } + + //calculate the lowest/largest m eigenpairs; Solve the generalized eigenvalue problem. + DenseSymMatProd Aop(gramA); + DenseCholesky Bop(gramB); + + SymGEigsSolver, + DenseCholesky, GEIGS_CHOLESKY> + geigs(&Aop, &Bop, m_nev, std::min(10, int(gramA.rows()) - 1)); + + geigs.init(); + int nconv = geigs.compute(); + + //Mat evecs; + if (geigs.info() == SUCCESSFUL) + { + m_evalues = geigs.eigenvalues(); + m_evectors = geigs.eigenvectors(); + sort_epairs(m_evalues, m_evectors, SMALLEST_ALGE); + } + else + { + // Problem With General EgenVec + m_info = geigs.info(); + break; + } + + // Compute Ritz vectors + if (iter_num > 0) + { + eVecX = m_evectors.block(0, 0, m_nev, m_nev); + eVecR = m_evectors.block(m_nev, 0, BlockSize, m_nev); + eVecD = m_evectors.block(m_nev + BlockSize, 0, BlockSize, m_nev); + + sparse_eVecX = eVecX.sparseView(); + sparse_eVecR = eVecR.sparseView(); + sparse_eVecD = eVecD.sparseView(); + + DD = m_residuals * sparse_eVecR; // new conjugate directions + ADD = AR * sparse_eVecR; + BDD = BR * sparse_eVecR; + + DD = DD + directions * sparse_eVecD; + ADD = ADD + AD * sparse_eVecD; + BDD = BDD + BD * sparse_eVecD; + } + else + { + eVecX = m_evectors.block(0, 0, m_nev, m_nev); + eVecR = m_evectors.block(m_nev, 0, BlockSize, m_nev); + + sparse_eVecX = eVecX.sparseView(); + sparse_eVecR = eVecR.sparseView(); + + DD = m_residuals * sparse_eVecR; + ADD = AR * sparse_eVecR; + BDD = BR * sparse_eVecR; + } + + X = X * sparse_eVecX + DD; + AX = AX * sparse_eVecX + ADD; + BX = BX * sparse_eVecX + BDD; + + directions = DD; + AD = ADD; + BD = BDD; + + } // iteration loop + + // calculate last residuals + m_residuals.resize(m_n, m_nev); + for (int i = 0; i < m_nev; i++) + { + m_residuals.col(i) = AX.col(i) - m_evalues(i) * BX.col(i); + } + BlockSize = checkConvergence_getBlocksize(m_residuals, tolerance_L2, columnsToDelete); + + if (BlockSize == 0) + { + m_info = SUCCESSFUL; + } + } // compute + + Vector eigenvalues() + { + return m_evalues; + } + + Matrix eigenvectors() + { + return m_evectors; + } + + Matrix residuals() + { + return Matrix(m_residuals); + } + + int info() { return m_info; } +}; + +} // namespace Spectra + +#endif // LOBPCG_SOLVER diff --git a/gtsam/3rdparty/Spectra/contrib/PartialSVDSolver.h b/gtsam/3rdparty/Spectra/contrib/PartialSVDSolver.h new file mode 100644 index 000000000..2fab26b97 --- /dev/null +++ b/gtsam/3rdparty/Spectra/contrib/PartialSVDSolver.h @@ -0,0 +1,202 @@ +// Copyright (C) 2018 Yixuan Qiu +// +// This Source Code Form is subject to the terms of the Mozilla +// Public License v. 2.0. If a copy of the MPL was not distributed +// with this file, You can obtain one at https://mozilla.org/MPL/2.0/. + +#ifndef PARTIAL_SVD_SOLVER_H +#define PARTIAL_SVD_SOLVER_H + +#include +#include "../SymEigsSolver.h" + +namespace Spectra { + +// Abstract class for matrix operation +template +class SVDMatOp +{ +public: + virtual int rows() const = 0; + virtual int cols() const = 0; + + // y_out = A' * A * x_in or y_out = A * A' * x_in + virtual void perform_op(const Scalar* x_in, Scalar* y_out) = 0; + + virtual ~SVDMatOp() {} +}; + +// Operation of a tall matrix in SVD +// We compute the eigenvalues of A' * A +// MatrixType is either Eigen::Matrix or Eigen::SparseMatrix +template +class SVDTallMatOp : public SVDMatOp +{ +private: + typedef Eigen::Matrix Vector; + typedef Eigen::Map MapConstVec; + typedef Eigen::Map MapVec; + typedef const Eigen::Ref ConstGenericMatrix; + + ConstGenericMatrix m_mat; + const int m_dim; + Vector m_cache; + +public: + // Constructor + SVDTallMatOp(ConstGenericMatrix& mat) : + m_mat(mat), + m_dim(std::min(mat.rows(), mat.cols())), + m_cache(mat.rows()) + {} + + // These are the rows and columns of A' * A + int rows() const { return m_dim; } + int cols() const { return m_dim; } + + // y_out = A' * A * x_in + void perform_op(const Scalar* x_in, Scalar* y_out) + { + MapConstVec x(x_in, m_mat.cols()); + MapVec y(y_out, m_mat.cols()); + m_cache.noalias() = m_mat * x; + y.noalias() = m_mat.transpose() * m_cache; + } +}; + +// Operation of a wide matrix in SVD +// We compute the eigenvalues of A * A' +// MatrixType is either Eigen::Matrix or Eigen::SparseMatrix +template +class SVDWideMatOp : public SVDMatOp +{ +private: + typedef Eigen::Matrix Vector; + typedef Eigen::Map MapConstVec; + typedef Eigen::Map MapVec; + typedef const Eigen::Ref ConstGenericMatrix; + + ConstGenericMatrix m_mat; + const int m_dim; + Vector m_cache; + +public: + // Constructor + SVDWideMatOp(ConstGenericMatrix& mat) : + m_mat(mat), + m_dim(std::min(mat.rows(), mat.cols())), + m_cache(mat.cols()) + {} + + // These are the rows and columns of A * A' + int rows() const { return m_dim; } + int cols() const { return m_dim; } + + // y_out = A * A' * x_in + void perform_op(const Scalar* x_in, Scalar* y_out) + { + MapConstVec x(x_in, m_mat.rows()); + MapVec y(y_out, m_mat.rows()); + m_cache.noalias() = m_mat.transpose() * x; + y.noalias() = m_mat * m_cache; + } +}; + +// Partial SVD solver +// MatrixType is either Eigen::Matrix or Eigen::SparseMatrix +template > +class PartialSVDSolver +{ +private: + typedef Eigen::Matrix Matrix; + typedef Eigen::Matrix Vector; + typedef const Eigen::Ref ConstGenericMatrix; + + ConstGenericMatrix m_mat; + const int m_m; + const int m_n; + SVDMatOp* m_op; + SymEigsSolver >* m_eigs; + int m_nconv; + Matrix m_evecs; + +public: + // Constructor + PartialSVDSolver(ConstGenericMatrix& mat, int ncomp, int ncv) : + m_mat(mat), m_m(mat.rows()), m_n(mat.cols()), m_evecs(0, 0) + { + // Determine the matrix type, tall or wide + if (m_m > m_n) + { + m_op = new SVDTallMatOp(mat); + } + else + { + m_op = new SVDWideMatOp(mat); + } + + // Solver object + m_eigs = new SymEigsSolver >(m_op, ncomp, ncv); + } + + // Destructor + virtual ~PartialSVDSolver() + { + delete m_eigs; + delete m_op; + } + + // Computation + int compute(int maxit = 1000, Scalar tol = 1e-10) + { + m_eigs->init(); + m_nconv = m_eigs->compute(maxit, tol); + + return m_nconv; + } + + // The converged singular values + Vector singular_values() const + { + Vector svals = m_eigs->eigenvalues().cwiseSqrt(); + + return svals; + } + + // The converged left singular vectors + Matrix matrix_U(int nu) + { + if (m_evecs.cols() < 1) + { + m_evecs = m_eigs->eigenvectors(); + } + nu = std::min(nu, m_nconv); + if (m_m <= m_n) + { + return m_evecs.leftCols(nu); + } + + return m_mat * (m_evecs.leftCols(nu).array().rowwise() / m_eigs->eigenvalues().head(nu).transpose().array().sqrt()).matrix(); + } + + // The converged right singular vectors + Matrix matrix_V(int nv) + { + if (m_evecs.cols() < 1) + { + m_evecs = m_eigs->eigenvectors(); + } + nv = std::min(nv, m_nconv); + if (m_m > m_n) + { + return m_evecs.leftCols(nv); + } + + return m_mat.transpose() * (m_evecs.leftCols(nv).array().rowwise() / m_eigs->eigenvalues().head(nv).transpose().array().sqrt()).matrix(); + } +}; + +} // namespace Spectra + +#endif // PARTIAL_SVD_SOLVER_H diff --git a/gtsam/CMakeLists.txt b/gtsam/CMakeLists.txt index 49b8bc19b..8736a5954 100644 --- a/gtsam/CMakeLists.txt +++ b/gtsam/CMakeLists.txt @@ -136,6 +136,8 @@ target_include_directories(gtsam BEFORE PUBLIC # SuiteSparse_config $ $ + # Spectra + $ # CCOLAMD $ $ From aae9c19d0fa7dc152b0818511a0a7d11e96c53bc Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Tue, 11 Aug 2020 00:25:42 -0500 Subject: [PATCH 337/869] example using CombinedImuFactor --- examples/CombinedImuFactorsExample.cpp | 287 +++++++++++++++++++++++++ 1 file changed, 287 insertions(+) create mode 100644 examples/CombinedImuFactorsExample.cpp diff --git a/examples/CombinedImuFactorsExample.cpp b/examples/CombinedImuFactorsExample.cpp new file mode 100644 index 000000000..f04f2ddd4 --- /dev/null +++ b/examples/CombinedImuFactorsExample.cpp @@ -0,0 +1,287 @@ +/* ---------------------------------------------------------------------------- + + * GTSAM Copyright 2010, Georgia Tech Research Corporation, + * Atlanta, Georgia 30332-0415 + * All Rights Reserved + * Authors: Frank Dellaert, et al. (see THANKS for the full author list) + + * See LICENSE for the license information + + * -------------------------------------------------------------------------- */ + +/** + * @file CombinedImuFactorsExample + * @brief Test example for using GTSAM ImuCombinedFactor + * navigation code. + * @author Varun Agrawal + */ + +/** + * Example of use of the CombinedImuFactor in + * conjunction with GPS + * - we read IMU and GPS data from a CSV file, with the following format: + * A row starting with "i" is the first initial position formatted with + * N, E, D, qx, qY, qZ, qW, velN, velE, velD + * A row starting with "0" is an imu measurement + * linAccN, linAccE, linAccD, angVelN, angVelE, angVelD + * A row starting with "1" is a gps correction formatted with + * N, E, D, qX, qY, qZ, qW + * Note that for GPS correction, we're only using the position not the + * rotation. The rotation is provided in the file for ground truth comparison. + * + * Usage: ./CombinedImuFactorsExample [data_csv_path] [-c] + * optional arguments: + * data_csv_path path to the CSV file with the IMU data. + * -c use CombinedImuFactor + */ + +// GTSAM related includes. +#include +#include +#include +#include +#include +#include +#include +#include + +#include +#include +#include + +using namespace gtsam; +using namespace std; + +using symbol_shorthand::B; // Bias (ax,ay,az,gx,gy,gz) +using symbol_shorthand::V; // Vel (xdot,ydot,zdot) +using symbol_shorthand::X; // Pose3 (x,y,z,r,p,y) + +Vector10 readInitialState(ifstream& file) { + string value; + // Format is (N,E,D,qX,qY,qZ,qW,velN,velE,velD) + Vector10 initial_state; + getline(file, value, ','); // i + for (int i = 0; i < 9; i++) { + getline(file, value, ','); + initial_state(i) = atof(value.c_str()); + } + getline(file, value, '\n'); + initial_state(9) = atof(value.c_str()); + + return initial_state; +} + +boost::shared_ptr imuParams() { + // We use the sensor specs to build the noise model for the IMU factor. + double accel_noise_sigma = 0.0003924; + double gyro_noise_sigma = 0.000205689024915; + double accel_bias_rw_sigma = 0.004905; + double gyro_bias_rw_sigma = 0.000001454441043; + Matrix33 measured_acc_cov = I_3x3 * pow(accel_noise_sigma, 2); + Matrix33 measured_omega_cov = I_3x3 * pow(gyro_noise_sigma, 2); + Matrix33 integration_error_cov = + I_3x3 * 1e-8; // error committed in integrating position from velocities + Matrix33 bias_acc_cov = I_3x3 * pow(accel_bias_rw_sigma, 2); + Matrix33 bias_omega_cov = I_3x3 * pow(gyro_bias_rw_sigma, 2); + Matrix66 bias_acc_omega_int = + I_6x6 * 1e-5; // error in the bias used for preintegration + + auto p = PreintegratedCombinedMeasurements::Params::MakeSharedD(0.0); + // PreintegrationBase params: + p->accelerometerCovariance = + measured_acc_cov; // acc white noise in continuous + p->integrationCovariance = + integration_error_cov; // integration uncertainty continuous + // should be using 2nd order integration + // PreintegratedRotation params: + p->gyroscopeCovariance = + measured_omega_cov; // gyro white noise in continuous + // PreintegrationCombinedMeasurements params: + p->biasAccCovariance = bias_acc_cov; // acc bias in continuous + p->biasOmegaCovariance = bias_omega_cov; // gyro bias in continuous + p->biasAccOmegaInt = bias_acc_omega_int; + + return p; +} + +int main(int argc, char* argv[]) { + string data_filename, output_filename; + if (argc == 3) { + data_filename = argv[1]; + output_filename = argv[2]; + } else if (argc == 2) { + data_filename = argv[1]; + output_filename = "imuFactorExampleResults.csv"; + } else { + printf("using default CSV file\n"); + data_filename = findExampleDataFile("imuAndGPSdata.csv"); + output_filename = "imuFactorExampleResults.csv"; + } + + // Set up output file for plotting errors + FILE* fp_out = fopen(output_filename.c_str(), "w+"); + fprintf(fp_out, + "#time(s),x(m),y(m),z(m),qx,qy,qz,qw,gt_x(m),gt_y(m),gt_z(m),gt_qx," + "gt_qy,gt_qz,gt_qw\n"); + + // Begin parsing the CSV file. Input the first line for initialization. + // From there, we'll iterate through the file and we'll preintegrate the IMU + // or add in the GPS given the input. + ifstream file(data_filename.c_str()); + + Vector10 initial_state = readInitialState(file); + cout << "initial state:\n" << initial_state.transpose() << "\n\n"; + + // Assemble initial quaternion through GTSAM constructor + // ::Quaternion(w,x,y,z); + Rot3 prior_rotation = Rot3::Quaternion(initial_state(6), initial_state(3), + initial_state(4), initial_state(5)); + Point3 prior_point(initial_state.head<3>()); + Pose3 prior_pose(prior_rotation, prior_point); + Vector3 prior_velocity(initial_state.tail<3>()); + + imuBias::ConstantBias prior_imu_bias; // assume zero initial bias + + int index = 0; + + Values initial_values; + + // insert pose at initialization + initial_values.insert(X(index), prior_pose); + initial_values.insert(V(index), prior_velocity); + initial_values.insert(B(index), prior_imu_bias); + + // Assemble prior noise model and add it the graph.` + auto pose_noise_model = noiseModel::Diagonal::Sigmas( + (Vector(6) << 0.01, 0.01, 0.01, 0.5, 0.5, 0.5) + .finished()); // rad,rad,rad,m, m, m + auto velocity_noise_model = noiseModel::Isotropic::Sigma(3, 0.1); // m/s + auto bias_noise_model = noiseModel::Isotropic::Sigma(6, 1e-3); + + // Add all prior factors (pose, velocity, bias) to the graph. + NonlinearFactorGraph graph; + graph.addPrior(X(index), prior_pose, pose_noise_model); + graph.addPrior(V(index), prior_velocity, velocity_noise_model); + graph.addPrior(B(index), prior_imu_bias, + bias_noise_model); + + auto p = imuParams(); + + std::shared_ptr preintegrated = + std::make_shared(p, prior_imu_bias); + + assert(preintegrated); + + // Store previous state for imu integration and latest predicted outcome. + NavState prev_state(prior_pose, prior_velocity); + NavState prop_state = prev_state; + imuBias::ConstantBias prev_bias = prior_imu_bias; + + // Keep track of total error over the entire run as simple performance metric. + double current_position_error = 0.0, current_orientation_error = 0.0; + + double output_time = 0.0; + double dt = 0.005; // The real system has noise, but here, results are nearly + // exactly the same, so keeping this for simplicity. + + // All priors have been set up, now iterate through the data file. + while (file.good()) { + // Parse out first value + string value; + getline(file, value, ','); + int type = atoi(value.c_str()); + + if (type == 0) { // IMU measurement + Vector6 imu; + for (int i = 0; i < 5; ++i) { + getline(file, value, ','); + imu(i) = atof(value.c_str()); + } + getline(file, value, '\n'); + imu(5) = atof(value.c_str()); + + // Adding the IMU preintegration. + preintegrated->integrateMeasurement(imu.head<3>(), imu.tail<3>(), dt); + + } else if (type == 1) { // GPS measurement + Vector7 gps; + for (int i = 0; i < 6; ++i) { + getline(file, value, ','); + gps(i) = atof(value.c_str()); + } + getline(file, value, '\n'); + gps(6) = atof(value.c_str()); + + index++; + + // Adding IMU factor and GPS factor and optimizing. + auto preint_imu_combined = + dynamic_cast( + *preintegrated); + CombinedImuFactor imu_factor(X(index - 1), V(index - 1), X(index), + V(index), B(index - 1), B(index), + preint_imu_combined); + graph.add(imu_factor); + + auto correction_noise = noiseModel::Isotropic::Sigma(3, 1.0); + GPSFactor gps_factor(X(index), + Point3(gps(0), // N, + gps(1), // E, + gps(2)), // D, + correction_noise); + graph.add(gps_factor); + + // Now optimize and compare results. + prop_state = preintegrated->predict(prev_state, prev_bias); + initial_values.insert(X(index), prop_state.pose()); + initial_values.insert(V(index), prop_state.v()); + initial_values.insert(B(index), prev_bias); + + LevenbergMarquardtParams params; + params.setVerbosityLM("SUMMARY"); + LevenbergMarquardtOptimizer optimizer(graph, initial_values, params); + Values result = optimizer.optimize(); + + // Overwrite the beginning of the preintegration for the next step. + prev_state = + NavState(result.at(X(index)), result.at(V(index))); + prev_bias = result.at(B(index)); + + // Reset the preintegration object. + preintegrated->resetIntegrationAndSetBias(prev_bias); + + // Print out the position and orientation error for comparison. + Vector3 result_position = prev_state.pose().translation(); + Vector3 position_error = result_position - gps.head<3>(); + current_position_error = position_error.norm(); + + Quaternion result_quat = prev_state.pose().rotation().toQuaternion(); + Quaternion gps_quat(gps(6), gps(3), gps(4), gps(5)); + Quaternion quat_error = result_quat * gps_quat.inverse(); + quat_error.normalize(); + Vector3 euler_angle_error(quat_error.x() * 2, quat_error.y() * 2, + quat_error.z() * 2); + current_orientation_error = euler_angle_error.norm(); + + // display statistics + cout << "Position error:" << current_position_error << "\t " + << "Angular error:" << current_orientation_error << "\n" << endl; + + fprintf(fp_out, "%f,%f,%f,%f,%f,%f,%f,%f,%f,%f,%f,%f,%f,%f,%f\n", + output_time, result_position(0), result_position(1), + result_position(2), result_quat.x(), result_quat.y(), + result_quat.z(), result_quat.w(), gps(0), gps(1), gps(2), + gps_quat.x(), gps_quat.y(), gps_quat.z(), gps_quat.w()); + + output_time += 1.0; + + } else { + cerr << "ERROR parsing file\n"; + return 1; + } + } + fclose(fp_out); + cout << "Complete, results written to " << output_filename << "\n\n"; + + return 0; +} From 3bc109de538c8281c25370ee61686816ad846fed Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Tue, 11 Aug 2020 00:26:34 -0500 Subject: [PATCH 338/869] renamed ImuFactorExample2 to be more consistent with naming --- examples/{ImuFactorExample2.cpp => ImuFactorsExample2.cpp} | 0 1 file changed, 0 insertions(+), 0 deletions(-) rename examples/{ImuFactorExample2.cpp => ImuFactorsExample2.cpp} (100%) diff --git a/examples/ImuFactorExample2.cpp b/examples/ImuFactorsExample2.cpp similarity index 100% rename from examples/ImuFactorExample2.cpp rename to examples/ImuFactorsExample2.cpp From 311491abfc19a549397d907679c45d16a2a12753 Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Tue, 11 Aug 2020 00:29:29 -0500 Subject: [PATCH 339/869] revert author change --- cython/gtsam/examples/ImuFactorISAM2Example.py | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/cython/gtsam/examples/ImuFactorISAM2Example.py b/cython/gtsam/examples/ImuFactorISAM2Example.py index 3d3138bf5..4187fe878 100644 --- a/cython/gtsam/examples/ImuFactorISAM2Example.py +++ b/cython/gtsam/examples/ImuFactorISAM2Example.py @@ -1,6 +1,6 @@ """ -iSAM2 example with ImuFactor. -Author: Frank Dellaert, Varun Agrawal +ImuFactor example with iSAM2. +Authors: Robert Truax (C++), Frank Dellaert, Varun Agrawal (Python) """ # pylint: disable=invalid-name, E1101 From 4949f8bb9d507de8cac51ebf75d48db8ed88d499 Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Tue, 11 Aug 2020 01:32:44 -0500 Subject: [PATCH 340/869] reworked basic ImuFactorsExample --- examples/ImuFactorsExample.cpp | 194 ++++++++++++++++----------------- 1 file changed, 92 insertions(+), 102 deletions(-) diff --git a/examples/ImuFactorsExample.cpp b/examples/ImuFactorsExample.cpp index 315f7b8e1..fe1a99ed0 100644 --- a/examples/ImuFactorsExample.cpp +++ b/examples/ImuFactorsExample.cpp @@ -40,15 +40,15 @@ */ // GTSAM related includes. +#include #include #include #include -#include -#include +#include #include #include -#include -#include +#include +#include #include #include @@ -64,45 +64,75 @@ using symbol_shorthand::B; // Bias (ax,ay,az,gx,gy,gz) using symbol_shorthand::V; // Vel (xdot,ydot,zdot) using symbol_shorthand::X; // Pose3 (x,y,z,r,p,y) -static const char output_filename[] = "imuFactorExampleResults.csv"; -static const char use_combined_imu_flag[3] = "-c"; +boost::shared_ptr imuParams() { + // We use the sensor specs to build the noise model for the IMU factor. + double accel_noise_sigma = 0.0003924; + double gyro_noise_sigma = 0.000205689024915; + double accel_bias_rw_sigma = 0.004905; + double gyro_bias_rw_sigma = 0.000001454441043; + Matrix33 measured_acc_cov = I_3x3 * pow(accel_noise_sigma, 2); + Matrix33 measured_omega_cov = I_3x3 * pow(gyro_noise_sigma, 2); + Matrix33 integration_error_cov = + I_3x3 * 1e-8; // error committed in integrating position from velocities + Matrix33 bias_acc_cov = I_3x3 * pow(accel_bias_rw_sigma, 2); + Matrix33 bias_omega_cov = I_3x3 * pow(gyro_bias_rw_sigma, 2); + Matrix66 bias_acc_omega_int = + I_6x6 * 1e-5; // error in the bias used for preintegration + + auto p = PreintegratedCombinedMeasurements::Params::MakeSharedD(0.0); + // PreintegrationBase params: + p->accelerometerCovariance = + measured_acc_cov; // acc white noise in continuous + p->integrationCovariance = + integration_error_cov; // integration uncertainty continuous + // should be using 2nd order integration + // PreintegratedRotation params: + p->gyroscopeCovariance = + measured_omega_cov; // gyro white noise in continuous + // PreintegrationCombinedMeasurements params: + p->biasAccCovariance = bias_acc_cov; // acc bias in continuous + p->biasOmegaCovariance = bias_omega_cov; // gyro bias in continuous + p->biasAccOmegaInt = bias_acc_omega_int; + + return p; +} int main(int argc, char* argv[]) { - string data_filename; - bool use_combined_imu = false; + string data_filename, output_filename; -#ifndef USE_LM - printf("Using ISAM2\n"); - ISAM2Params parameters; - parameters.relinearizeThreshold = 0.01; - parameters.relinearizeSkip = 1; - ISAM2 isam2(parameters); -#else - printf("Using Levenberg Marquardt Optimizer\n"); -#endif + bool use_isam = false; - if (argc < 2) { - printf("using default CSV file\n"); - data_filename = findExampleDataFile("imuAndGPSdata.csv"); - } else if (argc < 3) { - if (strcmp(argv[1], use_combined_imu_flag) == 0) { - printf("using CombinedImuFactor\n"); - use_combined_imu = true; - printf("using default CSV file\n"); - data_filename = findExampleDataFile("imuAndGPSdata.csv"); - } else { - data_filename = argv[1]; - } - } else { + if (argc == 4) { data_filename = argv[1]; - if (strcmp(argv[2], use_combined_imu_flag) == 0) { - printf("using CombinedImuFactor\n"); - use_combined_imu = true; - } + output_filename = argv[2]; + use_isam = atoi(argv[3]); + + } else if (argc == 3) { + data_filename = argv[1]; + output_filename = argv[2]; + } else if (argc == 2) { + data_filename = argv[1]; + output_filename = "imuFactorExampleResults.csv"; + } else { + printf("using default files\n"); + data_filename = findExampleDataFile("imuAndGPSdata.csv"); + output_filename = "imuFactorExampleResults.csv"; + } + + ISAM2* isam2; + if (use_isam) { + printf("Using ISAM2\n"); + ISAM2Params parameters; + parameters.relinearizeThreshold = 0.01; + parameters.relinearizeSkip = 1; + isam2 = new ISAM2(parameters); + + } else { + printf("Using Levenberg Marquardt Optimizer\n"); } // Set up output file for plotting errors - FILE* fp_out = fopen(output_filename, "w+"); + FILE* fp_out = fopen(output_filename.c_str(), "w+"); fprintf(fp_out, "#time(s),x(m),y(m),z(m),qx,qy,qz,qw,gt_x(m),gt_y(m),gt_z(m),gt_qx," "gt_qy,gt_qz,gt_qw\n"); @@ -152,43 +182,11 @@ int main(int argc, char* argv[]) { graph->addPrior(V(correction_count), prior_velocity, velocity_noise_model); graph->addPrior(B(correction_count), prior_imu_bias, bias_noise_model); - // We use the sensor specs to build the noise model for the IMU factor. - double accel_noise_sigma = 0.0003924; - double gyro_noise_sigma = 0.000205689024915; - double accel_bias_rw_sigma = 0.004905; - double gyro_bias_rw_sigma = 0.000001454441043; - Matrix33 measured_acc_cov = I_3x3 * pow(accel_noise_sigma, 2); - Matrix33 measured_omega_cov = I_3x3 * pow(gyro_noise_sigma, 2); - Matrix33 integration_error_cov = - I_3x3 * 1e-8; // error committed in integrating position from velocities - Matrix33 bias_acc_cov = I_3x3 * pow(accel_bias_rw_sigma, 2); - Matrix33 bias_omega_cov = I_3x3 * pow(gyro_bias_rw_sigma, 2); - Matrix66 bias_acc_omega_int = - I_6x6 * 1e-5; // error in the bias used for preintegration + auto p = imuParams(); - auto p = PreintegratedCombinedMeasurements::Params::MakeSharedD(0.0); - // PreintegrationBase params: - p->accelerometerCovariance = - measured_acc_cov; // acc white noise in continuous - p->integrationCovariance = - integration_error_cov; // integration uncertainty continuous - // should be using 2nd order integration - // PreintegratedRotation params: - p->gyroscopeCovariance = - measured_omega_cov; // gyro white noise in continuous - // PreintegrationCombinedMeasurements params: - p->biasAccCovariance = bias_acc_cov; // acc bias in continuous - p->biasOmegaCovariance = bias_omega_cov; // gyro bias in continuous - p->biasAccOmegaInt = bias_acc_omega_int; + std::shared_ptr preintegrated = + std::make_shared(p, prior_imu_bias); - std::shared_ptr preintegrated = nullptr; - if (use_combined_imu) { - preintegrated = - std::make_shared(p, prior_imu_bias); - } else { - preintegrated = - std::make_shared(p, prior_imu_bias); - } assert(preintegrated); // Store previous state for imu integration and latest predicted outcome. @@ -233,27 +231,16 @@ int main(int argc, char* argv[]) { correction_count++; // Adding IMU factor and GPS factor and optimizing. - if (use_combined_imu) { - auto preint_imu_combined = - dynamic_cast( - *preintegrated); - CombinedImuFactor imu_factor( - X(correction_count - 1), V(correction_count - 1), - X(correction_count), V(correction_count), B(correction_count - 1), - B(correction_count), preint_imu_combined); - graph->add(imu_factor); - } else { - auto preint_imu = - dynamic_cast(*preintegrated); - ImuFactor imu_factor(X(correction_count - 1), V(correction_count - 1), - X(correction_count), V(correction_count), - B(correction_count - 1), preint_imu); - graph->add(imu_factor); - imuBias::ConstantBias zero_bias(Vector3(0, 0, 0), Vector3(0, 0, 0)); - graph->add(BetweenFactor( - B(correction_count - 1), B(correction_count), zero_bias, - bias_noise_model)); - } + auto preint_imu = + dynamic_cast(*preintegrated); + ImuFactor imu_factor(X(correction_count - 1), V(correction_count - 1), + X(correction_count), V(correction_count), + B(correction_count - 1), preint_imu); + graph->add(imu_factor); + imuBias::ConstantBias zero_bias(Vector3(0, 0, 0), Vector3(0, 0, 0)); + graph->add(BetweenFactor( + B(correction_count - 1), B(correction_count), zero_bias, + bias_noise_model)); auto correction_noise = noiseModel::Isotropic::Sigma(3, 1.0); GPSFactor gps_factor(X(correction_count), @@ -270,18 +257,21 @@ int main(int argc, char* argv[]) { initial_values.insert(B(correction_count), prev_bias); Values result; -#ifdef USE_LM - LevenbergMarquardtOptimizer optimizer(*graph, initial_values); - result = optimizer.optimize(); -#else - isam2.update(*graph, initial_values); - isam2.update(); - result = isam2.calculateEstimate(); - // reset the graph - graph->resize(0); - initial_values.clear(); -#endif + if (use_isam) { + isam2->update(*graph, initial_values); + isam2->update(); + result = isam2->calculateEstimate(); + + // reset the graph + graph->resize(0); + initial_values.clear(); + + } else { + LevenbergMarquardtOptimizer optimizer(*graph, initial_values); + result = optimizer.optimize(); + } + // Overwrite the beginning of the preintegration for the next step. prev_state = NavState(result.at(X(correction_count)), result.at(V(correction_count))); From a1f6e1585af155692ae9611bbe4324f957b2e496 Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Tue, 11 Aug 2020 01:32:58 -0500 Subject: [PATCH 341/869] use boost program_options for command line parsing --- examples/CombinedImuFactorsExample.cpp | 48 +++++++++++++++-------- examples/ImuFactorsExample.cpp | 54 ++++++++++++++------------ 2 files changed, 62 insertions(+), 40 deletions(-) diff --git a/examples/CombinedImuFactorsExample.cpp b/examples/CombinedImuFactorsExample.cpp index f04f2ddd4..2e5c46025 100644 --- a/examples/CombinedImuFactorsExample.cpp +++ b/examples/CombinedImuFactorsExample.cpp @@ -29,12 +29,11 @@ * Note that for GPS correction, we're only using the position not the * rotation. The rotation is provided in the file for ground truth comparison. * - * Usage: ./CombinedImuFactorsExample [data_csv_path] [-c] - * optional arguments: - * data_csv_path path to the CSV file with the IMU data. - * -c use CombinedImuFactor + * See usage: ./CombinedImuFactorsExample --help */ +#include + // GTSAM related includes. #include #include @@ -56,6 +55,29 @@ using symbol_shorthand::B; // Bias (ax,ay,az,gx,gy,gz) using symbol_shorthand::V; // Vel (xdot,ydot,zdot) using symbol_shorthand::X; // Pose3 (x,y,z,r,p,y) +namespace po = boost::program_options; + +po::variables_map parseOptions(int argc, char* argv[]) { + po::options_description desc; + desc.add_options()("help,h", "produce help message")( + "data_csv_path", po::value()->default_value("imuAndGPSdata.csv"), + "path to the CSV file with the IMU data")( + "output_filename", + po::value()->default_value("imuFactorExampleResults.csv"), + "path to the result file to use")("use_isam", po::bool_switch(), + "use ISAM as the optimizer"); + + po::variables_map vm; + po::store(po::parse_command_line(argc, argv, desc), vm); + + if (vm.count("help")) { + cout << desc << "\n"; + exit(1); + } + + return vm; +} + Vector10 readInitialState(ifstream& file) { string value; // Format is (N,E,D,qX,qY,qZ,qW,velN,velE,velD) @@ -106,17 +128,10 @@ boost::shared_ptr imuParams() { int main(int argc, char* argv[]) { string data_filename, output_filename; - if (argc == 3) { - data_filename = argv[1]; - output_filename = argv[2]; - } else if (argc == 2) { - data_filename = argv[1]; - output_filename = "imuFactorExampleResults.csv"; - } else { - printf("using default CSV file\n"); - data_filename = findExampleDataFile("imuAndGPSdata.csv"); - output_filename = "imuFactorExampleResults.csv"; - } + po::variables_map var_map = parseOptions(argc, argv); + + data_filename = findExampleDataFile(var_map["data_csv_path"].as()); + output_filename = var_map["output_filename"].as(); // Set up output file for plotting errors FILE* fp_out = fopen(output_filename.c_str(), "w+"); @@ -265,7 +280,8 @@ int main(int argc, char* argv[]) { // display statistics cout << "Position error:" << current_position_error << "\t " - << "Angular error:" << current_orientation_error << "\n" << endl; + << "Angular error:" << current_orientation_error << "\n" + << endl; fprintf(fp_out, "%f,%f,%f,%f,%f,%f,%f,%f,%f,%f,%f,%f,%f,%f,%f\n", output_time, result_position(0), result_position(1), diff --git a/examples/ImuFactorsExample.cpp b/examples/ImuFactorsExample.cpp index fe1a99ed0..20dc2c261 100644 --- a/examples/ImuFactorsExample.cpp +++ b/examples/ImuFactorsExample.cpp @@ -31,14 +31,11 @@ * Note that for GPS correction, we're only using the position not the * rotation. The rotation is provided in the file for ground truth comparison. * - * Usage: ./ImuFactorsExample [data_csv_path] [-c] - * optional arguments: - * data_csv_path path to the CSV file with the IMU data. - * -c use CombinedImuFactor - * Note: Define USE_LM to use Levenberg Marquardt Optimizer - * By default ISAM2 is used + * See usage: ./ImuFactorsExample --help */ +#include + // GTSAM related includes. #include #include @@ -54,9 +51,6 @@ #include #include -// Uncomment the following to use Levenberg Marquardt Optimizer -// #define USE_LM - using namespace gtsam; using namespace std; @@ -64,6 +58,29 @@ using symbol_shorthand::B; // Bias (ax,ay,az,gx,gy,gz) using symbol_shorthand::V; // Vel (xdot,ydot,zdot) using symbol_shorthand::X; // Pose3 (x,y,z,r,p,y) +namespace po = boost::program_options; + +po::variables_map parseOptions(int argc, char* argv[]) { + po::options_description desc; + desc.add_options()("help,h", "produce help message")( + "data_csv_path", po::value()->default_value("imuAndGPSdata.csv"), + "path to the CSV file with the IMU data")( + "output_filename", + po::value()->default_value("imuFactorExampleResults.csv"), + "path to the result file to use")("use_isam", po::bool_switch(), + "use ISAM as the optimizer"); + + po::variables_map vm; + po::store(po::parse_command_line(argc, argv, desc), vm); + + if (vm.count("help")) { + cout << desc << "\n"; + exit(1); + } + + return vm; +} + boost::shared_ptr imuParams() { // We use the sensor specs to build the noise model for the IMU factor. double accel_noise_sigma = 0.0003924; @@ -102,22 +119,11 @@ int main(int argc, char* argv[]) { bool use_isam = false; - if (argc == 4) { - data_filename = argv[1]; - output_filename = argv[2]; - use_isam = atoi(argv[3]); + po::variables_map var_map = parseOptions(argc, argv); - } else if (argc == 3) { - data_filename = argv[1]; - output_filename = argv[2]; - } else if (argc == 2) { - data_filename = argv[1]; - output_filename = "imuFactorExampleResults.csv"; - } else { - printf("using default files\n"); - data_filename = findExampleDataFile("imuAndGPSdata.csv"); - output_filename = "imuFactorExampleResults.csv"; - } + data_filename = findExampleDataFile(var_map["data_csv_path"].as()); + output_filename = var_map["output_filename"].as(); + use_isam = var_map["use_isam"].as(); ISAM2* isam2; if (use_isam) { From aa2d0f3dece0b1401b942596c50340362c735141 Mon Sep 17 00:00:00 2001 From: alexma3312 Date: Wed, 12 Aug 2020 13:14:18 -0400 Subject: [PATCH 342/869] Change typedef into using. --- gtsam/geometry/Pose3.h | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/gtsam/geometry/Pose3.h b/gtsam/geometry/Pose3.h index 57bec4dee..3efa1b04d 100644 --- a/gtsam/geometry/Pose3.h +++ b/gtsam/geometry/Pose3.h @@ -357,7 +357,8 @@ inline Matrix wedge(const Vector& xi) { } // Convenience typedef -typedef std::pair Pose3Pair; +// typedef std::pair Pose3Pair; +using Pose3Pair = std::pair; // For MATLAB wrapper typedef std::vector Pose3Vector; From 68a8320c6821e5d742d45411dcd0b69ee886e94e Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Thu, 13 Aug 2020 14:17:51 -0500 Subject: [PATCH 343/869] default string value for printing Imu factors --- gtsam/navigation/CombinedImuFactor.cpp | 9 +++++---- gtsam/navigation/CombinedImuFactor.h | 4 ++-- gtsam/navigation/ImuFactor.cpp | 14 +++++++------- gtsam/navigation/ImuFactor.h | 8 ++++---- gtsam/navigation/PreintegratedRotation.cpp | 5 ++--- gtsam/navigation/PreintegrationBase.cpp | 2 +- gtsam/navigation/PreintegrationBase.h | 2 +- 7 files changed, 22 insertions(+), 22 deletions(-) diff --git a/gtsam/navigation/CombinedImuFactor.cpp b/gtsam/navigation/CombinedImuFactor.cpp index 49c666030..e41a8de44 100644 --- a/gtsam/navigation/CombinedImuFactor.cpp +++ b/gtsam/navigation/CombinedImuFactor.cpp @@ -167,10 +167,11 @@ gtsam::NonlinearFactor::shared_ptr CombinedImuFactor::clone() const { //------------------------------------------------------------------------------ void CombinedImuFactor::print(const string& s, const KeyFormatter& keyFormatter) const { - cout << s << "CombinedImuFactor(" << keyFormatter(this->key1()) << "," - << keyFormatter(this->key2()) << "," << keyFormatter(this->key3()) << "," - << keyFormatter(this->key4()) << "," << keyFormatter(this->key5()) << "," - << keyFormatter(this->key6()) << ")\n"; + cout << (s == "" ? s : s + "\n") << "CombinedImuFactor(" + << keyFormatter(this->key1()) << "," << keyFormatter(this->key2()) << "," + << keyFormatter(this->key3()) << "," << keyFormatter(this->key4()) << "," + << keyFormatter(this->key5()) << "," << keyFormatter(this->key6()) + << ")\n"; _PIM_.print(" preintegrated measurements:"); this->noiseModel_->print(" noise model: "); } diff --git a/gtsam/navigation/CombinedImuFactor.h b/gtsam/navigation/CombinedImuFactor.h index 55cc48eda..387353136 100644 --- a/gtsam/navigation/CombinedImuFactor.h +++ b/gtsam/navigation/CombinedImuFactor.h @@ -303,8 +303,8 @@ public: GTSAM_EXPORT friend std::ostream& operator<<(std::ostream& os, const CombinedImuFactor&); /// print - void print(const std::string& s, const KeyFormatter& keyFormatter = - DefaultKeyFormatter) const override; + void print(const std::string& s = "", const KeyFormatter& keyFormatter = + DefaultKeyFormatter) const override; /// equals bool equals(const NonlinearFactor& expected, double tol = 1e-9) const override; diff --git a/gtsam/navigation/ImuFactor.cpp b/gtsam/navigation/ImuFactor.cpp index ac7221cd9..cebddf05d 100644 --- a/gtsam/navigation/ImuFactor.cpp +++ b/gtsam/navigation/ImuFactor.cpp @@ -130,10 +130,10 @@ std::ostream& operator<<(std::ostream& os, const ImuFactor& f) { //------------------------------------------------------------------------------ void ImuFactor::print(const string& s, const KeyFormatter& keyFormatter) const { - cout << s << "ImuFactor(" << keyFormatter(this->key1()) << "," - << keyFormatter(this->key2()) << "," << keyFormatter(this->key3()) << "," - << keyFormatter(this->key4()) << "," << keyFormatter(this->key5()) - << ")\n"; + cout << (s == "" ? s : s + "\n") << "ImuFactor(" << keyFormatter(this->key1()) + << "," << keyFormatter(this->key2()) << "," << keyFormatter(this->key3()) + << "," << keyFormatter(this->key4()) << "," << keyFormatter(this->key5()) + << ")\n"; cout << *this << endl; } @@ -226,9 +226,9 @@ std::ostream& operator<<(std::ostream& os, const ImuFactor2& f) { //------------------------------------------------------------------------------ void ImuFactor2::print(const string& s, const KeyFormatter& keyFormatter) const { - cout << s << "ImuFactor2(" << keyFormatter(this->key1()) << "," - << keyFormatter(this->key2()) << "," << keyFormatter(this->key3()) - << ")\n"; + cout << (s == "" ? s : s + "\n") << "ImuFactor2(" + << keyFormatter(this->key1()) << "," << keyFormatter(this->key2()) << "," + << keyFormatter(this->key3()) << ")\n"; cout << *this << endl; } diff --git a/gtsam/navigation/ImuFactor.h b/gtsam/navigation/ImuFactor.h index 957478e97..51df3f24a 100644 --- a/gtsam/navigation/ImuFactor.h +++ b/gtsam/navigation/ImuFactor.h @@ -205,8 +205,8 @@ public: /// @name Testable /// @{ GTSAM_EXPORT friend std::ostream& operator<<(std::ostream& os, const ImuFactor&); - void print(const std::string& s, const KeyFormatter& keyFormatter = - DefaultKeyFormatter) const override; + void print(const std::string& s = "", const KeyFormatter& keyFormatter = + DefaultKeyFormatter) const override; bool equals(const NonlinearFactor& expected, double tol = 1e-9) const override; /// @} @@ -283,8 +283,8 @@ public: /// @name Testable /// @{ GTSAM_EXPORT friend std::ostream& operator<<(std::ostream& os, const ImuFactor2&); - void print(const std::string& s, const KeyFormatter& keyFormatter = - DefaultKeyFormatter) const override; + void print(const std::string& s = "", const KeyFormatter& keyFormatter = + DefaultKeyFormatter) const override; bool equals(const NonlinearFactor& expected, double tol = 1e-9) const override; /// @} diff --git a/gtsam/navigation/PreintegratedRotation.cpp b/gtsam/navigation/PreintegratedRotation.cpp index c5d48b734..f827c7c59 100644 --- a/gtsam/navigation/PreintegratedRotation.cpp +++ b/gtsam/navigation/PreintegratedRotation.cpp @@ -26,12 +26,11 @@ using namespace std; namespace gtsam { void PreintegratedRotationParams::print(const string& s) const { - cout << s << endl; + cout << (s == "" ? s : s + "\n") << endl; cout << "gyroscopeCovariance:\n[\n" << gyroscopeCovariance << "\n]" << endl; if (omegaCoriolis) cout << "omegaCoriolis = (" << omegaCoriolis->transpose() << ")" << endl; - if (body_P_sensor) - body_P_sensor->print("body_P_sensor"); + if (body_P_sensor) body_P_sensor->print("body_P_sensor"); } bool PreintegratedRotationParams::equals( diff --git a/gtsam/navigation/PreintegrationBase.cpp b/gtsam/navigation/PreintegrationBase.cpp index 45560f34d..111594663 100644 --- a/gtsam/navigation/PreintegrationBase.cpp +++ b/gtsam/navigation/PreintegrationBase.cpp @@ -46,7 +46,7 @@ ostream& operator<<(ostream& os, const PreintegrationBase& pim) { //------------------------------------------------------------------------------ void PreintegrationBase::print(const string& s) const { - cout << s << *this << endl; + cout << (s == "" ? s : s + "\n") << *this << endl; } //------------------------------------------------------------------------------ diff --git a/gtsam/navigation/PreintegrationBase.h b/gtsam/navigation/PreintegrationBase.h index 2f02a95b8..e118a6232 100644 --- a/gtsam/navigation/PreintegrationBase.h +++ b/gtsam/navigation/PreintegrationBase.h @@ -116,7 +116,7 @@ class GTSAM_EXPORT PreintegrationBase { /// @name Testable /// @{ GTSAM_EXPORT friend std::ostream& operator<<(std::ostream& os, const PreintegrationBase& pim); - virtual void print(const std::string& s) const; + virtual void print(const std::string& s="") const; /// @} /// @name Main functionality From e8f91c663f36f4edede0d044e5069a37d5801084 Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Thu, 13 Aug 2020 21:55:17 -0500 Subject: [PATCH 344/869] fix FrobeniusBetweenFactor declaration --- gtsam/slam/FrobeniusFactor.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/gtsam/slam/FrobeniusFactor.h b/gtsam/slam/FrobeniusFactor.h index f254b4b81..474cf6143 100644 --- a/gtsam/slam/FrobeniusFactor.h +++ b/gtsam/slam/FrobeniusFactor.h @@ -92,7 +92,7 @@ class FrobeniusFactor : public NoiseModelFactor2 { * and in fact only SO3 and SO4 really work, as we need SO::AdjointMap. */ template -GTSAM_EXPORT class FrobeniusBetweenFactor : public NoiseModelFactor2 { +class GTSAM_EXPORT FrobeniusBetweenFactor : public NoiseModelFactor2 { Rot R12_; ///< measured rotation between R1 and R2 Eigen::Matrix R2hat_H_R1_; ///< fixed derivative of R2hat wrpt R1 From 4194f97897819ace187c3d6955bd6a4aacfa77e4 Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Fri, 14 Aug 2020 14:58:07 -0500 Subject: [PATCH 345/869] comment out timing-out CI stage --- .travis.yml | 10 +++++----- 1 file changed, 5 insertions(+), 5 deletions(-) diff --git a/.travis.yml b/.travis.yml index 2069f48e0..986e86cc2 100644 --- a/.travis.yml +++ b/.travis.yml @@ -90,11 +90,11 @@ jobs: env: CC=clang-9 CXX=clang++-9 CMAKE_BUILD_TYPE=Debug GTSAM_BUILD_UNSTABLE=OFF GTSAM_ALLOW_DEPRECATED_SINCE_V41=ON script: bash .travis.sh -b # on Linux, with GTSAM_WITH_TBB on to make sure GTSAM still compiles/tests - - stage: special - os: linux - compiler: gcc - env: CMAKE_BUILD_TYPE=Debug GTSAM_BUILD_UNSTABLE=OFF GTSAM_WITH_TBB=ON - script: bash .travis.sh -t + # - stage: special + # os: linux + # compiler: gcc + # env: CMAKE_BUILD_TYPE=Debug GTSAM_BUILD_UNSTABLE=OFF GTSAM_WITH_TBB=ON + # script: bash .travis.sh -t # -------- STAGE 2: TESTS ----------- # on Mac, GCC - stage: test From a978c15d8e17eeac95b334300e9b4fdff6e4110d Mon Sep 17 00:00:00 2001 From: Frank Dellaert Date: Wed, 12 Aug 2020 19:41:56 -0400 Subject: [PATCH 346/869] Templated some methods internally --- gtsam/slam/dataset.cpp | 360 ++++++++++++++++++------------- gtsam/slam/dataset.h | 45 ++-- gtsam/slam/tests/testDataset.cpp | 34 ++- 3 files changed, 267 insertions(+), 172 deletions(-) diff --git a/gtsam/slam/dataset.cpp b/gtsam/slam/dataset.cpp index 3a2d04127..4f56d3afe 100644 --- a/gtsam/slam/dataset.cpp +++ b/gtsam/slam/dataset.cpp @@ -105,10 +105,10 @@ string createRewrittenFileName(const string& name) { } /* ************************************************************************* */ -GraphAndValues load2D(pair dataset, int maxID, +GraphAndValues load2D(pair dataset, Key maxNr, bool addNoise, bool smart, NoiseFormat noiseFormat, KernelFunctionType kernelFunctionType) { - return load2D(dataset.first, dataset.second, maxID, addNoise, smart, + return load2D(dataset.first, dataset.second, maxNr, addNoise, smart, noiseFormat, kernelFunctionType); } @@ -226,6 +226,54 @@ boost::optional parseVertexLandmark(istream& is, const string& } } +/* ************************************************************************* */ +// Parse types T into a Key-indexed map +template +static map parseIntoMap(const string &filename, Key maxNr = 0) { + ifstream is(filename.c_str()); + if (!is) + throw invalid_argument("parse: can not find file " + filename); + + map result; + string tag; + while (!is.eof()) { + boost::optional> indexed_t; + is >> indexed_t; + if (indexed_t) { + // optional filter + if (maxNr && indexed_t->first >= maxNr) + continue; + result.insert(*indexed_t); + } + is.ignore(LINESIZE, '\n'); + } + return result; +} + +/* ************************************************************************* */ +istream &operator>>(istream &is, boost::optional &indexed) { + string tag; + is >> tag; + indexed = parseVertexPose(is, tag); + return is; +} + +map parse2DPoses(const string &filename, Key maxNr) { + return parseIntoMap(filename, maxNr); +} + +/* ************************************************************************* */ +istream &operator>>(istream &is, boost::optional &indexed) { + string tag; + is >> tag; + indexed = parseVertexLandmark(is, tag); + return is; +} + +map parse2DLandmarks(const string &filename, Key maxNr) { + return parseIntoMap(filename, maxNr); +} + /* ************************************************************************* */ boost::optional parseEdge(istream& is, const string& tag) { if ((tag == "EDGE2") || (tag == "EDGE") || (tag == "EDGE_SE2") @@ -241,49 +289,27 @@ boost::optional parseEdge(istream& is, const string& tag) { } /* ************************************************************************* */ -GraphAndValues load2D(const string& filename, SharedNoiseModel model, Key maxID, - bool addNoise, bool smart, NoiseFormat noiseFormat, - KernelFunctionType kernelFunctionType) { +GraphAndValues load2D(const string &filename, SharedNoiseModel model, Key maxNr, + bool addNoise, bool smart, NoiseFormat noiseFormat, + KernelFunctionType kernelFunctionType) { + + Values::shared_ptr initial(new Values); + + const auto poses = parse2DPoses(filename, maxNr); + for (const auto& key_pose : poses) { + initial->insert(key_pose.first, key_pose.second); + } + const auto landmarks = parse2DLandmarks(filename, maxNr); + for (const auto& key_landmark : landmarks) { + initial->insert(key_landmark.first, key_landmark.second); + } ifstream is(filename.c_str()); if (!is) throw invalid_argument("load2D: can not find file " + filename); - Values::shared_ptr initial(new Values); NonlinearFactorGraph::shared_ptr graph(new NonlinearFactorGraph); - string tag; - - // load the poses and landmarks - while (!is.eof()) { - if (!(is >> tag)) - break; - - const auto indexed_pose = parseVertexPose(is, tag); - if (indexed_pose) { - Key id = indexed_pose->first; - - // optional filter - if (maxID && id >= maxID) - continue; - - initial->insert(id, indexed_pose->second); - } - const auto indexed_landmark = parseVertexLandmark(is, tag); - if (indexed_landmark) { - Key id = indexed_landmark->first; - - // optional filter - if (maxID && id >= maxID) - continue; - - initial->insert(id, indexed_landmark->second); - } - is.ignore(LINESIZE, '\n'); - } - is.clear(); /* clears the end-of-file and error flags */ - is.seekg(0, ios::beg); - // If asked, create a sampler with random number generator std::unique_ptr sampler; if (addNoise) { @@ -302,6 +328,7 @@ GraphAndValues load2D(const string& filename, SharedNoiseModel model, Key maxID, bool haveLandmark = false; const bool useModelInFile = !model; while (!is.eof()) { + string tag; if (!(is >> tag)) break; @@ -315,7 +342,7 @@ GraphAndValues load2D(const string& filename, SharedNoiseModel model, Key maxID, kernelFunctionType); // optional filter - if (maxID && (id1 >= maxID || id2 >= maxID)) + if (maxNr && (id1 >= maxNr || id2 >= maxNr)) continue; if (useModelInFile) @@ -375,7 +402,7 @@ GraphAndValues load2D(const string& filename, SharedNoiseModel model, Key maxID, if (tag == "LANDMARK" || tag == "BR") { // optional filter - if (maxID && id1 >= maxID) + if (maxNr && id1 >= maxNr) continue; // Create noise model @@ -404,8 +431,8 @@ GraphAndValues load2D(const string& filename, SharedNoiseModel model, Key maxID, /* ************************************************************************* */ GraphAndValues load2D_robust(const string& filename, - noiseModel::Base::shared_ptr& model, int maxID) { - return load2D(filename, model, maxID); + noiseModel::Base::shared_ptr& model, Key maxNr) { + return load2D(filename, model, maxNr); } /* ************************************************************************* */ @@ -448,10 +475,10 @@ GraphAndValues readG2o(const string& g2oFile, const bool is3D, return load3D(g2oFile); } else { // just call load2D - int maxID = 0; + Key maxNr = 0; bool addNoise = false; bool smart = true; - return load2D(g2oFile, SharedNoiseModel(), maxID, addNoise, smart, + return load2D(g2oFile, SharedNoiseModel(), maxNr, addNoise, smart, NoiseFormatG2O, kernelFunctionType); } } @@ -516,8 +543,8 @@ void writeG2o(const NonlinearFactorGraph& graph, const Values& estimate, Pose2 pose = factor->measured(); //.inverse(); stream << "EDGE_SE2 " << factor->key1() << " " << factor->key2() << " " << pose.x() << " " << pose.y() << " " << pose.theta(); - for (int i = 0; i < 3; i++){ - for (int j = i; j < 3; j++){ + for (size_t i = 0; i < 3; i++){ + for (size_t j = i; j < 3; j++){ stream << " " << Info(i, j); } } @@ -545,13 +572,13 @@ void writeG2o(const NonlinearFactorGraph& graph, const Values& estimate, << " " << q.y() << " " << q.z() << " " << q.w(); Matrix InfoG2o = I_6x6; - InfoG2o.block(0,0,3,3) = Info.block(3,3,3,3); // cov translation - InfoG2o.block(3,3,3,3) = Info.block(0,0,3,3); // cov rotation - InfoG2o.block(0,3,3,3) = Info.block(0,3,3,3); // off diagonal - InfoG2o.block(3,0,3,3) = Info.block(3,0,3,3); // off diagonal + InfoG2o.block<3, 3>(0, 0) = Info.block<3, 3>(3, 3); // cov translation + InfoG2o.block<3, 3>(3, 3) = Info.block<3, 3>(0, 0); // cov rotation + InfoG2o.block<3, 3>(0, 3) = Info.block<3, 3>(0, 3); // off diagonal + InfoG2o.block<3, 3>(3, 0) = Info.block<3, 3>(3, 0); // off diagonal - for (int i = 0; i < 6; i++){ - for (int j = i; j < 6; j++){ + for (size_t i = 0; i < 6; i++){ + for (size_t j = i; j < 6; j++){ stream << " " << InfoG2o(i, j); } } @@ -562,126 +589,157 @@ void writeG2o(const NonlinearFactorGraph& graph, const Values& estimate, } /* ************************************************************************* */ -static Rot3 NormalizedRot3(double w, double x, double y, double z) { +// parse quaternion in x,y,z,w order, and normalize to unit length +istream &operator>>(istream &is, Quaternion &q) { + double x, y, z, w; + is >> x >> y >> z >> w; const double norm = sqrt(w * w + x * x + y * y + z * z), f = 1.0 / norm; - return Rot3::Quaternion(f * w, f * x, f * y, f * z); + q = Quaternion(f * w, f * x, f * y, f * z); + return is; } /* ************************************************************************* */ -std::map parse3DPoses(const string& filename) { +// parse Rot3 from roll, pitch, yaw +istream &operator>>(istream &is, Rot3 &R) { + double yaw, pitch, roll; + is >> roll >> pitch >> yaw; // notice order ! + R = Rot3::Ypr(yaw, pitch, roll); + return is; +} + +/* ************************************************************************* */ +istream &operator>>(istream &is, boost::optional> &indexed) { + string tag; + is >> tag; + if (tag == "VERTEX3") { + Key id; + double x, y, z; + Rot3 R; + is >> id >> x >> y >> z >> R; + indexed.reset({id, Pose3(R, {x, y, z})}); + } else if (tag == "VERTEX_SE3:QUAT") { + Key id; + double x, y, z; + Quaternion q; + is >> id >> x >> y >> z >> q; + indexed.reset({id, Pose3(q, {x, y, z})}); + } + return is; +} + +map parse3DPoses(const string &filename, Key maxNr) { + return parseIntoMap(filename, maxNr); +} + +/* ************************************************************************* */ +istream &operator>>(istream &is, boost::optional> &indexed) { + string tag; + is >> tag; + if (tag == "VERTEX_TRACKXYZ") { + Key id; + double x, y, z; + is >> id >> x >> y >> z; + indexed.reset({id, Point3(x, y, z)}); + } + return is; +} + +map parse3DLandmarks(const string &filename, Key maxNr) { + return parseIntoMap(filename, maxNr); +} + +/* ************************************************************************* */ +// Parse BetweenFactor shared pointers into a vector +template +static vector>> +parseIntoVector(const string &filename, Key maxNr = 0) { ifstream is(filename.c_str()); if (!is) - throw invalid_argument("parse3DPoses: can not find file " + filename); + throw invalid_argument("parse: can not find file " + filename); - std::map poses; + vector>> result; + string tag; while (!is.eof()) { - char buf[LINESIZE]; - is.getline(buf, LINESIZE); - istringstream ls(buf); - string tag; - ls >> tag; - - if (tag == "VERTEX3") { - Key id; - double x, y, z, roll, pitch, yaw; - ls >> id >> x >> y >> z >> roll >> pitch >> yaw; - poses.emplace(id, Pose3(Rot3::Ypr(yaw, pitch, roll), {x, y, z})); - } - if (tag == "VERTEX_SE3:QUAT") { - Key id; - double x, y, z, qx, qy, qz, qw; - ls >> id >> x >> y >> z >> qx >> qy >> qz >> qw; - poses.emplace(id, Pose3(NormalizedRot3(qw, qx, qy, qz), {x, y, z})); + boost::shared_ptr> shared; + is >> shared; + if (shared) { + // optional filter + if (maxNr && (shared->key1() >= maxNr || shared->key1() >= maxNr)) + continue; + result.push_back(shared); } + is.ignore(LINESIZE, '\n'); } - return poses; + return result; } /* ************************************************************************* */ -std::map parse3DLandmarks(const string& filename) { - ifstream is(filename.c_str()); - if (!is) - throw invalid_argument("parse3DLandmarks: can not find file " + filename); - - std::map landmarks; - while (!is.eof()) { - char buf[LINESIZE]; - is.getline(buf, LINESIZE); - istringstream ls(buf); - string tag; - ls >> tag; - - if (tag == "VERTEX_TRACKXYZ") { - Key id; - double x, y, z; - ls >> id >> x >> y >> z; - landmarks.emplace(id, Point3(x, y, z)); - } +// Parse a symmetric covariance matrix (onlyupper-triangular part is stored) +istream &operator>>(istream &is, Matrix6 &m) { + for (size_t i = 0; i < 6; i++) + for (size_t j = i; j < 6; j++){ + is >> m(i, j); + m(j,i) = m(i,j); } - return landmarks; + return is; } /* ************************************************************************* */ -BetweenFactorPose3s parse3DFactors( - const string& filename, - const noiseModel::Diagonal::shared_ptr& corruptingNoise) { - ifstream is(filename.c_str()); - if (!is) throw invalid_argument("parse3DFactors: can not find file " + filename); +istream &operator>>(istream &is, + boost::shared_ptr> &shared) { + string tag; + is >> tag; + + Matrix6 m; + if (tag == "EDGE3") { + Key id1, id2; + double x, y, z; + Rot3 R; + is >> id1 >> id2 >> x >> y >> z >> R; + Pose3 pose(R, {x, y, z}); + + is >> m; + SharedNoiseModel model = noiseModel::Gaussian::Information(m); + shared.reset(new BetweenFactor(id1, id2, pose, model)); + } + if (tag == "EDGE_SE3:QUAT") { + Key id1, id2; + double x, y, z; + Quaternion q; + is >> id1 >> id2 >> x >> y >> z >> q; + Pose3 pose(q, {x, y, z}); + + // EDGE_SE3:QUAT stores covariance in t,R order, unlike GTSAM: + is >> m; + Matrix6 mgtsam; + mgtsam.block<3, 3>(0, 0) = m.block<3, 3>(3, 3); // cov rotation + mgtsam.block<3, 3>(3, 3) = m.block<3, 3>(0, 0); // cov translation + mgtsam.block<3, 3>(0, 3) = m.block<3, 3>(0, 3); // off diagonal + mgtsam.block<3, 3>(3, 0) = m.block<3, 3>(3, 0); // off diagonal + SharedNoiseModel model = noiseModel::Gaussian::Information(mgtsam); + + shared.reset(new BetweenFactor(id1, id2, pose, model)); + } + return is; +} + +/* ************************************************************************* */ +BetweenFactorPose3s +parse3DFactors(const string &filename, + const noiseModel::Diagonal::shared_ptr &corruptingNoise, + Key maxNr) { + auto factors = parseIntoVector(filename, maxNr); - boost::optional sampler; if (corruptingNoise) { - sampler = Sampler(corruptingNoise); - } - - std::vector::shared_ptr> factors; - while (!is.eof()) { - char buf[LINESIZE]; - is.getline(buf, LINESIZE); - istringstream ls(buf); - string tag; - ls >> tag; - - if (tag == "EDGE3") { - Key id1, id2; - double x, y, z, roll, pitch, yaw; - ls >> id1 >> id2 >> x >> y >> z >> roll >> pitch >> yaw; - Matrix m(6, 6); - for (size_t i = 0; i < 6; i++) - for (size_t j = i; j < 6; j++) ls >> m(i, j); - SharedNoiseModel model = noiseModel::Gaussian::Information(m); - factors.emplace_back(new BetweenFactor( - id1, id2, Pose3(Rot3::Ypr(yaw, pitch, roll), {x, y, z}), model)); - } - if (tag == "EDGE_SE3:QUAT") { - Key id1, id2; - double x, y, z, qx, qy, qz, qw; - ls >> id1 >> id2 >> x >> y >> z >> qx >> qy >> qz >> qw; - Matrix m(6, 6); - for (size_t i = 0; i < 6; i++) { - for (size_t j = i; j < 6; j++) { - double mij; - ls >> mij; - m(i, j) = mij; - m(j, i) = mij; - } - } - Matrix mgtsam(6, 6); - - mgtsam.block<3, 3>(0, 0) = m.block<3, 3>(3, 3); // cov rotation - mgtsam.block<3, 3>(3, 3) = m.block<3, 3>(0, 0); // cov translation - mgtsam.block<3, 3>(0, 3) = m.block<3, 3>(0, 3); // off diagonal - mgtsam.block<3, 3>(3, 0) = m.block<3, 3>(3, 0); // off diagonal - - SharedNoiseModel model = noiseModel::Gaussian::Information(mgtsam); - auto R12 = NormalizedRot3(qw, qx, qy, qz); - if (sampler) { - R12 = R12.retract(sampler->sample()); - } - - factors.emplace_back(new BetweenFactor( - id1, id2, Pose3(R12, {x, y, z}), model)); + Sampler sampler(corruptingNoise); + for (auto factor : factors) { + auto pose = factor->measured(); + factor.reset(new BetweenFactor(factor->key1(), factor->key2(), + pose.retract(sampler.sample()), + factor->noiseModel())); } } + return factors; } diff --git a/gtsam/slam/dataset.h b/gtsam/slam/dataset.h index 30fa913ba..caef96cf4 100644 --- a/gtsam/slam/dataset.h +++ b/gtsam/slam/dataset.h @@ -23,10 +23,8 @@ #include #include #include -#include -#include +#include #include -#include #include #include #include @@ -114,18 +112,35 @@ GTSAM_EXPORT boost::optional parseVertexLandmark(std::istream& GTSAM_EXPORT boost::optional parseEdge(std::istream& is, const std::string& tag); +using BetweenFactorPose2s = + std::vector::shared_ptr>; + +/// Parse edges in 2D g2o graph file into a set of BetweenFactors. +GTSAM_EXPORT BetweenFactorPose2s parse2DFactors( + const std::string &filename, + const noiseModel::Diagonal::shared_ptr &corruptingNoise = nullptr); + +/// Parse vertices in 2D g2o graph file into a map of Pose2s. +GTSAM_EXPORT std::map parse2DPoses(const std::string &filename, + Key maxNr = 0); + +/// Parse landmarks in 2D g2o graph file into a map of Point2s. +GTSAM_EXPORT std::map parse2DLandmarks(const string &filename, + Key maxNr = 0); + /// Return type for load functions -typedef std::pair GraphAndValues; +using GraphAndValues = + std::pair; /** * Load TORO 2D Graph * @param dataset/model pair as constructed by [dataset] - * @param maxID if non-zero cut out vertices >= maxID + * @param maxNr if non-zero cut out vertices >= maxNr * @param addNoise add noise to the edges * @param smart try to reduce complexity of covariance to cheapest model */ GTSAM_EXPORT GraphAndValues load2D( - std::pair dataset, int maxID = 0, + std::pair dataset, Key maxNr = 0, bool addNoise = false, bool smart = true, // NoiseFormat noiseFormat = NoiseFormatAUTO, @@ -135,7 +150,7 @@ GTSAM_EXPORT GraphAndValues load2D( * Load TORO/G2O style graph files * @param filename * @param model optional noise model to use instead of one specified by file - * @param maxID if non-zero cut out vertices >= maxID + * @param maxNr if non-zero cut out vertices >= maxNr * @param addNoise add noise to the edges * @param smart try to reduce complexity of covariance to cheapest model * @param noiseFormat how noise parameters are stored @@ -143,13 +158,13 @@ GTSAM_EXPORT GraphAndValues load2D( * @return graph and initial values */ GTSAM_EXPORT GraphAndValues load2D(const std::string& filename, - SharedNoiseModel model = SharedNoiseModel(), Key maxID = 0, bool addNoise = + SharedNoiseModel model = SharedNoiseModel(), Key maxNr = 0, bool addNoise = false, bool smart = true, NoiseFormat noiseFormat = NoiseFormatAUTO, // KernelFunctionType kernelFunctionType = KernelFunctionTypeNONE); /// @deprecated load2D now allows for arbitrary models and wrapping a robust kernel GTSAM_EXPORT GraphAndValues load2D_robust(const std::string& filename, - noiseModel::Base::shared_ptr& model, int maxID = 0); + noiseModel::Base::shared_ptr& model, Key maxNr = 0); /** save 2d graph */ GTSAM_EXPORT void save2D(const NonlinearFactorGraph& graph, @@ -179,14 +194,18 @@ GTSAM_EXPORT void writeG2o(const NonlinearFactorGraph& graph, /// Parse edges in 3D TORO graph file into a set of BetweenFactors. using BetweenFactorPose3s = std::vector::shared_ptr>; -GTSAM_EXPORT BetweenFactorPose3s parse3DFactors(const std::string& filename, - const noiseModel::Diagonal::shared_ptr& corruptingNoise=nullptr); +GTSAM_EXPORT BetweenFactorPose3s parse3DFactors( + const std::string &filename, + const noiseModel::Diagonal::shared_ptr &corruptingNoise = nullptr, + Key maxNr = 0); /// Parse vertices in 3D TORO/g2o graph file into a map of Pose3s. -GTSAM_EXPORT std::map parse3DPoses(const std::string& filename); +GTSAM_EXPORT std::map parse3DPoses(const std::string &filename, + Key maxNr = 0); /// Parse landmarks in 3D g2o graph file into a map of Point3s. -GTSAM_EXPORT std::map parse3DLandmarks(const string& filename); +GTSAM_EXPORT std::map parse3DLandmarks(const std::string &filename, + Key maxNr = 0); /// Load TORO 3D Graph GTSAM_EXPORT GraphAndValues load3D(const std::string& filename); diff --git a/gtsam/slam/tests/testDataset.cpp b/gtsam/slam/tests/testDataset.cpp index b6b1776d2..6ee44cfd6 100644 --- a/gtsam/slam/tests/testDataset.cpp +++ b/gtsam/slam/tests/testDataset.cpp @@ -89,20 +89,38 @@ TEST( dataSet, parseEdge) } /* ************************************************************************* */ -TEST( dataSet, load2D) -{ +TEST(dataSet, load2D) { ///< The structure where we will save the SfM data const string filename = findExampleDataFile("w100.graph"); NonlinearFactorGraph::shared_ptr graph; Values::shared_ptr initial; boost::tie(graph, initial) = load2D(filename); - EXPECT_LONGS_EQUAL(300,graph->size()); - EXPECT_LONGS_EQUAL(100,initial->size()); - noiseModel::Unit::shared_ptr model = noiseModel::Unit::Create(3); - BetweenFactor expected(1, 0, Pose2(-0.99879,0.0417574,-0.00818381), model); - BetweenFactor::shared_ptr actual = boost::dynamic_pointer_cast< - BetweenFactor >(graph->at(0)); + EXPECT_LONGS_EQUAL(300, graph->size()); + EXPECT_LONGS_EQUAL(100, initial->size()); + auto model = noiseModel::Unit::Create(3); + BetweenFactor expected(1, 0, Pose2(-0.99879, 0.0417574, -0.00818381), + model); + BetweenFactor::shared_ptr actual = + boost::dynamic_pointer_cast>(graph->at(0)); EXPECT(assert_equal(expected, *actual)); + + // // Check factor parsing + // const auto actualFactors = parse2DFactors(filename); + // for (size_t i : {0, 1, 2, 3, 4, 5}) { + // EXPECT(assert_equal( + // *boost::dynamic_pointer_cast>(graph->at(i)), + // *actualFactors[i], 1e-5)); + // } + + // Check pose parsing + const auto actualPoses = parse2DPoses(filename); + for (size_t j : {0, 1, 2, 3, 4}) { + EXPECT(assert_equal(initial->at(j), actualPoses.at(j), 1e-5)); + } + + // Check landmark parsing + const auto actualLandmarks = parse2DLandmarks(filename); + EXPECT_LONGS_EQUAL(0, actualLandmarks.size()); } /* ************************************************************************* */ From d67afa8a3d141cc1b913c6fb88ddac74b1c55c1a Mon Sep 17 00:00:00 2001 From: Frank Dellaert Date: Wed, 12 Aug 2020 23:24:52 -0400 Subject: [PATCH 347/869] Very generic parseToVector --- gtsam/slam/dataset.cpp | 576 +++++++++++++++++++------------ gtsam/slam/dataset.h | 24 +- gtsam/slam/tests/testDataset.cpp | 14 +- 3 files changed, 370 insertions(+), 244 deletions(-) diff --git a/gtsam/slam/dataset.cpp b/gtsam/slam/dataset.cpp index 4f56d3afe..29162dafb 100644 --- a/gtsam/slam/dataset.cpp +++ b/gtsam/slam/dataset.cpp @@ -21,21 +21,25 @@ #include #include #include + #include #include #include + +#include +#include + +#include + #include #include -#include -#include -#include -#include + #include #include #include -#include #include #include +#include #include #include @@ -56,7 +60,7 @@ using namespace gtsam::symbol_shorthand; namespace gtsam { /* ************************************************************************* */ -string findExampleDataFile(const string& name) { +string findExampleDataFile(const string &name) { // Search source tree and installed location vector rootsToSearch; @@ -73,88 +77,88 @@ string findExampleDataFile(const string& name) { namesToSearch.push_back(name + ".xml"); // Find first name that exists - for(const fs::path root: rootsToSearch) { - for(const fs::path name: namesToSearch) { + for (const fs::path root : rootsToSearch) { + for (const fs::path name : namesToSearch) { if (fs::is_regular_file(root / name)) return (root / name).string(); } } // If we did not return already, then we did not find the file - throw invalid_argument( - "gtsam::findExampleDataFile could not find a matching file in\n" - GTSAM_SOURCE_TREE_DATASET_DIR " or\n" - GTSAM_INSTALLED_DATASET_DIR " named\n" + name + ", " + name - + ".graph, or " + name + ".txt"); + throw invalid_argument("gtsam::findExampleDataFile could not find a matching " + "file in\n" GTSAM_SOURCE_TREE_DATASET_DIR + " or\n" GTSAM_INSTALLED_DATASET_DIR " named\n" + + name + ", " + name + ".graph, or " + name + ".txt"); } /* ************************************************************************* */ -string createRewrittenFileName(const string& name) { +string createRewrittenFileName(const string &name) { // Search source tree and installed location if (!exists(fs::path(name))) { throw invalid_argument( - "gtsam::createRewrittenFileName could not find a matching file in\n" - + name); + "gtsam::createRewrittenFileName could not find a matching file in\n" + + name); } fs::path p(name); - fs::path newpath = fs::path(p.parent_path().string()) - / fs::path(p.stem().string() + "-rewritten.txt"); + fs::path newpath = fs::path(p.parent_path().string()) / + fs::path(p.stem().string() + "-rewritten.txt"); return newpath.string(); } /* ************************************************************************* */ GraphAndValues load2D(pair dataset, Key maxNr, - bool addNoise, bool smart, NoiseFormat noiseFormat, - KernelFunctionType kernelFunctionType) { + bool addNoise, bool smart, NoiseFormat noiseFormat, + KernelFunctionType kernelFunctionType) { return load2D(dataset.first, dataset.second, maxNr, addNoise, smart, - noiseFormat, kernelFunctionType); + noiseFormat, kernelFunctionType); } /* ************************************************************************* */ -// Read noise parameters and interpret them according to flags -static SharedNoiseModel readNoiseModel(ifstream& is, bool smart, - NoiseFormat noiseFormat, KernelFunctionType kernelFunctionType) { - double v1, v2, v3, v4, v5, v6; - is >> v1 >> v2 >> v3 >> v4 >> v5 >> v6; - +// Interpret noise parameters according to flags +static SharedNoiseModel +createNoiseModel(const Vector6 v, bool smart, NoiseFormat noiseFormat, + KernelFunctionType kernelFunctionType) { if (noiseFormat == NoiseFormatAUTO) { // Try to guess covariance matrix layout - if (v1 != 0.0 && v2 == 0.0 && v3 != 0.0 && v4 != 0.0 && v5 == 0.0 - && v6 == 0.0) { - // NoiseFormatGRAPH + if (v(0) != 0.0 && v(1) == 0.0 && v(2) != 0.0 && // + v(3) != 0.0 && v(4) == 0.0 && v(5) == 0.0) { noiseFormat = NoiseFormatGRAPH; - } else if (v1 != 0.0 && v2 == 0.0 && v3 == 0.0 && v4 != 0.0 && v5 == 0.0 - && v6 != 0.0) { - // NoiseFormatCOV + } else if (v(0) != 0.0 && v(1) == 0.0 && v(2) == 0.0 && // + v(3) != 0.0 && v(4) == 0.0 && v(5) != 0.0) { noiseFormat = NoiseFormatCOV; } else { throw std::invalid_argument( - "load2D: unrecognized covariance matrix format in dataset file. Please specify the noise format."); + "load2D: unrecognized covariance matrix format in dataset file. " + "Please specify the noise format."); } } // Read matrix and check that diagonal entries are non-zero - Matrix M(3, 3); + Matrix3 M; switch (noiseFormat) { case NoiseFormatG2O: case NoiseFormatCOV: - // i.e., [ v1 v2 v3; v2' v4 v5; v3' v5' v6 ] - if (v1 == 0.0 || v4 == 0.0 || v6 == 0.0) + // i.e., [v(0) v(1) v(2); + // v(1)' v(3) v(4); + // v(2)' v(4)' v(5) ] + if (v(0) == 0.0 || v(3) == 0.0 || v(5) == 0.0) throw runtime_error( "load2D::readNoiseModel looks like this is not G2O matrix order"); - M << v1, v2, v3, v2, v4, v5, v3, v5, v6; + M << v(0), v(1), v(2), v(1), v(3), v(4), v(2), v(4), v(5); break; case NoiseFormatTORO: case NoiseFormatGRAPH: // http://www.openslam.org/toro.html // inf_ff inf_fs inf_ss inf_rr inf_fr inf_sr - // i.e., [ v1 v2 v5; v2' v3 v6; v5' v6' v4 ] - if (v1 == 0.0 || v3 == 0.0 || v4 == 0.0) + // i.e., [v(0) v(1) v(4); + // v(1)' v(2) v(5); + // v(4)' v(5)' v(3) ] + if (v(0) == 0.0 || v(2) == 0.0 || v(3) == 0.0) throw invalid_argument( "load2D::readNoiseModel looks like this is not TORO matrix order"); - M << v1, v2, v5, v2, v3, v6, v5, v6, v4; + M << v(0), v(1), v(4), v(1), v(2), v(5), v(4), v(5), v(3); break; default: throw runtime_error("load2D: invalid noise format"); @@ -195,15 +199,18 @@ static SharedNoiseModel readNoiseModel(ifstream& is, bool smart, } } -#ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V41 /* ************************************************************************* */ -boost::optional parseVertex(istream& is, const string& tag) { - return parseVertexPose(is, tag); +// Read noise parameters and interpret them according to flags +static SharedNoiseModel readNoiseModel(istream &is, bool smart, + NoiseFormat noiseFormat, + KernelFunctionType kernelFunctionType) { + Vector6 v; + is >> v(0) >> v(1) >> v(2) >> v(3) >> v(4) >> v(5); + return createNoiseModel(v, smart, noiseFormat, kernelFunctionType); } -#endif /* ************************************************************************* */ -boost::optional parseVertexPose(istream& is, const string& tag) { +boost::optional parseVertexPose(istream &is, const string &tag) { if ((tag == "VERTEX2") || (tag == "VERTEX_SE2") || (tag == "VERTEX")) { Key id; double x, y, yaw; @@ -215,7 +222,8 @@ boost::optional parseVertexPose(istream& is, const string& tag) { } /* ************************************************************************* */ -boost::optional parseVertexLandmark(istream& is, const string& tag) { +boost::optional parseVertexLandmark(istream &is, + const string &tag) { if (tag == "VERTEX_XY") { Key id; double x, y; @@ -275,9 +283,37 @@ map parse2DLandmarks(const string &filename, Key maxNr) { } /* ************************************************************************* */ -boost::optional parseEdge(istream& is, const string& tag) { - if ((tag == "EDGE2") || (tag == "EDGE") || (tag == "EDGE_SE2") - || (tag == "ODOMETRY")) { +// Parse a file by first parsing the `Parsed` type and then processing it with +// the supplied `process` function. Result is put in a vector evaluates to true. +// Requires: a stream >> operator for boost::optional +template +static vector +parseToVector(const string &filename, + const std::function process) { + ifstream is(filename.c_str()); + if (!is) + throw invalid_argument("parse: can not find file " + filename); + + vector result; + string tag; + while (!is.eof()) { + boost::optional parsed; + is >> parsed; + if (parsed) { + Output factor = process(*parsed); // can return nullptr + if (factor) { + result.push_back(factor); + } + } + is.ignore(LINESIZE, '\n'); + } + return result; +} + +/* ************************************************************************* */ +boost::optional parseEdge(istream &is, const string &tag) { + if ((tag == "EDGE2") || (tag == "EDGE") || (tag == "EDGE_SE2") || + (tag == "ODOMETRY")) { Key id1, id2; double x, y, yaw; @@ -288,6 +324,86 @@ boost::optional parseEdge(istream& is, const string& tag) { } } +/* ************************************************************************* */ +struct Measurement2 { + Key id1, id2; + Pose2 pose; + Vector6 v; // 6 noise model parameters for edge +}; + +istream &operator>>(istream &is, boost::optional &edge) { + string tag; + is >> tag; + if ((tag == "EDGE2") || (tag == "EDGE") || (tag == "EDGE_SE2") || + (tag == "ODOMETRY")) { + Key id1, id2; + double x, y, yaw; + Vector6 v; + is >> id1 >> id2 >> x >> y >> yaw >> // + v(0) >> v(1) >> v(2) >> v(3) >> v(4) >> v(5); + edge.reset({id1, id2, Pose2(x, y, yaw), v}); + } + return is; +} + +/* ************************************************************************* */ +// Create a sampler +boost::shared_ptr createSampler(const SharedNoiseModel &model) { + auto noise = boost::dynamic_pointer_cast(model); + if (!noise) + throw invalid_argument("gtsam::load: invalid noise model for adding noise" + "(current version assumes diagonal noise model)!"); + return boost::shared_ptr(new Sampler(noise)); +} + +/* ************************************************************************* */ +// Small functor to process the edge into a BetweenFactor::shared_ptr +struct ProcessPose2 { + // The arguments + Key maxNr = 0; + SharedNoiseModel model; + boost::shared_ptr sampler; + + // Arguments for parsing noise model + bool smart = true; + NoiseFormat noiseFormat = NoiseFormatAUTO; + KernelFunctionType kernelFunctionType = KernelFunctionTypeNONE; + + // The actual function + BetweenFactor::shared_ptr operator()(const Measurement2 &edge) { + // optional filter + if (maxNr && (edge.id1 >= maxNr || edge.id2 >= maxNr)) + return nullptr; + + // Get pose and optionally add noise + Pose2 T12 = edge.pose; + if (sampler) + T12 = T12.retract(sampler->sample()); + + // Create factor + // If model is nullptr we use the model from the file + return boost::make_shared>( + edge.id1, edge.id2, T12, + model + ? model + : createNoiseModel(edge.v, smart, noiseFormat, kernelFunctionType)); + } +}; + +/* ************************************************************************* */ +BetweenFactorPose2s +parse2DFactors(const string &filename, + const noiseModel::Diagonal::shared_ptr &corruptingNoise, + Key maxNr) { + ProcessPose2 process; + process.maxNr = maxNr; + if (corruptingNoise) { + process.sampler = createSampler(corruptingNoise); + } + return parseToVector::shared_ptr>(filename, + process); +} + /* ************************************************************************* */ GraphAndValues load2D(const string &filename, SharedNoiseModel model, Key maxNr, bool addNoise, bool smart, NoiseFormat noiseFormat, @@ -296,11 +412,11 @@ GraphAndValues load2D(const string &filename, SharedNoiseModel model, Key maxNr, Values::shared_ptr initial(new Values); const auto poses = parse2DPoses(filename, maxNr); - for (const auto& key_pose : poses) { + for (const auto &key_pose : poses) { initial->insert(key_pose.first, key_pose.second); } const auto landmarks = parse2DLandmarks(filename, maxNr); - for (const auto& key_landmark : landmarks) { + for (const auto &key_landmark : landmarks) { initial->insert(key_landmark.first, key_landmark.second); } @@ -311,7 +427,7 @@ GraphAndValues load2D(const string &filename, SharedNoiseModel model, Key maxNr, NonlinearFactorGraph::shared_ptr graph(new NonlinearFactorGraph); // If asked, create a sampler with random number generator - std::unique_ptr sampler; + boost::shared_ptr sampler; if (addNoise) { noiseModel::Diagonal::shared_ptr noise; if (model) @@ -319,7 +435,7 @@ GraphAndValues load2D(const string &filename, SharedNoiseModel model, Key maxNr, if (!noise) throw invalid_argument( "gtsam::load2D: invalid noise model for adding noise" - "(current version assumes diagonal noise model)!"); + "(current version assumes diagonal noise model)!"); sampler.reset(new Sampler(noise)); } @@ -335,11 +451,11 @@ GraphAndValues load2D(const string &filename, SharedNoiseModel model, Key maxNr, auto between_pose = parseEdge(is, tag); if (between_pose) { std::tie(id1, id2) = between_pose->first; - Pose2& l1Xl2 = between_pose->second; + Pose2 l1Xl2 = between_pose->second; // read noise model - SharedNoiseModel modelInFile = readNoiseModel(is, smart, noiseFormat, - kernelFunctionType); + SharedNoiseModel modelInFile = + readNoiseModel(is, smart, noiseFormat, kernelFunctionType); // optional filter if (maxNr && (id1 >= maxNr || id2 >= maxNr)) @@ -369,7 +485,8 @@ GraphAndValues load2D(const string &filename, SharedNoiseModel model, Key maxNr, is >> id1 >> id2 >> bearing >> range >> bearing_std >> range_std; } - // A landmark measurement, TODO Frank says: don't know why is converted to bearing-range + // A landmark measurement, TODO Frank says: don't know why is converted to + // bearing-range if (tag == "LANDMARK") { double lmx, lmy; double v1, v2, v3; @@ -380,8 +497,9 @@ GraphAndValues load2D(const string &filename, SharedNoiseModel model, Key maxNr, bearing = atan2(lmy, lmx); range = sqrt(lmx * lmx + lmy * lmy); - // In our experience, the x-y covariance on landmark sightings is not very good, so assume - // it describes the uncertainty at a range of 10m, and convert that to bearing/range uncertainty. + // In our experience, the x-y covariance on landmark sightings is not + // very good, so assume it describes the uncertainty at a range of 10m, + // and convert that to bearing/range uncertainty. if (std::abs(v1 - v3) < 1e-4) { bearing_std = sqrt(v1 / 10.0); range_std = sqrt(v1); @@ -389,10 +507,11 @@ GraphAndValues load2D(const string &filename, SharedNoiseModel model, Key maxNr, bearing_std = 1; range_std = 1; if (!haveLandmark) { - cout - << "Warning: load2D is a very simple dataset loader and is ignoring the\n" - "non-uniform covariance on LANDMARK measurements in this file." - << endl; + cout << "Warning: load2D is a very simple dataset loader and is " + "ignoring the\n" + "non-uniform covariance on LANDMARK measurements in this " + "file." + << endl; haveLandmark = true; } } @@ -407,11 +526,12 @@ GraphAndValues load2D(const string &filename, SharedNoiseModel model, Key maxNr, // Create noise model noiseModel::Diagonal::shared_ptr measurementNoise = - noiseModel::Diagonal::Sigmas((Vector(2) << bearing_std, range_std).finished()); + noiseModel::Diagonal::Sigmas( + (Vector(2) << bearing_std, range_std).finished()); // Add to graph *graph += BearingRangeFactor(id1, L(id2), bearing, range, - measurementNoise); + measurementNoise); // Insert poses or points if they do not exist yet if (!initial->exists(id1)) @@ -430,46 +550,46 @@ GraphAndValues load2D(const string &filename, SharedNoiseModel model, Key maxNr, } /* ************************************************************************* */ -GraphAndValues load2D_robust(const string& filename, - noiseModel::Base::shared_ptr& model, Key maxNr) { +GraphAndValues load2D_robust(const string &filename, + noiseModel::Base::shared_ptr &model, Key maxNr) { return load2D(filename, model, maxNr); } /* ************************************************************************* */ -void save2D(const NonlinearFactorGraph& graph, const Values& config, - const noiseModel::Diagonal::shared_ptr model, const string& filename) { +void save2D(const NonlinearFactorGraph &graph, const Values &config, + const noiseModel::Diagonal::shared_ptr model, + const string &filename) { fstream stream(filename.c_str(), fstream::out); // save poses - - for(const Values::ConstKeyValuePair& key_value: config) { - const Pose2& pose = key_value.value.cast(); + for (const Values::ConstKeyValuePair &key_value : config) { + const Pose2 &pose = key_value.value.cast(); stream << "VERTEX2 " << key_value.key << " " << pose.x() << " " << pose.y() - << " " << pose.theta() << endl; + << " " << pose.theta() << endl; } // save edges - Matrix R = model->R(); - Matrix RR = trans(R) * R; //prod(trans(R),R); - for(boost::shared_ptr factor_: graph) { - boost::shared_ptr > factor = - boost::dynamic_pointer_cast >(factor_); + // TODO(frank): why don't we use model in factor? + Matrix3 R = model->R(); + Matrix3 RR = R.transpose() * R; + for (auto f : graph) { + auto factor = boost::dynamic_pointer_cast>(f); if (!factor) continue; - Pose2 pose = factor->measured().inverse(); + const Pose2 pose = factor->measured().inverse(); stream << "EDGE2 " << factor->key2() << " " << factor->key1() << " " - << pose.x() << " " << pose.y() << " " << pose.theta() << " " << RR(0, 0) - << " " << RR(0, 1) << " " << RR(1, 1) << " " << RR(2, 2) << " " - << RR(0, 2) << " " << RR(1, 2) << endl; + << pose.x() << " " << pose.y() << " " << pose.theta() << " " + << RR(0, 0) << " " << RR(0, 1) << " " << RR(1, 1) << " " << RR(2, 2) + << " " << RR(0, 2) << " " << RR(1, 2) << endl; } stream.close(); } /* ************************************************************************* */ -GraphAndValues readG2o(const string& g2oFile, const bool is3D, +GraphAndValues readG2o(const string &g2oFile, const bool is3D, KernelFunctionType kernelFunctionType) { if (is3D) { return load3D(g2oFile); @@ -484,86 +604,90 @@ GraphAndValues readG2o(const string& g2oFile, const bool is3D, } /* ************************************************************************* */ -void writeG2o(const NonlinearFactorGraph& graph, const Values& estimate, - const string& filename) { +void writeG2o(const NonlinearFactorGraph &graph, const Values &estimate, + const string &filename) { fstream stream(filename.c_str(), fstream::out); // save 2D poses - for (const auto& key_value : estimate) { - auto p = dynamic_cast*>(&key_value.value); - if (!p) continue; - const Pose2& pose = p->value(); + for (const auto &key_value : estimate) { + auto p = dynamic_cast *>(&key_value.value); + if (!p) + continue; + const Pose2 &pose = p->value(); stream << "VERTEX_SE2 " << key_value.key << " " << pose.x() << " " - << pose.y() << " " << pose.theta() << endl; + << pose.y() << " " << pose.theta() << endl; } // save 3D poses - for(const auto& key_value: estimate) { - auto p = dynamic_cast*>(&key_value.value); - if (!p) continue; - const Pose3& pose = p->value(); + for (const auto &key_value : estimate) { + auto p = dynamic_cast *>(&key_value.value); + if (!p) + continue; + const Pose3 &pose = p->value(); const Point3 t = pose.translation(); const auto q = pose.rotation().toQuaternion(); stream << "VERTEX_SE3:QUAT " << key_value.key << " " << t.x() << " " - << t.y() << " " << t.z() << " " << q.x() << " " << q.y() << " " - << q.z() << " " << q.w() << endl; + << t.y() << " " << t.z() << " " << q.x() << " " << q.y() << " " + << q.z() << " " << q.w() << endl; } // save 2D landmarks - for(const auto& key_value: estimate) { - auto p = dynamic_cast*>(&key_value.value); - if (!p) continue; - const Point2& point = p->value(); + for (const auto &key_value : estimate) { + auto p = dynamic_cast *>(&key_value.value); + if (!p) + continue; + const Point2 &point = p->value(); stream << "VERTEX_XY " << key_value.key << " " << point.x() << " " - << point.y() << endl; + << point.y() << endl; } // save 3D landmarks - for(const auto& key_value: estimate) { - auto p = dynamic_cast*>(&key_value.value); - if (!p) continue; - const Point3& point = p->value(); + for (const auto &key_value : estimate) { + auto p = dynamic_cast *>(&key_value.value); + if (!p) + continue; + const Point3 &point = p->value(); stream << "VERTEX_TRACKXYZ " << key_value.key << " " << point.x() << " " - << point.y() << " " << point.z() << endl; + << point.y() << " " << point.z() << endl; } // save edges (2D or 3D) - for(const auto& factor_: graph) { - boost::shared_ptr > factor = - boost::dynamic_pointer_cast >(factor_); - if (factor){ + for (const auto &factor_ : graph) { + boost::shared_ptr> factor = + boost::dynamic_pointer_cast>(factor_); + if (factor) { SharedNoiseModel model = factor->noiseModel(); boost::shared_ptr gaussianModel = boost::dynamic_pointer_cast(model); - if (!gaussianModel){ + if (!gaussianModel) { model->print("model\n"); throw invalid_argument("writeG2o: invalid noise model!"); } - Matrix Info = gaussianModel->R().transpose() * gaussianModel->R(); + Matrix3 Info = gaussianModel->R().transpose() * gaussianModel->R(); Pose2 pose = factor->measured(); //.inverse(); stream << "EDGE_SE2 " << factor->key1() << " " << factor->key2() << " " - << pose.x() << " " << pose.y() << " " << pose.theta(); - for (size_t i = 0; i < 3; i++){ - for (size_t j = i; j < 3; j++){ + << pose.x() << " " << pose.y() << " " << pose.theta(); + for (size_t i = 0; i < 3; i++) { + for (size_t j = i; j < 3; j++) { stream << " " << Info(i, j); } } stream << endl; } - boost::shared_ptr< BetweenFactor > factor3D = - boost::dynamic_pointer_cast< BetweenFactor >(factor_); + boost::shared_ptr> factor3D = + boost::dynamic_pointer_cast>(factor_); - if (factor3D){ + if (factor3D) { SharedNoiseModel model = factor3D->noiseModel(); boost::shared_ptr gaussianModel = boost::dynamic_pointer_cast(model); - if (!gaussianModel){ + if (!gaussianModel) { model->print("model\n"); throw invalid_argument("writeG2o: invalid noise model!"); } - Matrix Info = gaussianModel->R().transpose() * gaussianModel->R(); + Matrix6 Info = gaussianModel->R().transpose() * gaussianModel->R(); const Pose3 pose3D = factor3D->measured(); const Point3 p = pose3D.translation(); const auto q = pose3D.rotation().toQuaternion(); @@ -571,14 +695,14 @@ void writeG2o(const NonlinearFactorGraph& graph, const Values& estimate, << " " << p.x() << " " << p.y() << " " << p.z() << " " << q.x() << " " << q.y() << " " << q.z() << " " << q.w(); - Matrix InfoG2o = I_6x6; + Matrix6 InfoG2o = I_6x6; InfoG2o.block<3, 3>(0, 0) = Info.block<3, 3>(3, 3); // cov translation InfoG2o.block<3, 3>(3, 3) = Info.block<3, 3>(0, 0); // cov rotation InfoG2o.block<3, 3>(0, 3) = Info.block<3, 3>(0, 3); // off diagonal InfoG2o.block<3, 3>(3, 0) = Info.block<3, 3>(3, 0); // off diagonal - for (size_t i = 0; i < 6; i++){ - for (size_t j = i; j < 6; j++){ + for (size_t i = 0; i < 6; i++) { + for (size_t j = i; j < 6; j++) { stream << " " << InfoG2o(i, j); } } @@ -602,7 +726,7 @@ istream &operator>>(istream &is, Quaternion &q) { // parse Rot3 from roll, pitch, yaw istream &operator>>(istream &is, Rot3 &R) { double yaw, pitch, roll; - is >> roll >> pitch >> yaw; // notice order ! + is >> roll >> pitch >> yaw; // notice order ! R = Rot3::Ypr(yaw, pitch, roll); return is; } @@ -648,69 +772,43 @@ map parse3DLandmarks(const string &filename, Key maxNr) { return parseIntoMap(filename, maxNr); } -/* ************************************************************************* */ -// Parse BetweenFactor shared pointers into a vector -template -static vector>> -parseIntoVector(const string &filename, Key maxNr = 0) { - ifstream is(filename.c_str()); - if (!is) - throw invalid_argument("parse: can not find file " + filename); - - vector>> result; - string tag; - while (!is.eof()) { - boost::shared_ptr> shared; - is >> shared; - if (shared) { - // optional filter - if (maxNr && (shared->key1() >= maxNr || shared->key1() >= maxNr)) - continue; - result.push_back(shared); - } - is.ignore(LINESIZE, '\n'); - } - return result; -} - /* ************************************************************************* */ // Parse a symmetric covariance matrix (onlyupper-triangular part is stored) istream &operator>>(istream &is, Matrix6 &m) { for (size_t i = 0; i < 6; i++) - for (size_t j = i; j < 6; j++){ + for (size_t j = i; j < 6; j++) { is >> m(i, j); - m(j,i) = m(i,j); - } + m(j, i) = m(i, j); + } return is; } /* ************************************************************************* */ -istream &operator>>(istream &is, - boost::shared_ptr> &shared) { +struct Measurement3 { + Key id1, id2; + Pose3 pose; + SharedNoiseModel model; +}; + +istream &operator>>(istream &is, boost::optional &edge) { string tag; is >> tag; - Matrix6 m; if (tag == "EDGE3") { Key id1, id2; double x, y, z; Rot3 R; - is >> id1 >> id2 >> x >> y >> z >> R; - Pose3 pose(R, {x, y, z}); - - is >> m; - SharedNoiseModel model = noiseModel::Gaussian::Information(m); - shared.reset(new BetweenFactor(id1, id2, pose, model)); + is >> id1 >> id2 >> x >> y >> z >> R >> m; + edge.reset( + {id1, id2, Pose3(R, {x, y, z}), noiseModel::Gaussian::Information(m)}); } if (tag == "EDGE_SE3:QUAT") { Key id1, id2; double x, y, z; Quaternion q; - is >> id1 >> id2 >> x >> y >> z >> q; - Pose3 pose(q, {x, y, z}); + is >> id1 >> id2 >> x >> y >> z >> q >> m; // EDGE_SE3:QUAT stores covariance in t,R order, unlike GTSAM: - is >> m; Matrix6 mgtsam; mgtsam.block<3, 3>(0, 0) = m.block<3, 3>(3, 3); // cov rotation mgtsam.block<3, 3>(3, 3) = m.block<3, 3>(0, 0); // cov translation @@ -718,47 +816,67 @@ istream &operator>>(istream &is, mgtsam.block<3, 3>(3, 0) = m.block<3, 3>(3, 0); // off diagonal SharedNoiseModel model = noiseModel::Gaussian::Information(mgtsam); - shared.reset(new BetweenFactor(id1, id2, pose, model)); + edge.reset({id1, id2, Pose3(q, {x, y, z}), + noiseModel::Gaussian::Information(mgtsam)}); } return is; } +/* ************************************************************************* */ +// Small functor to process the edge into a BetweenFactor::shared_ptr +struct ProcessPose3 { + // The arguments + Key maxNr = 0; + SharedNoiseModel model; + boost::shared_ptr sampler; + + // The actual function + BetweenFactor::shared_ptr operator()(const Measurement3 &edge) { + // optional filter + if (maxNr && (edge.id1 >= maxNr || edge.id2 >= maxNr)) + return nullptr; + + // Get pose and optionally add noise + Pose3 T12 = edge.pose; + if (sampler) + T12 = T12.retract(sampler->sample()); + + // Create factor + return boost::make_shared>(edge.id1, edge.id2, T12, + edge.model); + } +}; + /* ************************************************************************* */ BetweenFactorPose3s parse3DFactors(const string &filename, const noiseModel::Diagonal::shared_ptr &corruptingNoise, Key maxNr) { - auto factors = parseIntoVector(filename, maxNr); - + ProcessPose3 process; + process.maxNr = maxNr; if (corruptingNoise) { - Sampler sampler(corruptingNoise); - for (auto factor : factors) { - auto pose = factor->measured(); - factor.reset(new BetweenFactor(factor->key1(), factor->key2(), - pose.retract(sampler.sample()), - factor->noiseModel())); - } + process.sampler = createSampler(corruptingNoise); } - - return factors; + return parseToVector::shared_ptr>(filename, + process); } /* ************************************************************************* */ -GraphAndValues load3D(const string& filename) { +GraphAndValues load3D(const string &filename) { const auto factors = parse3DFactors(filename); NonlinearFactorGraph::shared_ptr graph(new NonlinearFactorGraph); - for (const auto& factor : factors) { + for (const auto &factor : factors) { graph->push_back(factor); } Values::shared_ptr initial(new Values); const auto poses = parse3DPoses(filename); - for (const auto& key_pose : poses) { + for (const auto &key_pose : poses) { initial->insert(key_pose.first, key_pose.second); } const auto landmarks = parse3DLandmarks(filename); - for (const auto& key_landmark : landmarks) { + for (const auto &key_landmark : landmarks) { initial->insert(key_landmark.first, key_landmark.second); } @@ -766,7 +884,8 @@ GraphAndValues load3D(const string& filename) { } /* ************************************************************************* */ -Rot3 openGLFixedRotation() { // this is due to different convention for cameras in gtsam and openGL +Rot3 openGLFixedRotation() { // this is due to different convention for + // cameras in gtsam and openGL /* R = [ 1 0 0 * 0 -1 0 * 0 0 -1] @@ -779,7 +898,7 @@ Rot3 openGLFixedRotation() { // this is due to different convention for cameras } /* ************************************************************************* */ -Pose3 openGL2gtsam(const Rot3& R, double tx, double ty, double tz) { +Pose3 openGL2gtsam(const Rot3 &R, double tx, double ty, double tz) { Rot3 R90 = openGLFixedRotation(); Rot3 wRc = (R.inverse()).compose(R90); @@ -788,7 +907,7 @@ Pose3 openGL2gtsam(const Rot3& R, double tx, double ty, double tz) { } /* ************************************************************************* */ -Pose3 gtsam2openGL(const Rot3& R, double tx, double ty, double tz) { +Pose3 gtsam2openGL(const Rot3 &R, double tx, double ty, double tz) { Rot3 R90 = openGLFixedRotation(); Rot3 cRw_openGL = R90.compose(R.inverse()); Point3 t_openGL = cRw_openGL.rotate(Point3(-tx, -ty, -tz)); @@ -796,13 +915,13 @@ Pose3 gtsam2openGL(const Rot3& R, double tx, double ty, double tz) { } /* ************************************************************************* */ -Pose3 gtsam2openGL(const Pose3& PoseGTSAM) { +Pose3 gtsam2openGL(const Pose3 &PoseGTSAM) { return gtsam2openGL(PoseGTSAM.rotation(), PoseGTSAM.x(), PoseGTSAM.y(), - PoseGTSAM.z()); + PoseGTSAM.z()); } /* ************************************************************************* */ -bool readBundler(const string& filename, SfmData &data) { +bool readBundler(const string &filename, SfmData &data) { // Load the data file ifstream is(filename.c_str(), ifstream::in); if (!is) { @@ -837,7 +956,7 @@ bool readBundler(const string& filename, SfmData &data) { // Check for all-zero R, in which case quit if (r11 == 0 && r12 == 0 && r13 == 0) { cout << "Error in readBundler: zero rotation matrix for pose " << i - << endl; + << endl; return false; } @@ -889,7 +1008,7 @@ bool readBundler(const string& filename, SfmData &data) { } /* ************************************************************************* */ -bool readBAL(const string& filename, SfmData &data) { +bool readBAL(const string &filename, SfmData &data) { // Load the data file ifstream is(filename.c_str(), ifstream::in); if (!is) { @@ -937,7 +1056,7 @@ bool readBAL(const string& filename, SfmData &data) { // Get the 3D position float x, y, z; is >> x >> y >> z; - SfmTrack& track = data.tracks[j]; + SfmTrack &track = data.tracks[j]; track.p = Point3(x, y, z); track.r = 0.4f; track.g = 0.4f; @@ -949,7 +1068,7 @@ bool readBAL(const string& filename, SfmData &data) { } /* ************************************************************************* */ -bool writeBAL(const string& filename, SfmData &data) { +bool writeBAL(const string &filename, SfmData &data) { // Open the output file ofstream os; os.open(filename.c_str()); @@ -967,29 +1086,32 @@ bool writeBAL(const string& filename, SfmData &data) { // Write observations os << data.number_cameras() << " " << data.number_tracks() << " " - << nrObservations << endl; + << nrObservations << endl; os << endl; for (size_t j = 0; j < data.number_tracks(); j++) { // for each 3D point j - const SfmTrack& track = data.tracks[j]; + const SfmTrack &track = data.tracks[j]; - for (size_t k = 0; k < track.number_measurements(); k++) { // for each observation of the 3D point j + for (size_t k = 0; k < track.number_measurements(); + k++) { // for each observation of the 3D point j size_t i = track.measurements[k].first; // camera id double u0 = data.cameras[i].calibration().u0(); double v0 = data.cameras[i].calibration().v0(); if (u0 != 0 || v0 != 0) { - cout - << "writeBAL has not been tested for calibration with nonzero (u0,v0)" - << endl; + cout << "writeBAL has not been tested for calibration with nonzero " + "(u0,v0)" + << endl; } - double pixelBALx = track.measurements[k].second.x() - u0; // center of image is the origin - double pixelBALy = -(track.measurements[k].second.y() - v0); // center of image is the origin + double pixelBALx = track.measurements[k].second.x() - + u0; // center of image is the origin + double pixelBALy = -(track.measurements[k].second.y() - + v0); // center of image is the origin Point2 pixelMeasurement(pixelBALx, pixelBALy); - os << i /*camera id*/<< " " << j /*point id*/<< " " - << pixelMeasurement.x() /*u of the pixel*/<< " " - << pixelMeasurement.y() /*v of the pixel*/<< endl; + os << i /*camera id*/ << " " << j /*point id*/ << " " + << pixelMeasurement.x() /*u of the pixel*/ << " " + << pixelMeasurement.y() /*v of the pixel*/ << endl; } } os << endl; @@ -1022,15 +1144,17 @@ bool writeBAL(const string& filename, SfmData &data) { return true; } -bool writeBALfromValues(const string& filename, const SfmData &data, - Values& values) { +bool writeBALfromValues(const string &filename, const SfmData &data, + Values &values) { using Camera = PinholeCamera; SfmData dataValues = data; // Store poses or cameras in SfmData size_t nrPoses = values.count(); - if (nrPoses == dataValues.number_cameras()) { // we only estimated camera poses - for (size_t i = 0; i < dataValues.number_cameras(); i++) { // for each camera + if (nrPoses == + dataValues.number_cameras()) { // we only estimated camera poses + for (size_t i = 0; i < dataValues.number_cameras(); + i++) { // for each camera Key poseKey = symbol('x', i); Pose3 pose = values.at(poseKey); Cal3Bundler K = dataValues.cameras[i].calibration(); @@ -1039,29 +1163,29 @@ bool writeBALfromValues(const string& filename, const SfmData &data, } } else { size_t nrCameras = values.count(); - if (nrCameras == dataValues.number_cameras()) { // we only estimated camera poses and calibration - for (size_t i = 0; i < nrCameras; i++) { // for each camera - Key cameraKey = i; // symbol('c',i); + if (nrCameras == dataValues.number_cameras()) { // we only estimated camera + // poses and calibration + for (size_t i = 0; i < nrCameras; i++) { // for each camera + Key cameraKey = i; // symbol('c',i); Camera camera = values.at(cameraKey); dataValues.cameras[i] = camera; } } else { - cout - << "writeBALfromValues: different number of cameras in SfM_dataValues (#cameras " - << dataValues.number_cameras() << ") and values (#cameras " - << nrPoses << ", #poses " << nrCameras << ")!!" - << endl; + cout << "writeBALfromValues: different number of cameras in " + "SfM_dataValues (#cameras " + << dataValues.number_cameras() << ") and values (#cameras " + << nrPoses << ", #poses " << nrCameras << ")!!" << endl; return false; } } // Store 3D points in SfmData - size_t nrPoints = values.count(), nrTracks = dataValues.number_tracks(); + size_t nrPoints = values.count(), + nrTracks = dataValues.number_tracks(); if (nrPoints != nrTracks) { - cout - << "writeBALfromValues: different number of points in SfM_dataValues (#points= " - << nrTracks << ") and values (#points " - << nrPoints << ")!!" << endl; + cout << "writeBALfromValues: different number of points in " + "SfM_dataValues (#points= " + << nrTracks << ") and values (#points " << nrPoints << ")!!" << endl; } for (size_t j = 0; j < nrTracks; j++) { // for each point @@ -1073,7 +1197,7 @@ bool writeBALfromValues(const string& filename, const SfmData &data, dataValues.tracks[j].r = 1.0; dataValues.tracks[j].g = 0.0; dataValues.tracks[j].b = 0.0; - dataValues.tracks[j].p = Point3(0,0,0); + dataValues.tracks[j].p = Point3(0, 0, 0); } } @@ -1081,22 +1205,22 @@ bool writeBALfromValues(const string& filename, const SfmData &data, return writeBAL(filename, dataValues); } -Values initialCamerasEstimate(const SfmData& db) { +Values initialCamerasEstimate(const SfmData &db) { Values initial; size_t i = 0; // NO POINTS: j = 0; - for(const SfmCamera& camera: db.cameras) + for (const SfmCamera &camera : db.cameras) initial.insert(i++, camera); return initial; } -Values initialCamerasAndPointsEstimate(const SfmData& db) { +Values initialCamerasAndPointsEstimate(const SfmData &db) { Values initial; size_t i = 0, j = 0; - for(const SfmCamera& camera: db.cameras) + for (const SfmCamera &camera : db.cameras) initial.insert((i++), camera); - for(const SfmTrack& track: db.tracks) + for (const SfmTrack &track : db.tracks) initial.insert(P(j++), track.p); return initial; } -} // \namespace gtsam +} // namespace gtsam diff --git a/gtsam/slam/dataset.h b/gtsam/slam/dataset.h index caef96cf4..5b92800af 100644 --- a/gtsam/slam/dataset.h +++ b/gtsam/slam/dataset.h @@ -77,16 +77,6 @@ typedef std::pair IndexedPose; typedef std::pair IndexedLandmark; typedef std::pair, Pose2> IndexedEdge; -#ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V41 -/** - * Parse TORO/G2O vertex "id x y yaw" - * @param is input stream - * @param tag string parsed from input stream, will only parse if vertex type - */ -GTSAM_EXPORT boost::optional parseVertex(std::istream& is, - const std::string& tag); -#endif - /** * Parse TORO/G2O vertex "id x y yaw" * @param is input stream @@ -118,7 +108,8 @@ using BetweenFactorPose2s = /// Parse edges in 2D g2o graph file into a set of BetweenFactors. GTSAM_EXPORT BetweenFactorPose2s parse2DFactors( const std::string &filename, - const noiseModel::Diagonal::shared_ptr &corruptingNoise = nullptr); + const noiseModel::Diagonal::shared_ptr &corruptingNoise = nullptr, + Key maxNr = 0); /// Parse vertices in 2D g2o graph file into a map of Pose2s. GTSAM_EXPORT std::map parse2DPoses(const std::string &filename, @@ -343,4 +334,15 @@ GTSAM_EXPORT Values initialCamerasEstimate(const SfmData& db); */ GTSAM_EXPORT Values initialCamerasAndPointsEstimate(const SfmData& db); +#ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V41 +/** + * Parse TORO/G2O vertex "id x y yaw" + * @param is input stream + * @param tag string parsed from input stream, will only parse if vertex type + */ +GTSAM_EXPORT boost::optional parseVertex(std::istream &is, + const std::string &tag) { + return parseVertexPose(is, tag); +} +#endif } // namespace gtsam diff --git a/gtsam/slam/tests/testDataset.cpp b/gtsam/slam/tests/testDataset.cpp index 6ee44cfd6..bc65dc351 100644 --- a/gtsam/slam/tests/testDataset.cpp +++ b/gtsam/slam/tests/testDataset.cpp @@ -104,13 +104,13 @@ TEST(dataSet, load2D) { boost::dynamic_pointer_cast>(graph->at(0)); EXPECT(assert_equal(expected, *actual)); - // // Check factor parsing - // const auto actualFactors = parse2DFactors(filename); - // for (size_t i : {0, 1, 2, 3, 4, 5}) { - // EXPECT(assert_equal( - // *boost::dynamic_pointer_cast>(graph->at(i)), - // *actualFactors[i], 1e-5)); - // } + // Check factor parsing + const auto actualFactors = parse2DFactors(filename); + for (size_t i : {0, 1, 2, 3, 4, 5}) { + EXPECT(assert_equal( + *boost::dynamic_pointer_cast>(graph->at(i)), + *actualFactors[i], 1e-5)); + } // Check pose parsing const auto actualPoses = parse2DPoses(filename); From aa3c0f8c5d679e1c5fb7fd16ae8078243e810672 Mon Sep 17 00:00:00 2001 From: Frank Dellaert Date: Wed, 12 Aug 2020 23:59:57 -0400 Subject: [PATCH 348/869] refactored load2d --- gtsam/slam/dataset.cpp | 189 ++++++++++++++++++----------------------- gtsam/slam/dataset.h | 26 +++--- 2 files changed, 96 insertions(+), 119 deletions(-) diff --git a/gtsam/slam/dataset.cpp b/gtsam/slam/dataset.cpp index 29162dafb..af8904e49 100644 --- a/gtsam/slam/dataset.cpp +++ b/gtsam/slam/dataset.cpp @@ -108,10 +108,10 @@ string createRewrittenFileName(const string &name) { } /* ************************************************************************* */ -GraphAndValues load2D(pair dataset, Key maxNr, +GraphAndValues load2D(pair dataset, Key maxKey, bool addNoise, bool smart, NoiseFormat noiseFormat, KernelFunctionType kernelFunctionType) { - return load2D(dataset.first, dataset.second, maxNr, addNoise, smart, + return load2D(dataset.first, dataset.second, maxKey, addNoise, smart, noiseFormat, kernelFunctionType); } @@ -199,16 +199,6 @@ createNoiseModel(const Vector6 v, bool smart, NoiseFormat noiseFormat, } } -/* ************************************************************************* */ -// Read noise parameters and interpret them according to flags -static SharedNoiseModel readNoiseModel(istream &is, bool smart, - NoiseFormat noiseFormat, - KernelFunctionType kernelFunctionType) { - Vector6 v; - is >> v(0) >> v(1) >> v(2) >> v(3) >> v(4) >> v(5); - return createNoiseModel(v, smart, noiseFormat, kernelFunctionType); -} - /* ************************************************************************* */ boost::optional parseVertexPose(istream &is, const string &tag) { if ((tag == "VERTEX2") || (tag == "VERTEX_SE2") || (tag == "VERTEX")) { @@ -237,7 +227,7 @@ boost::optional parseVertexLandmark(istream &is, /* ************************************************************************* */ // Parse types T into a Key-indexed map template -static map parseIntoMap(const string &filename, Key maxNr = 0) { +static map parseIntoMap(const string &filename, Key maxKey = 0) { ifstream is(filename.c_str()); if (!is) throw invalid_argument("parse: can not find file " + filename); @@ -249,7 +239,7 @@ static map parseIntoMap(const string &filename, Key maxNr = 0) { is >> indexed_t; if (indexed_t) { // optional filter - if (maxNr && indexed_t->first >= maxNr) + if (maxKey && indexed_t->first >= maxKey) continue; result.insert(*indexed_t); } @@ -266,8 +256,8 @@ istream &operator>>(istream &is, boost::optional &indexed) { return is; } -map parse2DPoses(const string &filename, Key maxNr) { - return parseIntoMap(filename, maxNr); +map parse2DPoses(const string &filename, Key maxKey) { + return parseIntoMap(filename, maxKey); } /* ************************************************************************* */ @@ -278,8 +268,8 @@ istream &operator>>(istream &is, boost::optional &indexed) { return is; } -map parse2DLandmarks(const string &filename, Key maxNr) { - return parseIntoMap(filename, maxNr); +map parse2DLandmarks(const string &filename, Key maxKey) { + return parseIntoMap(filename, maxKey); } /* ************************************************************************* */ @@ -360,19 +350,26 @@ boost::shared_ptr createSampler(const SharedNoiseModel &model) { // Small functor to process the edge into a BetweenFactor::shared_ptr struct ProcessPose2 { // The arguments - Key maxNr = 0; + Key maxKey; SharedNoiseModel model; boost::shared_ptr sampler; // Arguments for parsing noise model - bool smart = true; - NoiseFormat noiseFormat = NoiseFormatAUTO; - KernelFunctionType kernelFunctionType = KernelFunctionTypeNONE; + bool smart; + NoiseFormat noiseFormat; + KernelFunctionType kernelFunctionType; + + ProcessPose2(Key maxKey = 0, SharedNoiseModel model = nullptr, + boost::shared_ptr sampler = nullptr, bool smart = true, + NoiseFormat noiseFormat = NoiseFormatAUTO, + KernelFunctionType kernelFunctionType = KernelFunctionTypeNONE) + : maxKey(maxKey), model(model), sampler(sampler), smart(smart), + noiseFormat(noiseFormat), kernelFunctionType(kernelFunctionType) {} // The actual function BetweenFactor::shared_ptr operator()(const Measurement2 &edge) { // optional filter - if (maxNr && (edge.id1 >= maxNr || edge.id2 >= maxNr)) + if (maxKey && (edge.id1 >= maxKey || edge.id2 >= maxKey)) return nullptr; // Get pose and optionally add noise @@ -394,90 +391,32 @@ struct ProcessPose2 { BetweenFactorPose2s parse2DFactors(const string &filename, const noiseModel::Diagonal::shared_ptr &corruptingNoise, - Key maxNr) { - ProcessPose2 process; - process.maxNr = maxNr; - if (corruptingNoise) { - process.sampler = createSampler(corruptingNoise); - } + Key maxKey) { + ProcessPose2 process(maxKey, nullptr, + corruptingNoise ? createSampler(corruptingNoise) + : nullptr); + return parseToVector::shared_ptr>(filename, process); } /* ************************************************************************* */ -GraphAndValues load2D(const string &filename, SharedNoiseModel model, Key maxNr, - bool addNoise, bool smart, NoiseFormat noiseFormat, - KernelFunctionType kernelFunctionType) { - - Values::shared_ptr initial(new Values); - - const auto poses = parse2DPoses(filename, maxNr); - for (const auto &key_pose : poses) { - initial->insert(key_pose.first, key_pose.second); - } - const auto landmarks = parse2DLandmarks(filename, maxNr); - for (const auto &key_landmark : landmarks) { - initial->insert(key_landmark.first, key_landmark.second); - } - +static void parseOthers(const string &filename, Key maxKey, + NonlinearFactorGraph::shared_ptr graph, + Values::shared_ptr initial) { + // Do a pass to get other types of measurements ifstream is(filename.c_str()); if (!is) throw invalid_argument("load2D: can not find file " + filename); - NonlinearFactorGraph::shared_ptr graph(new NonlinearFactorGraph); - - // If asked, create a sampler with random number generator - boost::shared_ptr sampler; - if (addNoise) { - noiseModel::Diagonal::shared_ptr noise; - if (model) - noise = boost::dynamic_pointer_cast(model); - if (!noise) - throw invalid_argument( - "gtsam::load2D: invalid noise model for adding noise" - "(current version assumes diagonal noise model)!"); - sampler.reset(new Sampler(noise)); - } - - // Parse the pose constraints Key id1, id2; - bool haveLandmark = false; - const bool useModelInFile = !model; while (!is.eof()) { string tag; if (!(is >> tag)) break; - auto between_pose = parseEdge(is, tag); - if (between_pose) { - std::tie(id1, id2) = between_pose->first; - Pose2 l1Xl2 = between_pose->second; - - // read noise model - SharedNoiseModel modelInFile = - readNoiseModel(is, smart, noiseFormat, kernelFunctionType); - - // optional filter - if (maxNr && (id1 >= maxNr || id2 >= maxNr)) - continue; - - if (useModelInFile) - model = modelInFile; - - if (addNoise) - l1Xl2 = l1Xl2.retract(sampler->sample()); - - // Insert vertices if pure odometry file - if (!initial->exists(id1)) - initial->insert(id1, Pose2()); - if (!initial->exists(id2)) - initial->insert(id2, initial->at(id1) * l1Xl2); - - NonlinearFactor::shared_ptr factor( - new BetweenFactor(id1, id2, l1Xl2, model)); - graph->push_back(factor); - } // Parse measurements + bool haveLandmark = false; double bearing, range, bearing_std, range_std; // A bearing-range measurement @@ -485,8 +424,7 @@ GraphAndValues load2D(const string &filename, SharedNoiseModel model, Key maxNr, is >> id1 >> id2 >> bearing >> range >> bearing_std >> range_std; } - // A landmark measurement, TODO Frank says: don't know why is converted to - // bearing-range + // A landmark measurement, converted to bearing-range if (tag == "LANDMARK") { double lmx, lmy; double v1, v2, v3; @@ -521,7 +459,7 @@ GraphAndValues load2D(const string &filename, SharedNoiseModel model, Key maxNr, if (tag == "LANDMARK" || tag == "BR") { // optional filter - if (maxNr && id1 >= maxNr) + if (maxKey && id1 >= maxKey) continue; // Create noise model @@ -545,14 +483,53 @@ GraphAndValues load2D(const string &filename, SharedNoiseModel model, Key maxNr, } is.ignore(LINESIZE, '\n'); } +} + +/* ************************************************************************* */ +GraphAndValues load2D(const string &filename, SharedNoiseModel model, Key maxKey, + bool addNoise, bool smart, NoiseFormat noiseFormat, + KernelFunctionType kernelFunctionType) { + + Values::shared_ptr initial(new Values); + + const auto poses = parse2DPoses(filename, maxKey); + for (const auto &key_pose : poses) { + initial->insert(key_pose.first, key_pose.second); + } + const auto landmarks = parse2DLandmarks(filename, maxKey); + for (const auto &key_landmark : landmarks) { + initial->insert(key_landmark.first, key_landmark.second); + } + + // Parse the pose constraints + ProcessPose2 process(maxKey, model, addNoise ? createSampler(model) : nullptr, + smart, noiseFormat, kernelFunctionType); + auto factors = parseToVector::shared_ptr>( + filename, process); + + // Add factors into the graph and add poses if necessary + auto graph = boost::make_shared(); + for (const auto &f : factors) { + graph->push_back(f); + + // Insert vertices if pure odometry file + Key id1 = f->key1(), id2 = f->key2(); + if (!initial->exists(id1)) + initial->insert(id1, Pose2()); + if (!initial->exists(id2)) + initial->insert(id2, initial->at(id1) * f->measured()); + } + + // Do a pass to parse landmarks and bearing-range measurements + parseOthers(filename, maxKey, graph, initial); return make_pair(graph, initial); } /* ************************************************************************* */ GraphAndValues load2D_robust(const string &filename, - noiseModel::Base::shared_ptr &model, Key maxNr) { - return load2D(filename, model, maxNr); + noiseModel::Base::shared_ptr &model, Key maxKey) { + return load2D(filename, model, maxKey); } /* ************************************************************************* */ @@ -595,10 +572,10 @@ GraphAndValues readG2o(const string &g2oFile, const bool is3D, return load3D(g2oFile); } else { // just call load2D - Key maxNr = 0; + Key maxKey = 0; bool addNoise = false; bool smart = true; - return load2D(g2oFile, SharedNoiseModel(), maxNr, addNoise, smart, + return load2D(g2oFile, SharedNoiseModel(), maxKey, addNoise, smart, NoiseFormatG2O, kernelFunctionType); } } @@ -751,8 +728,8 @@ istream &operator>>(istream &is, boost::optional> &indexed) { return is; } -map parse3DPoses(const string &filename, Key maxNr) { - return parseIntoMap(filename, maxNr); +map parse3DPoses(const string &filename, Key maxKey) { + return parseIntoMap(filename, maxKey); } /* ************************************************************************* */ @@ -768,8 +745,8 @@ istream &operator>>(istream &is, boost::optional> &indexed) { return is; } -map parse3DLandmarks(const string &filename, Key maxNr) { - return parseIntoMap(filename, maxNr); +map parse3DLandmarks(const string &filename, Key maxKey) { + return parseIntoMap(filename, maxKey); } /* ************************************************************************* */ @@ -826,14 +803,14 @@ istream &operator>>(istream &is, boost::optional &edge) { // Small functor to process the edge into a BetweenFactor::shared_ptr struct ProcessPose3 { // The arguments - Key maxNr = 0; + Key maxKey = 0; SharedNoiseModel model; boost::shared_ptr sampler; // The actual function BetweenFactor::shared_ptr operator()(const Measurement3 &edge) { // optional filter - if (maxNr && (edge.id1 >= maxNr || edge.id2 >= maxNr)) + if (maxKey && (edge.id1 >= maxKey || edge.id2 >= maxKey)) return nullptr; // Get pose and optionally add noise @@ -851,9 +828,9 @@ struct ProcessPose3 { BetweenFactorPose3s parse3DFactors(const string &filename, const noiseModel::Diagonal::shared_ptr &corruptingNoise, - Key maxNr) { + Key maxKey) { ProcessPose3 process; - process.maxNr = maxNr; + process.maxKey = maxKey; if (corruptingNoise) { process.sampler = createSampler(corruptingNoise); } diff --git a/gtsam/slam/dataset.h b/gtsam/slam/dataset.h index 5b92800af..61eb9256e 100644 --- a/gtsam/slam/dataset.h +++ b/gtsam/slam/dataset.h @@ -109,15 +109,15 @@ using BetweenFactorPose2s = GTSAM_EXPORT BetweenFactorPose2s parse2DFactors( const std::string &filename, const noiseModel::Diagonal::shared_ptr &corruptingNoise = nullptr, - Key maxNr = 0); + Key maxKey = 0); /// Parse vertices in 2D g2o graph file into a map of Pose2s. GTSAM_EXPORT std::map parse2DPoses(const std::string &filename, - Key maxNr = 0); + Key maxKey = 0); /// Parse landmarks in 2D g2o graph file into a map of Point2s. GTSAM_EXPORT std::map parse2DLandmarks(const string &filename, - Key maxNr = 0); + Key maxKey = 0); /// Return type for load functions using GraphAndValues = @@ -126,12 +126,12 @@ using GraphAndValues = /** * Load TORO 2D Graph * @param dataset/model pair as constructed by [dataset] - * @param maxNr if non-zero cut out vertices >= maxNr + * @param maxKey if non-zero cut out vertices >= maxKey * @param addNoise add noise to the edges * @param smart try to reduce complexity of covariance to cheapest model */ GTSAM_EXPORT GraphAndValues load2D( - std::pair dataset, Key maxNr = 0, + std::pair dataset, Key maxKey = 0, bool addNoise = false, bool smart = true, // NoiseFormat noiseFormat = NoiseFormatAUTO, @@ -141,7 +141,7 @@ GTSAM_EXPORT GraphAndValues load2D( * Load TORO/G2O style graph files * @param filename * @param model optional noise model to use instead of one specified by file - * @param maxNr if non-zero cut out vertices >= maxNr + * @param maxKey if non-zero cut out vertices >= maxKey * @param addNoise add noise to the edges * @param smart try to reduce complexity of covariance to cheapest model * @param noiseFormat how noise parameters are stored @@ -149,13 +149,13 @@ GTSAM_EXPORT GraphAndValues load2D( * @return graph and initial values */ GTSAM_EXPORT GraphAndValues load2D(const std::string& filename, - SharedNoiseModel model = SharedNoiseModel(), Key maxNr = 0, bool addNoise = + SharedNoiseModel model = SharedNoiseModel(), Key maxKey = 0, bool addNoise = false, bool smart = true, NoiseFormat noiseFormat = NoiseFormatAUTO, // KernelFunctionType kernelFunctionType = KernelFunctionTypeNONE); /// @deprecated load2D now allows for arbitrary models and wrapping a robust kernel GTSAM_EXPORT GraphAndValues load2D_robust(const std::string& filename, - noiseModel::Base::shared_ptr& model, Key maxNr = 0); + noiseModel::Base::shared_ptr& model, Key maxKey = 0); /** save 2d graph */ GTSAM_EXPORT void save2D(const NonlinearFactorGraph& graph, @@ -188,15 +188,15 @@ using BetweenFactorPose3s = std::vector::shared_ptr> GTSAM_EXPORT BetweenFactorPose3s parse3DFactors( const std::string &filename, const noiseModel::Diagonal::shared_ptr &corruptingNoise = nullptr, - Key maxNr = 0); + Key maxKey = 0); /// Parse vertices in 3D TORO/g2o graph file into a map of Pose3s. GTSAM_EXPORT std::map parse3DPoses(const std::string &filename, - Key maxNr = 0); + Key maxKey = 0); /// Parse landmarks in 3D g2o graph file into a map of Point3s. GTSAM_EXPORT std::map parse3DLandmarks(const std::string &filename, - Key maxNr = 0); + Key maxKey = 0); /// Load TORO 3D Graph GTSAM_EXPORT GraphAndValues load3D(const std::string& filename); @@ -340,8 +340,8 @@ GTSAM_EXPORT Values initialCamerasAndPointsEstimate(const SfmData& db); * @param is input stream * @param tag string parsed from input stream, will only parse if vertex type */ -GTSAM_EXPORT boost::optional parseVertex(std::istream &is, - const std::string &tag) { +inline boost::optional parseVertex(std::istream &is, + const std::string &tag) { return parseVertexPose(is, tag); } #endif From e62d04ce2715f9fa913ce0979447334c3eb27855 Mon Sep 17 00:00:00 2001 From: Frank Dellaert Date: Thu, 13 Aug 2020 20:38:58 -0400 Subject: [PATCH 349/869] Templated parse methods --- gtsam/nonlinear/Values.h | 2 +- gtsam/sam/BearingRangeFactor.h | 15 +- gtsam/sfm/BinaryMeasurement.h | 93 ++-- gtsam/slam/dataset.cpp | 763 +++++++++++++++++-------------- gtsam/slam/dataset.h | 79 ++-- gtsam/slam/tests/testDataset.cpp | 26 +- timing/timeFrobeniusFactor.cpp | 2 +- 7 files changed, 530 insertions(+), 450 deletions(-) diff --git a/gtsam/nonlinear/Values.h b/gtsam/nonlinear/Values.h index aadbcf394..b49188b68 100644 --- a/gtsam/nonlinear/Values.h +++ b/gtsam/nonlinear/Values.h @@ -397,7 +397,7 @@ namespace gtsam { template size_t count() const { size_t i = 0; - for (const auto& key_value : *this) { + for (const auto key_value : *this) { if (dynamic_cast*>(&key_value.value)) ++i; } diff --git a/gtsam/sam/BearingRangeFactor.h b/gtsam/sam/BearingRangeFactor.h index af7b47446..b8e231915 100644 --- a/gtsam/sam/BearingRangeFactor.h +++ b/gtsam/sam/BearingRangeFactor.h @@ -42,12 +42,19 @@ class BearingRangeFactor public: typedef boost::shared_ptr shared_ptr; - /// default constructor + /// Default constructor BearingRangeFactor() {} - /// primary constructor - BearingRangeFactor(Key key1, Key key2, const B& measuredBearing, - const R& measuredRange, const SharedNoiseModel& model) + /// Construct from BearingRange instance + BearingRangeFactor(Key key1, Key key2, const T &bearingRange, + const SharedNoiseModel &model) + : Base({key1, key2}, model, T(bearingRange)) { + this->initialize(expression({key1, key2})); + } + + /// Construct from separate bearing and range + BearingRangeFactor(Key key1, Key key2, const B &measuredBearing, + const R &measuredRange, const SharedNoiseModel &model) : Base({key1, key2}, model, T(measuredBearing, measuredRange)) { this->initialize(expression({key1, key2})); } diff --git a/gtsam/sfm/BinaryMeasurement.h b/gtsam/sfm/BinaryMeasurement.h index c4b4a9804..c525c1b9e 100644 --- a/gtsam/sfm/BinaryMeasurement.h +++ b/gtsam/sfm/BinaryMeasurement.h @@ -15,78 +15,69 @@ * @file BinaryMeasurement.h * @author Akshay Krishnan * @date July 2020 - * @brief Binary measurement represents a measurement between two keys in a graph. - * A binary measurement is similar to a BetweenFactor, except that it does not contain - * an error function. It is a measurement (along with a noise model) from one key to - * another. Note that the direction is important. A measurement from key1 to key2 is not - * the same as the same measurement from key2 to key1. + * @brief Binary measurement represents a measurement between two keys in a + * graph. A binary measurement is similar to a BetweenFactor, except that it + * does not contain an error function. It is a measurement (along with a noise + * model) from one key to another. Note that the direction is important. A + * measurement from key1 to key2 is not the same as the same measurement from + * key2 to key1. */ -#include - #include -#include -#include - +#include #include #include +#include +#include + namespace gtsam { -template -class BinaryMeasurement { - // Check that VALUE type is testable - BOOST_CONCEPT_ASSERT((IsTestable)); - - public: - typedef VALUE T; +template class BinaryMeasurement : public Factor { + // Check that T type is testable + BOOST_CONCEPT_ASSERT((IsTestable)); +public: // shorthand for a smart pointer to a measurement - typedef typename boost::shared_ptr shared_ptr; + using shared_ptr = typename boost::shared_ptr; - private: - Key key1_, key2_; /** Keys */ +private: + T measured_; ///< The measurement + SharedNoiseModel noiseModel_; ///< Noise model - VALUE measured_; /** The measurement */ +public: + BinaryMeasurement(Key key1, Key key2, const T &measured, + const SharedNoiseModel &model = nullptr) + : Factor(std::vector({key1, key2})), measured_(measured), + noiseModel_(model) {} - SharedNoiseModel noiseModel_; /** Noise model */ - - public: - /** Constructor */ - BinaryMeasurement(Key key1, Key key2, const VALUE &measured, - const SharedNoiseModel &model = nullptr) : - key1_(key1), key2_(key2), measured_(measured), noiseModel_(model) { - } - - Key key1() const { return key1_; } - - Key key2() const { return key2_; } + /// @name Standard Interface + /// @{ + Key key1() const { return keys_[0]; } + Key key2() const { return keys_[1]; } + const T &measured() const { return measured_; } const SharedNoiseModel &noiseModel() const { return noiseModel_; } - /** implement functions needed for Testable */ + /// @} + /// @name Testable + /// @{ - /** print */ - void print(const std::string &s, const KeyFormatter &keyFormatter = DefaultKeyFormatter) const { - std::cout << s << "BinaryMeasurement(" - << keyFormatter(this->key1()) << "," + void print(const std::string &s, + const KeyFormatter &keyFormatter = DefaultKeyFormatter) const { + std::cout << s << "BinaryMeasurement(" << keyFormatter(this->key1()) << "," << keyFormatter(this->key2()) << ")\n"; traits::Print(measured_, " measured: "); this->noiseModel_->print(" noise model: "); } - /** equals */ bool equals(const BinaryMeasurement &expected, double tol = 1e-9) const { - const BinaryMeasurement *e = dynamic_cast *> (&expected); - return e != nullptr && key1_ == e->key1_ && - key2_ == e->key2_ - && traits::Equals(this->measured_, e->measured_, tol) && - noiseModel_->equals(*expected.noiseModel()); + const BinaryMeasurement *e = + dynamic_cast *>(&expected); + return e != nullptr && Factor::equals(*e) && + traits::Equals(this->measured_, e->measured_, tol) && + noiseModel_->equals(*expected.noiseModel()); } - - /** return the measured value */ - VALUE measured() const { - return measured_; - } -}; // \class BetweenMeasurement -} \ No newline at end of file + /// @} +}; +} // namespace gtsam \ No newline at end of file diff --git a/gtsam/slam/dataset.cpp b/gtsam/slam/dataset.cpp index af8904e49..11473d084 100644 --- a/gtsam/slam/dataset.cpp +++ b/gtsam/slam/dataset.cpp @@ -108,11 +108,94 @@ string createRewrittenFileName(const string &name) { } /* ************************************************************************* */ -GraphAndValues load2D(pair dataset, Key maxKey, - bool addNoise, bool smart, NoiseFormat noiseFormat, - KernelFunctionType kernelFunctionType) { - return load2D(dataset.first, dataset.second, maxKey, addNoise, smart, - noiseFormat, kernelFunctionType); +// Parse a file by calling the parse(is, tag) function for every line. +template +using Parser = + std::function(istream &is, const string &tag)>; + +template +static void parseLines(const string &filename, Parser parse) { + ifstream is(filename.c_str()); + if (!is) + throw invalid_argument("parse: can not find file " + filename); + while (!is.eof()) { + string tag; + is >> tag; + parse(is, tag); // ignore return value + is.ignore(LINESIZE, '\n'); + } +} + +/* ************************************************************************* */ +// Parse types T into a Key-indexed map +template +map parseToMap(const string &filename, Parser> parse, + Key maxKey) { + ifstream is(filename.c_str()); + if (!is) + throw invalid_argument("parse: can not find file " + filename); + + map result; + Parser> emplace = [&result, parse](istream &is, + const string &tag) { + if (auto t = parse(is, tag)) + result.emplace(*t); + return boost::none; + }; + parseLines(filename, emplace); + return result; +} + +/* ************************************************************************* */ +// Parse a file and push results on a vector +// TODO(frank): do we need this *and* parseMeasurements? +template +static vector parseToVector(const string &filename, Parser parse) { + vector result; + Parser add = [&result, parse](istream &is, const string &tag) { + if (auto t = parse(is, tag)) + result.push_back(*t); + return boost::none; + }; + parseLines(filename, add); + return result; +} + +/* ************************************************************************* */ +boost::optional parseVertexPose(istream &is, const string &tag) { + if ((tag == "VERTEX2") || (tag == "VERTEX_SE2") || (tag == "VERTEX")) { + Key id; + double x, y, yaw; + is >> id >> x >> y >> yaw; + return IndexedPose(id, Pose2(x, y, yaw)); + } else { + return boost::none; + } +} + +template <> +std::map parseVariables(const std::string &filename, + Key maxKey) { + return parseToMap(filename, parseVertexPose, maxKey); +} + +/* ************************************************************************* */ +boost::optional parseVertexLandmark(istream &is, + const string &tag) { + if (tag == "VERTEX_XY") { + Key id; + double x, y; + is >> id >> x >> y; + return IndexedLandmark(id, Point2(x, y)); + } else { + return boost::none; + } +} + +template <> +std::map parseVariables(const std::string &filename, + Key maxKey) { + return parseToMap(filename, parseVertexLandmark, maxKey); } /* ************************************************************************* */ @@ -199,107 +282,6 @@ createNoiseModel(const Vector6 v, bool smart, NoiseFormat noiseFormat, } } -/* ************************************************************************* */ -boost::optional parseVertexPose(istream &is, const string &tag) { - if ((tag == "VERTEX2") || (tag == "VERTEX_SE2") || (tag == "VERTEX")) { - Key id; - double x, y, yaw; - is >> id >> x >> y >> yaw; - return IndexedPose(id, Pose2(x, y, yaw)); - } else { - return boost::none; - } -} - -/* ************************************************************************* */ -boost::optional parseVertexLandmark(istream &is, - const string &tag) { - if (tag == "VERTEX_XY") { - Key id; - double x, y; - is >> id >> x >> y; - return IndexedLandmark(id, Point2(x, y)); - } else { - return boost::none; - } -} - -/* ************************************************************************* */ -// Parse types T into a Key-indexed map -template -static map parseIntoMap(const string &filename, Key maxKey = 0) { - ifstream is(filename.c_str()); - if (!is) - throw invalid_argument("parse: can not find file " + filename); - - map result; - string tag; - while (!is.eof()) { - boost::optional> indexed_t; - is >> indexed_t; - if (indexed_t) { - // optional filter - if (maxKey && indexed_t->first >= maxKey) - continue; - result.insert(*indexed_t); - } - is.ignore(LINESIZE, '\n'); - } - return result; -} - -/* ************************************************************************* */ -istream &operator>>(istream &is, boost::optional &indexed) { - string tag; - is >> tag; - indexed = parseVertexPose(is, tag); - return is; -} - -map parse2DPoses(const string &filename, Key maxKey) { - return parseIntoMap(filename, maxKey); -} - -/* ************************************************************************* */ -istream &operator>>(istream &is, boost::optional &indexed) { - string tag; - is >> tag; - indexed = parseVertexLandmark(is, tag); - return is; -} - -map parse2DLandmarks(const string &filename, Key maxKey) { - return parseIntoMap(filename, maxKey); -} - -/* ************************************************************************* */ -// Parse a file by first parsing the `Parsed` type and then processing it with -// the supplied `process` function. Result is put in a vector evaluates to true. -// Requires: a stream >> operator for boost::optional -template -static vector -parseToVector(const string &filename, - const std::function process) { - ifstream is(filename.c_str()); - if (!is) - throw invalid_argument("parse: can not find file " + filename); - - vector result; - string tag; - while (!is.eof()) { - boost::optional parsed; - is >> parsed; - if (parsed) { - Output factor = process(*parsed); // can return nullptr - if (factor) { - result.push_back(factor); - } - } - is.ignore(LINESIZE, '\n'); - } - return result; -} - /* ************************************************************************* */ boost::optional parseEdge(istream &is, const string &tag) { if ((tag == "EDGE2") || (tag == "EDGE") || (tag == "EDGE_SE2") || @@ -315,29 +297,74 @@ boost::optional parseEdge(istream &is, const string &tag) { } /* ************************************************************************* */ -struct Measurement2 { - Key id1, id2; - Pose2 pose; - Vector6 v; // 6 noise model parameters for edge -}; - -istream &operator>>(istream &is, boost::optional &edge) { - string tag; - is >> tag; - if ((tag == "EDGE2") || (tag == "EDGE") || (tag == "EDGE_SE2") || - (tag == "ODOMETRY")) { - Key id1, id2; - double x, y, yaw; - Vector6 v; - is >> id1 >> id2 >> x >> y >> yaw >> // - v(0) >> v(1) >> v(2) >> v(3) >> v(4) >> v(5); - edge.reset({id1, id2, Pose2(x, y, yaw), v}); - } - return is; -} +// Measurement parsers are implemented as a functor, as they has several options +// to filter and create the measurement model. +template struct ParseMeasurement; /* ************************************************************************* */ -// Create a sampler +// Converting from Measurement to BetweenFactor is generic +template struct ParseFactor : ParseMeasurement { + ParseFactor(const ParseMeasurement &parent) + : ParseMeasurement(parent) {} + + // We parse a measurement then convert + typename boost::optional::shared_ptr> + operator()(istream &is, const string &tag) { + if (auto m = ParseMeasurement::operator()(is, tag)) + return boost::make_shared>( + m->key1(), m->key2(), m->measured(), m->noiseModel()); + else + return boost::none; + } +}; + +/* ************************************************************************* */ +// Pose2 measurement parser +template <> struct ParseMeasurement { + // The arguments + boost::shared_ptr sampler; + Key maxKey; + + // For noise model creation + bool smart; + NoiseFormat noiseFormat; + KernelFunctionType kernelFunctionType; + + // If this is not null, will use instead of parsed model: + SharedNoiseModel model; + + // The actual parser + boost::optional> operator()(istream &is, + const string &tag) { + auto edge = parseEdge(is, tag); + if (!edge) + return boost::none; + + // parse noise model + Vector6 v; + is >> v(0) >> v(1) >> v(2) >> v(3) >> v(4) >> v(5); + + // optional filter + Key id1, id2; + tie(id1, id2) = edge->first; + if (maxKey && (id1 >= maxKey || id2 >= maxKey)) + return boost::none; + + // Get pose and optionally add noise + Pose2 &pose = edge->second; + if (sampler) + pose = pose.retract(sampler->sample()); + + // emplace measurement + auto modelFromFile = + createNoiseModel(v, smart, noiseFormat, kernelFunctionType); + return BinaryMeasurement(id1, id2, pose, + model ? model : modelFromFile); + } +}; + +/* ************************************************************************* */ +// Create a sampler to corrupt a measurement boost::shared_ptr createSampler(const SharedNoiseModel &model) { auto noise = boost::dynamic_pointer_cast(model); if (!noise) @@ -347,81 +374,75 @@ boost::shared_ptr createSampler(const SharedNoiseModel &model) { } /* ************************************************************************* */ -// Small functor to process the edge into a BetweenFactor::shared_ptr -struct ProcessPose2 { - // The arguments - Key maxKey; - SharedNoiseModel model; - boost::shared_ptr sampler; - - // Arguments for parsing noise model - bool smart; - NoiseFormat noiseFormat; - KernelFunctionType kernelFunctionType; - - ProcessPose2(Key maxKey = 0, SharedNoiseModel model = nullptr, - boost::shared_ptr sampler = nullptr, bool smart = true, - NoiseFormat noiseFormat = NoiseFormatAUTO, - KernelFunctionType kernelFunctionType = KernelFunctionTypeNONE) - : maxKey(maxKey), model(model), sampler(sampler), smart(smart), - noiseFormat(noiseFormat), kernelFunctionType(kernelFunctionType) {} - - // The actual function - BetweenFactor::shared_ptr operator()(const Measurement2 &edge) { - // optional filter - if (maxKey && (edge.id1 >= maxKey || edge.id2 >= maxKey)) - return nullptr; - - // Get pose and optionally add noise - Pose2 T12 = edge.pose; - if (sampler) - T12 = T12.retract(sampler->sample()); - - // Create factor - // If model is nullptr we use the model from the file - return boost::make_shared>( - edge.id1, edge.id2, T12, - model - ? model - : createNoiseModel(edge.v, smart, noiseFormat, kernelFunctionType)); - } -}; - -/* ************************************************************************* */ -BetweenFactorPose2s -parse2DFactors(const string &filename, - const noiseModel::Diagonal::shared_ptr &corruptingNoise, - Key maxKey) { - ProcessPose2 process(maxKey, nullptr, - corruptingNoise ? createSampler(corruptingNoise) - : nullptr); - - return parseToVector::shared_ptr>(filename, - process); +// Implementation of parseMeasurements for Pose2 +template <> +std::vector> +parseMeasurements(const std::string &filename, + const noiseModel::Diagonal::shared_ptr &model, Key maxKey) { + ParseMeasurement parse{model ? createSampler(model) : nullptr, maxKey, + true, NoiseFormatAUTO, KernelFunctionTypeNONE}; + return parseToVector>(filename, parse); } /* ************************************************************************* */ -static void parseOthers(const string &filename, Key maxKey, - NonlinearFactorGraph::shared_ptr graph, - Values::shared_ptr initial) { - // Do a pass to get other types of measurements - ifstream is(filename.c_str()); - if (!is) - throw invalid_argument("load2D: can not find file " + filename); +// Implementation of parseMeasurements for Rot2, which converts from Pose2 - Key id1, id2; - while (!is.eof()) { - string tag; - if (!(is >> tag)) - break; +// Extract Rot2 measurement from Pose2 measurement +static BinaryMeasurement convert(const BinaryMeasurement &p) { + auto gaussian = + boost::dynamic_pointer_cast(p.noiseModel()); + if (!gaussian) + throw std::invalid_argument( + "parseMeasurements can only convert Pose2 measurements " + "with Gaussian noise models."); + const Matrix3 M = gaussian->covariance(); + return BinaryMeasurement(p.key1(), p.key2(), p.measured().rotation(), + noiseModel::Isotropic::Variance(1, M(2, 2))); +} - // Parse measurements - bool haveLandmark = false; +template <> +std::vector> +parseMeasurements(const std::string &filename, + const noiseModel::Diagonal::shared_ptr &model, Key maxKey) { + auto poses = parseMeasurements(filename, model, maxKey); + std::vector> result; + result.reserve(poses.size()); + for (const auto &p : poses) + result.push_back(convert(p)); + return result; +} + +/* ************************************************************************* */ +// Implementation of parseFactors for Pose2 +template <> +std::vector::shared_ptr> +parseFactors(const std::string &filename, + const noiseModel::Diagonal::shared_ptr &model, Key maxKey) { + ParseFactor parse({model ? createSampler(model) : nullptr, maxKey, + true, NoiseFormatAUTO, KernelFunctionTypeNONE, + nullptr}); + return parseToVector::shared_ptr>(filename, parse); +} + +/* ************************************************************************* */ +using BearingRange2D = BearingRange; + +template <> struct ParseMeasurement { + // arguments + Key maxKey; + + // The actual parser + boost::optional> + operator()(istream &is, const string &tag) { + if (tag != "BR" && tag != "LANDMARK") + return boost::none; + + Key id1, id2; + is >> id1 >> id2; double bearing, range, bearing_std, range_std; - // A bearing-range measurement if (tag == "BR") { - is >> id1 >> id2 >> bearing >> range >> bearing_std >> range_std; + is >> bearing >> range >> bearing_std >> range_std; } // A landmark measurement, converted to bearing-range @@ -429,7 +450,7 @@ static void parseOthers(const string &filename, Key maxKey, double lmx, lmy; double v1, v2, v3; - is >> id1 >> id2 >> lmx >> lmy >> v1 >> v2 >> v3; + is >> lmx >> lmy >> v1 >> v2 >> v3; // Convert x,y to bearing,range bearing = atan2(lmy, lmx); @@ -442,90 +463,93 @@ static void parseOthers(const string &filename, Key maxKey, bearing_std = sqrt(v1 / 10.0); range_std = sqrt(v1); } else { + // TODO(frank): we are ignoring the non-uniform covariance bearing_std = 1; range_std = 1; - if (!haveLandmark) { - cout << "Warning: load2D is a very simple dataset loader and is " - "ignoring the\n" - "non-uniform covariance on LANDMARK measurements in this " - "file." - << endl; - haveLandmark = true; - } } } - // Do some common stuff for bearing-range measurements - if (tag == "LANDMARK" || tag == "BR") { + // optional filter + if (maxKey && id1 >= maxKey) + return boost::none; - // optional filter - if (maxKey && id1 >= maxKey) - continue; + // Create noise model + auto measurementNoise = noiseModel::Diagonal::Sigmas( + (Vector(2) << bearing_std, range_std).finished()); - // Create noise model - noiseModel::Diagonal::shared_ptr measurementNoise = - noiseModel::Diagonal::Sigmas( - (Vector(2) << bearing_std, range_std).finished()); - - // Add to graph - *graph += BearingRangeFactor(id1, L(id2), bearing, range, - measurementNoise); - - // Insert poses or points if they do not exist yet - if (!initial->exists(id1)) - initial->insert(id1, Pose2()); - if (!initial->exists(L(id2))) { - Pose2 pose = initial->at(id1); - Point2 local(cos(bearing) * range, sin(bearing) * range); - Point2 global = pose.transformFrom(local); - initial->insert(L(id2), global); - } - } - is.ignore(LINESIZE, '\n'); + return BinaryMeasurement( + id1, L(id2), BearingRange2D(bearing, range), measurementNoise); } -} +}; /* ************************************************************************* */ -GraphAndValues load2D(const string &filename, SharedNoiseModel model, Key maxKey, - bool addNoise, bool smart, NoiseFormat noiseFormat, +GraphAndValues load2D(const string &filename, SharedNoiseModel model, + Key maxKey, bool addNoise, bool smart, + NoiseFormat noiseFormat, KernelFunctionType kernelFunctionType) { - Values::shared_ptr initial(new Values); + auto graph = boost::make_shared(); + auto initial = boost::make_shared(); - const auto poses = parse2DPoses(filename, maxKey); + // TODO(frank): do a single pass + const auto poses = parseVariables(filename, maxKey); for (const auto &key_pose : poses) { initial->insert(key_pose.first, key_pose.second); } - const auto landmarks = parse2DLandmarks(filename, maxKey); + + const auto landmarks = parseVariables(filename, maxKey); for (const auto &key_landmark : landmarks) { - initial->insert(key_landmark.first, key_landmark.second); + initial->insert(L(key_landmark.first), key_landmark.second); } - // Parse the pose constraints - ProcessPose2 process(maxKey, model, addNoise ? createSampler(model) : nullptr, - smart, noiseFormat, kernelFunctionType); - auto factors = parseToVector::shared_ptr>( - filename, process); + // Create parser for Pose2 and bearing/range + ParseFactor parseBetweenFactor( + {addNoise ? createSampler(model) : nullptr, maxKey, smart, noiseFormat, + kernelFunctionType, model}); + ParseMeasurement parseBearingRange{maxKey}; - // Add factors into the graph and add poses if necessary - auto graph = boost::make_shared(); - for (const auto &f : factors) { - graph->push_back(f); + Parser parse = [&](istream &is, const string &tag) { + if (auto f = parseBetweenFactor(is, tag)) { + graph->push_back(*f); - // Insert vertices if pure odometry file - Key id1 = f->key1(), id2 = f->key2(); - if (!initial->exists(id1)) - initial->insert(id1, Pose2()); - if (!initial->exists(id2)) - initial->insert(id2, initial->at(id1) * f->measured()); - } + // Insert vertices if pure odometry file + Key key1 = (*f)->key1(), key2 = (*f)->key2(); + if (!initial->exists(key1)) + initial->insert(key1, Pose2()); + if (!initial->exists(key2)) + initial->insert(key2, initial->at(key1) * (*f)->measured()); + } else if (auto m = parseBearingRange(is, tag)) { + Key key1 = m->key1(), key2 = m->key2(); + BearingRange2D br = m->measured(); + graph->emplace_shared>(key1, key2, br, + m->noiseModel()); - // Do a pass to parse landmarks and bearing-range measurements - parseOthers(filename, maxKey, graph, initial); + // Insert poses or points if they do not exist yet + if (!initial->exists(key1)) + initial->insert(key1, Pose2()); + if (!initial->exists(key2)) { + Pose2 pose = initial->at(key1); + Point2 local = br.bearing() * Point2(br.range(), 0); + Point2 global = pose.transformFrom(local); + initial->insert(key2, global); + } + } + return 0; + }; + + parseLines(filename, parse); return make_pair(graph, initial); } +/* ************************************************************************* */ +GraphAndValues load2D(pair dataset, Key maxKey, + bool addNoise, bool smart, NoiseFormat noiseFormat, + KernelFunctionType kernelFunctionType) { + return load2D(dataset.first, dataset.second, maxKey, addNoise, smart, + noiseFormat, kernelFunctionType); +} + /* ************************************************************************* */ GraphAndValues load2D_robust(const string &filename, noiseModel::Base::shared_ptr &model, Key maxKey) { @@ -540,7 +564,7 @@ void save2D(const NonlinearFactorGraph &graph, const Values &config, fstream stream(filename.c_str(), fstream::out); // save poses - for (const Values::ConstKeyValuePair &key_value : config) { + for (const Values::ConstKeyValuePair key_value : config) { const Pose2 &pose = key_value.value.cast(); stream << "VERTEX2 " << key_value.key << " " << pose.x() << " " << pose.y() << " " << pose.theta() << endl; @@ -586,7 +610,7 @@ void writeG2o(const NonlinearFactorGraph &graph, const Values &estimate, fstream stream(filename.c_str(), fstream::out); // save 2D poses - for (const auto &key_value : estimate) { + for (const auto key_value : estimate) { auto p = dynamic_cast *>(&key_value.value); if (!p) continue; @@ -596,7 +620,7 @@ void writeG2o(const NonlinearFactorGraph &graph, const Values &estimate, } // save 3D poses - for (const auto &key_value : estimate) { + for (const auto key_value : estimate) { auto p = dynamic_cast *>(&key_value.value); if (!p) continue; @@ -609,7 +633,7 @@ void writeG2o(const NonlinearFactorGraph &graph, const Values &estimate, } // save 2D landmarks - for (const auto &key_value : estimate) { + for (const auto key_value : estimate) { auto p = dynamic_cast *>(&key_value.value); if (!p) continue; @@ -619,7 +643,7 @@ void writeG2o(const NonlinearFactorGraph &graph, const Values &estimate, } // save 3D landmarks - for (const auto &key_value : estimate) { + for (const auto key_value : estimate) { auto p = dynamic_cast *>(&key_value.value); if (!p) continue; @@ -709,44 +733,46 @@ istream &operator>>(istream &is, Rot3 &R) { } /* ************************************************************************* */ -istream &operator>>(istream &is, boost::optional> &indexed) { - string tag; - is >> tag; +boost::optional> parseVertexPose3(istream &is, + const string &tag) { if (tag == "VERTEX3") { Key id; double x, y, z; Rot3 R; is >> id >> x >> y >> z >> R; - indexed.reset({id, Pose3(R, {x, y, z})}); + return make_pair(id, Pose3(R, {x, y, z})); } else if (tag == "VERTEX_SE3:QUAT") { Key id; double x, y, z; Quaternion q; is >> id >> x >> y >> z >> q; - indexed.reset({id, Pose3(q, {x, y, z})}); - } - return is; + return make_pair(id, Pose3(q, {x, y, z})); + } else + return boost::none; } -map parse3DPoses(const string &filename, Key maxKey) { - return parseIntoMap(filename, maxKey); +template <> +std::map parseVariables(const std::string &filename, + Key maxKey) { + return parseToMap(filename, parseVertexPose3, maxKey); } /* ************************************************************************* */ -istream &operator>>(istream &is, boost::optional> &indexed) { - string tag; - is >> tag; +boost::optional> parseVertexPoint3(istream &is, + const string &tag) { if (tag == "VERTEX_TRACKXYZ") { Key id; double x, y, z; is >> id >> x >> y >> z; - indexed.reset({id, Point3(x, y, z)}); - } - return is; + return make_pair(id, Point3(x, y, z)); + } else + return boost::none; } -map parse3DLandmarks(const string &filename, Key maxKey) { - return parseIntoMap(filename, maxKey); +template <> +std::map parseVariables(const std::string &filename, + Key maxKey) { + return parseToMap(filename, parseVertexPoint3, maxKey); } /* ************************************************************************* */ @@ -761,97 +787,126 @@ istream &operator>>(istream &is, Matrix6 &m) { } /* ************************************************************************* */ -struct Measurement3 { - Key id1, id2; - Pose3 pose; - SharedNoiseModel model; +// Pose3 measurement parser +template <> struct ParseMeasurement { + // The arguments + boost::shared_ptr sampler; + Key maxKey; + + // The actual parser + boost::optional> operator()(istream &is, + const string &tag) { + if (tag != "EDGE3" && tag != "EDGE_SE3:QUAT") + return boost::none; + + // parse ids and optionally filter + Key id1, id2; + is >> id1 >> id2; + if (maxKey && (id1 >= maxKey || id2 >= maxKey)) + return boost::none; + + Matrix6 m; + if (tag == "EDGE3") { + double x, y, z; + Rot3 R; + is >> x >> y >> z >> R >> m; + Pose3 T12(R, {x, y, z}); + // optionally add noise + if (sampler) + T12 = T12.retract(sampler->sample()); + + return BinaryMeasurement(id1, id2, T12, + noiseModel::Gaussian::Information(m)); + } else if (tag == "EDGE_SE3:QUAT") { + double x, y, z; + Quaternion q; + is >> x >> y >> z >> q >> m; + + Pose3 T12(q, {x, y, z}); + // optionally add noise + if (sampler) + T12 = T12.retract(sampler->sample()); + + // EDGE_SE3:QUAT stores covariance in t,R order, unlike GTSAM: + Matrix6 mgtsam; + mgtsam.block<3, 3>(0, 0) = m.block<3, 3>(3, 3); // cov rotation + mgtsam.block<3, 3>(3, 3) = m.block<3, 3>(0, 0); // cov translation + mgtsam.block<3, 3>(0, 3) = m.block<3, 3>(0, 3); // off diagonal + mgtsam.block<3, 3>(3, 0) = m.block<3, 3>(3, 0); // off diagonal + SharedNoiseModel model = noiseModel::Gaussian::Information(mgtsam); + + return BinaryMeasurement( + id1, id2, T12, noiseModel::Gaussian::Information(mgtsam)); + } else + return boost::none; + } }; -istream &operator>>(istream &is, boost::optional &edge) { - string tag; - is >> tag; - Matrix6 m; - if (tag == "EDGE3") { - Key id1, id2; - double x, y, z; - Rot3 R; - is >> id1 >> id2 >> x >> y >> z >> R >> m; - edge.reset( - {id1, id2, Pose3(R, {x, y, z}), noiseModel::Gaussian::Information(m)}); - } - if (tag == "EDGE_SE3:QUAT") { - Key id1, id2; - double x, y, z; - Quaternion q; - is >> id1 >> id2 >> x >> y >> z >> q >> m; - - // EDGE_SE3:QUAT stores covariance in t,R order, unlike GTSAM: - Matrix6 mgtsam; - mgtsam.block<3, 3>(0, 0) = m.block<3, 3>(3, 3); // cov rotation - mgtsam.block<3, 3>(3, 3) = m.block<3, 3>(0, 0); // cov translation - mgtsam.block<3, 3>(0, 3) = m.block<3, 3>(0, 3); // off diagonal - mgtsam.block<3, 3>(3, 0) = m.block<3, 3>(3, 0); // off diagonal - SharedNoiseModel model = noiseModel::Gaussian::Information(mgtsam); - - edge.reset({id1, id2, Pose3(q, {x, y, z}), - noiseModel::Gaussian::Information(mgtsam)}); - } - return is; +/* ************************************************************************* */ +// Implementation of parseMeasurements for Pose3 +template <> +std::vector> +parseMeasurements(const std::string &filename, + const noiseModel::Diagonal::shared_ptr &model, Key maxKey) { + ParseMeasurement parse{model ? createSampler(model) : nullptr, maxKey}; + return parseToVector>(filename, parse); } /* ************************************************************************* */ -// Small functor to process the edge into a BetweenFactor::shared_ptr -struct ProcessPose3 { - // The arguments - Key maxKey = 0; - SharedNoiseModel model; - boost::shared_ptr sampler; +// Implementation of parseMeasurements for Rot3, which converts from Pose3 - // The actual function - BetweenFactor::shared_ptr operator()(const Measurement3 &edge) { - // optional filter - if (maxKey && (edge.id1 >= maxKey || edge.id2 >= maxKey)) - return nullptr; +// Extract Rot3 measurement from Pose3 measurement +static BinaryMeasurement convert(const BinaryMeasurement &p) { + auto gaussian = + boost::dynamic_pointer_cast(p.noiseModel()); + if (!gaussian) + throw std::invalid_argument( + "parseMeasurements can only convert Pose3 measurements " + "with Gaussian noise models."); + const Matrix6 M = gaussian->covariance(); + return BinaryMeasurement( + p.key1(), p.key2(), p.measured().rotation(), + noiseModel::Gaussian::Covariance(M.block<3, 3>(3, 3), true)); +} - // Get pose and optionally add noise - Pose3 T12 = edge.pose; - if (sampler) - T12 = T12.retract(sampler->sample()); - - // Create factor - return boost::make_shared>(edge.id1, edge.id2, T12, - edge.model); - } -}; +template <> +std::vector> +parseMeasurements(const std::string &filename, + const noiseModel::Diagonal::shared_ptr &model, Key maxKey) { + auto poses = parseMeasurements(filename, model, maxKey); + std::vector> result; + result.reserve(poses.size()); + for (const auto &p : poses) + result.push_back(convert(p)); + return result; +} /* ************************************************************************* */ -BetweenFactorPose3s -parse3DFactors(const string &filename, - const noiseModel::Diagonal::shared_ptr &corruptingNoise, - Key maxKey) { - ProcessPose3 process; - process.maxKey = maxKey; - if (corruptingNoise) { - process.sampler = createSampler(corruptingNoise); - } - return parseToVector::shared_ptr>(filename, - process); +// Implementation of parseFactors for Pose3 +template <> +std::vector::shared_ptr> +parseFactors(const std::string &filename, + const noiseModel::Diagonal::shared_ptr &model, Key maxKey) { + ParseFactor parse({model ? createSampler(model) : nullptr, maxKey}); + return parseToVector::shared_ptr>(filename, parse); } /* ************************************************************************* */ GraphAndValues load3D(const string &filename) { - const auto factors = parse3DFactors(filename); - NonlinearFactorGraph::shared_ptr graph(new NonlinearFactorGraph); + auto graph = boost::make_shared(); + auto initial = boost::make_shared(); + + // TODO(frank): do a single pass + const auto factors = parseFactors(filename); for (const auto &factor : factors) { graph->push_back(factor); } - Values::shared_ptr initial(new Values); - - const auto poses = parse3DPoses(filename); + const auto poses = parseVariables(filename); for (const auto &key_pose : poses) { initial->insert(key_pose.first, key_pose.second); } + const auto landmarks = parse3DLandmarks(filename); for (const auto &key_landmark : landmarks) { initial->insert(key_landmark.first, key_landmark.second); @@ -1200,4 +1255,20 @@ Values initialCamerasAndPointsEstimate(const SfmData &db) { return initial; } +#ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V41 +std::map parse3DPoses(const std::string &filename, Key maxKey) { + return parseVariables(filename, maxKey); +} + +std::map parse3DLandmarks(const std::string &filename, + Key maxKey) { + return parseVariables(filename, maxKey); +} + +BetweenFactorPose3s +parse3DFactors(const std::string &filename, + const noiseModel::Diagonal::shared_ptr &model, Key maxKey) { + return parseFactors(filename, model, maxKey); +} +#endif } // namespace gtsam diff --git a/gtsam/slam/dataset.h b/gtsam/slam/dataset.h index 61eb9256e..38ddfd1dc 100644 --- a/gtsam/slam/dataset.h +++ b/gtsam/slam/dataset.h @@ -20,6 +20,7 @@ #pragma once +#include #include #include #include @@ -72,6 +73,34 @@ enum KernelFunctionType { KernelFunctionTypeNONE, KernelFunctionTypeHUBER, KernelFunctionTypeTUKEY }; +/** + * Parse variables in 2D g2o graph file into a map. + * Instantiated in .cpp T equal to Pose2, Pose3 + */ +template +GTSAM_EXPORT std::map parseVariables(const std::string &filename, + Key maxKey = 0); + +/** + * Parse edges in 2D g2o graph file into a set of binary measuremnts. + * Instantiated in .cpp for T equal to Pose2, Pose3 + */ +template +GTSAM_EXPORT std::vector> +parseMeasurements(const std::string &filename, + const noiseModel::Diagonal::shared_ptr &model = nullptr, + Key maxKey = 0); + +/** + * Parse edges in 2D g2o graph file into a set of BetweenFactors. + * Instantiated in .cpp T equal to Pose2, Pose3 + */ +template +GTSAM_EXPORT std::vector::shared_ptr> +parseFactors(const std::string &filename, + const noiseModel::Diagonal::shared_ptr &model = nullptr, + Key maxKey = 0); + /// Return type for auxiliary functions typedef std::pair IndexedPose; typedef std::pair IndexedLandmark; @@ -90,7 +119,6 @@ GTSAM_EXPORT boost::optional parseVertexPose(std::istream& is, * @param is input stream * @param tag string parsed from input stream, will only parse if vertex type */ - GTSAM_EXPORT boost::optional parseVertexLandmark(std::istream& is, const std::string& tag); @@ -102,23 +130,6 @@ GTSAM_EXPORT boost::optional parseVertexLandmark(std::istream& GTSAM_EXPORT boost::optional parseEdge(std::istream& is, const std::string& tag); -using BetweenFactorPose2s = - std::vector::shared_ptr>; - -/// Parse edges in 2D g2o graph file into a set of BetweenFactors. -GTSAM_EXPORT BetweenFactorPose2s parse2DFactors( - const std::string &filename, - const noiseModel::Diagonal::shared_ptr &corruptingNoise = nullptr, - Key maxKey = 0); - -/// Parse vertices in 2D g2o graph file into a map of Pose2s. -GTSAM_EXPORT std::map parse2DPoses(const std::string &filename, - Key maxKey = 0); - -/// Parse landmarks in 2D g2o graph file into a map of Point2s. -GTSAM_EXPORT std::map parse2DLandmarks(const string &filename, - Key maxKey = 0); - /// Return type for load functions using GraphAndValues = std::pair; @@ -183,21 +194,6 @@ GTSAM_EXPORT GraphAndValues readG2o(const std::string& g2oFile, const bool is3D GTSAM_EXPORT void writeG2o(const NonlinearFactorGraph& graph, const Values& estimate, const std::string& filename); -/// Parse edges in 3D TORO graph file into a set of BetweenFactors. -using BetweenFactorPose3s = std::vector::shared_ptr>; -GTSAM_EXPORT BetweenFactorPose3s parse3DFactors( - const std::string &filename, - const noiseModel::Diagonal::shared_ptr &corruptingNoise = nullptr, - Key maxKey = 0); - -/// Parse vertices in 3D TORO/g2o graph file into a map of Pose3s. -GTSAM_EXPORT std::map parse3DPoses(const std::string &filename, - Key maxKey = 0); - -/// Parse landmarks in 3D g2o graph file into a map of Point3s. -GTSAM_EXPORT std::map parse3DLandmarks(const std::string &filename, - Key maxKey = 0); - /// Load TORO 3D Graph GTSAM_EXPORT GraphAndValues load3D(const std::string& filename); @@ -335,14 +331,21 @@ GTSAM_EXPORT Values initialCamerasEstimate(const SfmData& db); GTSAM_EXPORT Values initialCamerasAndPointsEstimate(const SfmData& db); #ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V41 -/** - * Parse TORO/G2O vertex "id x y yaw" - * @param is input stream - * @param tag string parsed from input stream, will only parse if vertex type - */ inline boost::optional parseVertex(std::istream &is, const std::string &tag) { return parseVertexPose(is, tag); } + +GTSAM_EXPORT std::map parse3DPoses(const std::string &filename, + Key maxKey = 0); + +GTSAM_EXPORT std::map parse3DLandmarks(const std::string &filename, + Key maxKey = 0); + +using BetweenFactorPose3s = std::vector::shared_ptr>; +GTSAM_EXPORT BetweenFactorPose3s parse3DFactors( + const std::string &filename, + const noiseModel::Diagonal::shared_ptr &model = nullptr, Key maxKey = 0); + #endif } // namespace gtsam diff --git a/gtsam/slam/tests/testDataset.cpp b/gtsam/slam/tests/testDataset.cpp index bc65dc351..864f42162 100644 --- a/gtsam/slam/tests/testDataset.cpp +++ b/gtsam/slam/tests/testDataset.cpp @@ -104,8 +104,16 @@ TEST(dataSet, load2D) { boost::dynamic_pointer_cast>(graph->at(0)); EXPECT(assert_equal(expected, *actual)); - // Check factor parsing - const auto actualFactors = parse2DFactors(filename); + // Check binary measurements, Pose2 + auto measurements = parseMeasurements(filename, nullptr, 5); + EXPECT_LONGS_EQUAL(4, measurements.size()); + + // Check binary measurements, Rot2 + auto measurements2 = parseMeasurements(filename); + EXPECT_LONGS_EQUAL(300, measurements2.size()); + + // // Check factor parsing + const auto actualFactors = parseFactors(filename); for (size_t i : {0, 1, 2, 3, 4, 5}) { EXPECT(assert_equal( *boost::dynamic_pointer_cast>(graph->at(i)), @@ -113,13 +121,13 @@ TEST(dataSet, load2D) { } // Check pose parsing - const auto actualPoses = parse2DPoses(filename); + const auto actualPoses = parseVariables(filename); for (size_t j : {0, 1, 2, 3, 4}) { EXPECT(assert_equal(initial->at(j), actualPoses.at(j), 1e-5)); } // Check landmark parsing - const auto actualLandmarks = parse2DLandmarks(filename); + const auto actualLandmarks = parseVariables(filename); EXPECT_LONGS_EQUAL(0, actualLandmarks.size()); } @@ -202,7 +210,7 @@ TEST(dataSet, readG2o3D) { } // Check factor parsing - const auto actualFactors = parse3DFactors(g2oFile); + const auto actualFactors = parseFactors(g2oFile); for (size_t i : {0, 1, 2, 3, 4, 5}) { EXPECT(assert_equal( *boost::dynamic_pointer_cast>(expectedGraph[i]), @@ -210,7 +218,7 @@ TEST(dataSet, readG2o3D) { } // Check pose parsing - const auto actualPoses = parse3DPoses(g2oFile); + const auto actualPoses = parseVariables(g2oFile); for (size_t j : {0, 1, 2, 3, 4}) { EXPECT(assert_equal(poses[j], actualPoses.at(j), 1e-5)); } @@ -277,7 +285,7 @@ TEST(dataSet, readG2oCheckDeterminants) { const string g2oFile = findExampleDataFile("toyExample.g2o"); // Check determinants in factors - auto factors = parse3DFactors(g2oFile); + auto factors = parseFactors(g2oFile); EXPECT_LONGS_EQUAL(6, factors.size()); for (const auto& factor : factors) { const Rot3 R = factor->measured().rotation(); @@ -285,7 +293,7 @@ TEST(dataSet, readG2oCheckDeterminants) { } // Check determinants in initial values - const map poses = parse3DPoses(g2oFile); + const map poses = parseVariables(g2oFile); EXPECT_LONGS_EQUAL(5, poses.size()); for (const auto& key_value : poses) { const Rot3 R = key_value.second.rotation(); @@ -300,7 +308,7 @@ TEST(dataSet, readG2oLandmarks) { const string g2oFile = findExampleDataFile("example_with_vertices.g2o"); // Check number of poses and landmarks. Should be 8 each. - const map poses = parse3DPoses(g2oFile); + const map poses = parseVariables(g2oFile); EXPECT_LONGS_EQUAL(8, poses.size()); const map landmarks = parse3DLandmarks(g2oFile); EXPECT_LONGS_EQUAL(8, landmarks.size()); diff --git a/timing/timeFrobeniusFactor.cpp b/timing/timeFrobeniusFactor.cpp index 8bdda968f..44bb084cc 100644 --- a/timing/timeFrobeniusFactor.cpp +++ b/timing/timeFrobeniusFactor.cpp @@ -58,7 +58,7 @@ int main(int argc, char* argv[]) { // Read G2O file const auto factors = parse3DFactors(g2oFile); - const auto poses = parse3DPoses(g2oFile); + const auto poses = parseVariables(g2oFile); // Build graph NonlinearFactorGraph graph; From de7b56a491fde5ec3ed1536b4b8270787e97b2a5 Mon Sep 17 00:00:00 2001 From: Frank Dellaert Date: Fri, 14 Aug 2020 22:02:17 -0400 Subject: [PATCH 350/869] Turn off gcc build as it times out every time --- .travis.yml | 10 +++++----- 1 file changed, 5 insertions(+), 5 deletions(-) diff --git a/.travis.yml b/.travis.yml index 986e86cc2..d6c6cb156 100644 --- a/.travis.yml +++ b/.travis.yml @@ -112,11 +112,11 @@ jobs: compiler: gcc env: CMAKE_BUILD_TYPE=Release script: bash .travis.sh -t - - stage: test - os: linux - compiler: gcc - env: CMAKE_BUILD_TYPE=Debug GTSAM_BUILD_UNSTABLE=OFF - script: bash .travis.sh -t + # - stage: test + # os: linux + # compiler: gcc + # env: CMAKE_BUILD_TYPE=Debug GTSAM_BUILD_UNSTABLE=OFF + # script: bash .travis.sh -t - stage: test os: linux compiler: clang From 97537f2a36b85f62c46dc04bcd4ed23ec25c8b98 Mon Sep 17 00:00:00 2001 From: Frank Dellaert Date: Sat, 15 Aug 2020 08:06:15 -0400 Subject: [PATCH 351/869] Avoid clang warnings about double-brace initialization --- gtsam/sam/BearingRangeFactor.h | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/gtsam/sam/BearingRangeFactor.h b/gtsam/sam/BearingRangeFactor.h index b8e231915..482dbb974 100644 --- a/gtsam/sam/BearingRangeFactor.h +++ b/gtsam/sam/BearingRangeFactor.h @@ -48,15 +48,15 @@ class BearingRangeFactor /// Construct from BearingRange instance BearingRangeFactor(Key key1, Key key2, const T &bearingRange, const SharedNoiseModel &model) - : Base({key1, key2}, model, T(bearingRange)) { - this->initialize(expression({key1, key2})); + : Base({{key1, key2}}, model, T(bearingRange)) { + this->initialize(expression({{key1, key2}})); } /// Construct from separate bearing and range BearingRangeFactor(Key key1, Key key2, const B &measuredBearing, const R &measuredRange, const SharedNoiseModel &model) - : Base({key1, key2}, model, T(measuredBearing, measuredRange)) { - this->initialize(expression({key1, key2})); + : Base({{key1, key2}}, model, T(measuredBearing, measuredRange)) { + this->initialize(expression({{key1, key2}})); } virtual ~BearingRangeFactor() {} From fc085626416b34c94379b9d76669a04746c87f56 Mon Sep 17 00:00:00 2001 From: Frank Dellaert Date: Sat, 15 Aug 2020 08:06:37 -0400 Subject: [PATCH 352/869] Hunted down deprecated use of parse3DLandmarks --- gtsam/slam/dataset.cpp | 2 +- gtsam/slam/tests/testDataset.cpp | 6 +++--- timing/timeFrobeniusFactor.cpp | 12 ++++++------ 3 files changed, 10 insertions(+), 10 deletions(-) diff --git a/gtsam/slam/dataset.cpp b/gtsam/slam/dataset.cpp index 11473d084..2aac939d9 100644 --- a/gtsam/slam/dataset.cpp +++ b/gtsam/slam/dataset.cpp @@ -907,7 +907,7 @@ GraphAndValues load3D(const string &filename) { initial->insert(key_pose.first, key_pose.second); } - const auto landmarks = parse3DLandmarks(filename); + const auto landmarks = parseVariables(filename); for (const auto &key_landmark : landmarks) { initial->insert(key_landmark.first, key_landmark.second); } diff --git a/gtsam/slam/tests/testDataset.cpp b/gtsam/slam/tests/testDataset.cpp index 864f42162..3e804b6b0 100644 --- a/gtsam/slam/tests/testDataset.cpp +++ b/gtsam/slam/tests/testDataset.cpp @@ -224,7 +224,7 @@ TEST(dataSet, readG2o3D) { } // Check landmark parsing - const auto actualLandmarks = parse3DLandmarks(g2oFile); + const auto actualLandmarks = parseVariables(g2oFile); for (size_t j : {0, 1, 2, 3, 4}) { EXPECT(assert_equal(poses[j], actualPoses.at(j), 1e-5)); } @@ -299,7 +299,7 @@ TEST(dataSet, readG2oCheckDeterminants) { const Rot3 R = key_value.second.rotation(); EXPECT_DOUBLES_EQUAL(1.0, R.matrix().determinant(), 1e-9); } - const map landmarks = parse3DLandmarks(g2oFile); + const map landmarks = parseVariables(g2oFile); EXPECT_LONGS_EQUAL(0, landmarks.size()); } @@ -310,7 +310,7 @@ TEST(dataSet, readG2oLandmarks) { // Check number of poses and landmarks. Should be 8 each. const map poses = parseVariables(g2oFile); EXPECT_LONGS_EQUAL(8, poses.size()); - const map landmarks = parse3DLandmarks(g2oFile); + const map landmarks = parseVariables(g2oFile); EXPECT_LONGS_EQUAL(8, landmarks.size()); } diff --git a/timing/timeFrobeniusFactor.cpp b/timing/timeFrobeniusFactor.cpp index 44bb084cc..c0ac28ed9 100644 --- a/timing/timeFrobeniusFactor.cpp +++ b/timing/timeFrobeniusFactor.cpp @@ -57,7 +57,7 @@ int main(int argc, char* argv[]) { } // Read G2O file - const auto factors = parse3DFactors(g2oFile); + const auto measurements = parseMeasurements(g2oFile); const auto poses = parseVariables(g2oFile); // Build graph @@ -66,12 +66,12 @@ int main(int argc, char* argv[]) { auto priorModel = noiseModel::Isotropic::Sigma(6, 10000); graph.add(PriorFactor(0, SOn::identity(4), priorModel)); auto G = boost::make_shared(SOn::VectorizedGenerators(4)); - for (const auto& factor : factors) { - const auto& keys = factor->keys(); - const auto& Tij = factor->measured(); - const auto& model = factor->noiseModel(); + for (const auto &m : measurements) { + const auto &keys = m.keys(); + const Rot3 &Tij = m.measured(); + const auto &model = m.noiseModel(); graph.emplace_shared( - keys[0], keys[1], Rot3(Tij.rotation().matrix()), 4, model, G); + keys[0], keys[1], Tij, 4, model, G); } std::mt19937 rng(42); From d0724a77bb30f3c4092a33b4a36b65a2d4da46f0 Mon Sep 17 00:00:00 2001 From: Fan Jiang Date: Wed, 29 Apr 2020 13:49:52 -0400 Subject: [PATCH 353/869] Backport GitHub Actions CI (#259) * Add GitHub Actions * Add Windows Check * Fix wrong os selection * Add XCode version * Upgrade GCC Version * Make GCC match Ubuntu name * Do not fail everyone when one failed * More checks on ccache * Do not expose GenericValue on Windows * Fix BetweenFactor for Windows * Update * Add Python CI * Typo * Add note about GENERICVALUE_VISIBILITY * Fix Windows Boost * Change substitution scheme to PowerShell * Fix the spurious error of the Point3 default constructor * Separate builds to allow easier restarts * Fix uninitialized variable usage * Change of policy, only build python stuff, mac and win on PRs * Further separate the Python tests --- .github/workflows/build-cython.yml | 96 +++++++++++++++++++++ .github/workflows/build-linux.yml | 71 +++++++++++++++ .github/workflows/build-macos.yml | 51 +++++++++++ .github/workflows/build-python.yml | 96 +++++++++++++++++++++ .github/workflows/build-windows.yml | 75 ++++++++++++++++ .travis.sh | 2 +- cython/gtsam/utils/visual_data_generator.py | 14 +-- gtsam/base/GenericValue.h | 8 ++ gtsam/slam/BetweenFactor.h | 8 ++ 9 files changed, 413 insertions(+), 8 deletions(-) create mode 100644 .github/workflows/build-cython.yml create mode 100644 .github/workflows/build-linux.yml create mode 100644 .github/workflows/build-macos.yml create mode 100644 .github/workflows/build-python.yml create mode 100644 .github/workflows/build-windows.yml diff --git a/.github/workflows/build-cython.yml b/.github/workflows/build-cython.yml new file mode 100644 index 000000000..c159a60fc --- /dev/null +++ b/.github/workflows/build-cython.yml @@ -0,0 +1,96 @@ +name: Cython CI + +on: [pull_request] + +jobs: + build: + name: ${{ matrix.name }} ${{ matrix.build_type }} ${{ matrix.python_version }} + runs-on: ${{ matrix.os }} + + env: + CTEST_OUTPUT_ON_FAILURE: ON + CTEST_PARALLEL_LEVEL: 2 + CMAKE_BUILD_TYPE: ${{ matrix.build_type }} + PYTHON_VERSION: ${{ matrix.python_version }} + WRAPPER: ${{ matrix.wrapper }} + strategy: + fail-fast: false + matrix: + # Github Actions requires a single row to be added to the build matrix. + # See https://help.github.com/en/articles/workflow-syntax-for-github-actions. + name: [ + ubuntu-18.04-gcc-5, + ubuntu-18.04-gcc-9, + ubuntu-18.04-clang-9, + macOS-10.15-xcode-11.3.1, + ] + + build_type: [Debug, Release] + python_version: [3] + wrapper: [cython] + include: + - name: ubuntu-18.04-gcc-5 + os: ubuntu-18.04 + compiler: gcc + version: "5" + + - name: ubuntu-18.04-gcc-9 + os: ubuntu-18.04 + compiler: gcc + version: "9" + + - name: ubuntu-18.04-clang-9 + os: ubuntu-18.04 + compiler: clang + version: "9" + + - name: macOS-10.15-xcode-11.3.1 + os: macOS-10.15 + compiler: xcode + version: "11.3.1" + + steps: + - name: Checkout + uses: actions/checkout@master + - name: Install (Linux) + if: runner.os == 'Linux' + run: | + # LLVM 9 is not in Bionic's repositories so we add the official LLVM repository. + if [ "${{ matrix.compiler }}" = "clang" ] && [ "${{ matrix.version }}" = "9" ]; then + sudo add-apt-repository "deb http://apt.llvm.org/bionic/ llvm-toolchain-bionic-9 main" + fi + sudo apt-get -y update + sudo apt-get -y upgrade + + sudo apt install cmake g++-9 clang-9 build-essential pkg-config libpython-dev python-numpy libboost-all-dev + + if [ "${{ matrix.compiler }}" = "gcc" ]; then + sudo apt-get install -y g++-${{ matrix.version }} g++-${{ matrix.version }}-multilib + echo "::set-env name=CC::gcc-${{ matrix.version }}" + echo "::set-env name=CXX::g++-${{ matrix.version }}" + else + sudo apt-get install -y clang-${{ matrix.version }} g++-multilib + echo "::set-env name=CC::clang-${{ matrix.version }}" + echo "::set-env name=CXX::clang++-${{ matrix.version }}" + fi + - name: Install (macOS) + if: runner.os == 'macOS' + run: | + brew install cmake ninja boost + if [ "${{ matrix.compiler }}" = "gcc" ]; then + brew install gcc@${{ matrix.version }} + echo "::set-env name=CC::gcc-${{ matrix.version }}" + echo "::set-env name=CXX::g++-${{ matrix.version }}" + else + sudo xcode-select -switch /Applications/Xcode_${{ matrix.version }}.app + echo "::set-env name=CC::clang" + echo "::set-env name=CXX::clang++" + fi + - name: Build (Linux) + if: runner.os == 'Linux' + run: | + bash .travis.python.sh + - name: Build (macOS) + if: runner.os == 'macOS' + run: | + bash .travis.python.sh \ No newline at end of file diff --git a/.github/workflows/build-linux.yml b/.github/workflows/build-linux.yml new file mode 100644 index 000000000..f58fe5f37 --- /dev/null +++ b/.github/workflows/build-linux.yml @@ -0,0 +1,71 @@ +name: CI Linux + +on: [push, pull_request] + +jobs: + build: + name: ${{ matrix.name }} ${{ matrix.build_type }} ${{ matrix.build_unstable }} + runs-on: ${{ matrix.os }} + + env: + CTEST_OUTPUT_ON_FAILURE: ON + CTEST_PARALLEL_LEVEL: 2 + CMAKE_BUILD_TYPE: ${{ matrix.build_type }} + GTSAM_BUILD_UNSTABLE: ${{ matrix.build_unstable }} + strategy: + fail-fast: false + matrix: + # Github Actions requires a single row to be added to the build matrix. + # See https://help.github.com/en/articles/workflow-syntax-for-github-actions. + name: [ + ubuntu-18.04-gcc-5, + ubuntu-18.04-gcc-9, + ubuntu-18.04-clang-9, + ] + + build_type: [Debug, Release] + build_unstable: [ON, OFF] + include: + - name: ubuntu-18.04-gcc-5 + os: ubuntu-18.04 + compiler: gcc + version: "5" + + - name: ubuntu-18.04-gcc-9 + os: ubuntu-18.04 + compiler: gcc + version: "9" + + - name: ubuntu-18.04-clang-9 + os: ubuntu-18.04 + compiler: clang + version: "9" + + steps: + - name: Checkout + uses: actions/checkout@master + - name: Install (Linux) + if: runner.os == 'Linux' + run: | + # LLVM 9 is not in Bionic's repositories so we add the official LLVM repository. + if [ "${{ matrix.compiler }}" = "clang" ] && [ "${{ matrix.version }}" = "9" ]; then + sudo add-apt-repository "deb http://apt.llvm.org/bionic/ llvm-toolchain-bionic-9 main" + fi + sudo apt-get -y update + sudo apt-get -y upgrade + + sudo apt install cmake g++-9 clang-9 build-essential pkg-config libpython-dev python-numpy libboost-all-dev + + if [ "${{ matrix.compiler }}" = "gcc" ]; then + sudo apt-get install -y g++-${{ matrix.version }} g++-${{ matrix.version }}-multilib + echo "::set-env name=CC::gcc-${{ matrix.version }}" + echo "::set-env name=CXX::g++-${{ matrix.version }}" + else + sudo apt-get install -y clang-${{ matrix.version }} g++-multilib + echo "::set-env name=CC::clang-${{ matrix.version }}" + echo "::set-env name=CXX::clang++-${{ matrix.version }}" + fi + - name: Build (Linux) + if: runner.os == 'Linux' + run: | + bash .travis.sh -t \ No newline at end of file diff --git a/.github/workflows/build-macos.yml b/.github/workflows/build-macos.yml new file mode 100644 index 000000000..2ab2e63c5 --- /dev/null +++ b/.github/workflows/build-macos.yml @@ -0,0 +1,51 @@ +name: CI macOS + +on: [pull_request] + +jobs: + build: + name: ${{ matrix.name }} ${{ matrix.build_type }} ${{ matrix.build_unstable }} + runs-on: ${{ matrix.os }} + + env: + CTEST_OUTPUT_ON_FAILURE: ON + CTEST_PARALLEL_LEVEL: 2 + CMAKE_BUILD_TYPE: ${{ matrix.build_type }} + GTSAM_BUILD_UNSTABLE: ${{ matrix.build_unstable }} + strategy: + fail-fast: false + matrix: + # Github Actions requires a single row to be added to the build matrix. + # See https://help.github.com/en/articles/workflow-syntax-for-github-actions. + name: [ + macOS-10.15-xcode-11.3.1, + ] + + build_type: [Debug, Release] + build_unstable: [ON, OFF] + include: + - name: macOS-10.15-xcode-11.3.1 + os: macOS-10.15 + compiler: xcode + version: "11.3.1" + + steps: + - name: Checkout + uses: actions/checkout@master + - name: Install (macOS) + if: runner.os == 'macOS' + run: | + brew install cmake ninja boost + if [ "${{ matrix.compiler }}" = "gcc" ]; then + brew install gcc@${{ matrix.version }} + echo "::set-env name=CC::gcc-${{ matrix.version }}" + echo "::set-env name=CXX::g++-${{ matrix.version }}" + else + sudo xcode-select -switch /Applications/Xcode_${{ matrix.version }}.app + echo "::set-env name=CC::clang" + echo "::set-env name=CXX::clang++" + fi + - name: Build (macOS) + if: runner.os == 'macOS' + run: | + bash .travis.sh -t \ No newline at end of file diff --git a/.github/workflows/build-python.yml b/.github/workflows/build-python.yml new file mode 100644 index 000000000..2dc98f05d --- /dev/null +++ b/.github/workflows/build-python.yml @@ -0,0 +1,96 @@ +name: Python CI + +on: [pull_request] + +jobs: + build: + name: ${{ matrix.name }} ${{ matrix.build_type }} ${{ matrix.python_version }} + runs-on: ${{ matrix.os }} + + env: + CTEST_OUTPUT_ON_FAILURE: ON + CTEST_PARALLEL_LEVEL: 2 + CMAKE_BUILD_TYPE: ${{ matrix.build_type }} + PYTHON_VERSION: ${{ matrix.python_version }} + WRAPPER: ${{ matrix.wrapper }} + strategy: + fail-fast: false + matrix: + # Github Actions requires a single row to be added to the build matrix. + # See https://help.github.com/en/articles/workflow-syntax-for-github-actions. + name: [ + ubuntu-18.04-gcc-5, + ubuntu-18.04-gcc-9, + ubuntu-18.04-clang-9, + macOS-10.15-xcode-11.3.1, + ] + + build_type: [Debug, Release] + python_version: [3] + wrapper: [pybind] + include: + - name: ubuntu-18.04-gcc-5 + os: ubuntu-18.04 + compiler: gcc + version: "5" + + - name: ubuntu-18.04-gcc-9 + os: ubuntu-18.04 + compiler: gcc + version: "9" + + - name: ubuntu-18.04-clang-9 + os: ubuntu-18.04 + compiler: clang + version: "9" + + - name: macOS-10.15-xcode-11.3.1 + os: macOS-10.15 + compiler: xcode + version: "11.3.1" + + steps: + - name: Checkout + uses: actions/checkout@master + - name: Install (Linux) + if: runner.os == 'Linux' + run: | + # LLVM 9 is not in Bionic's repositories so we add the official LLVM repository. + if [ "${{ matrix.compiler }}" = "clang" ] && [ "${{ matrix.version }}" = "9" ]; then + sudo add-apt-repository "deb http://apt.llvm.org/bionic/ llvm-toolchain-bionic-9 main" + fi + sudo apt-get -y update + sudo apt-get -y upgrade + + sudo apt install cmake g++-9 clang-9 build-essential pkg-config libpython-dev python-numpy libboost-all-dev + + if [ "${{ matrix.compiler }}" = "gcc" ]; then + sudo apt-get install -y g++-${{ matrix.version }} g++-${{ matrix.version }}-multilib + echo "::set-env name=CC::gcc-${{ matrix.version }}" + echo "::set-env name=CXX::g++-${{ matrix.version }}" + else + sudo apt-get install -y clang-${{ matrix.version }} g++-multilib + echo "::set-env name=CC::clang-${{ matrix.version }}" + echo "::set-env name=CXX::clang++-${{ matrix.version }}" + fi + - name: Install (macOS) + if: runner.os == 'macOS' + run: | + brew install cmake ninja boost + if [ "${{ matrix.compiler }}" = "gcc" ]; then + brew install gcc@${{ matrix.version }} + echo "::set-env name=CC::gcc-${{ matrix.version }}" + echo "::set-env name=CXX::g++-${{ matrix.version }}" + else + sudo xcode-select -switch /Applications/Xcode_${{ matrix.version }}.app + echo "::set-env name=CC::clang" + echo "::set-env name=CXX::clang++" + fi + - name: Build (Linux) + if: runner.os == 'Linux' + run: | + bash .travis.python.sh + - name: Build (macOS) + if: runner.os == 'macOS' + run: | + bash .travis.python.sh \ No newline at end of file diff --git a/.github/workflows/build-windows.yml b/.github/workflows/build-windows.yml new file mode 100644 index 000000000..516e67e1d --- /dev/null +++ b/.github/workflows/build-windows.yml @@ -0,0 +1,75 @@ +name: CI Windows + +on: [pull_request] + +jobs: + build: + name: ${{ matrix.name }} ${{ matrix.build_type }} ${{ matrix.build_unstable }} + runs-on: ${{ matrix.os }} + + env: + CTEST_OUTPUT_ON_FAILURE: ON + CTEST_PARALLEL_LEVEL: 2 + CMAKE_BUILD_TYPE: ${{ matrix.build_type }} + GTSAM_BUILD_UNSTABLE: ${{ matrix.build_unstable }} + strategy: + fail-fast: false + matrix: + # Github Actions requires a single row to be added to the build matrix. + # See https://help.github.com/en/articles/workflow-syntax-for-github-actions. + name: [ + windows-2016-cl, + windows-2019-cl, + ] + + build_type: [Debug, Release] + build_unstable: [ON, OFF] + include: + - name: windows-2016-cl + os: windows-2016 + compiler: cl + + - name: windows-2019-cl + os: windows-2019 + compiler: cl + + steps: + - name: Checkout + uses: actions/checkout@master + - name: Install (Windows) + if: runner.os == 'Windows' + shell: powershell + run: | + Invoke-Expression (New-Object System.Net.WebClient).DownloadString('https://get.scoop.sh') + scoop install ninja --global + if ("${{ matrix.compiler }}".StartsWith("clang")) { + scoop install llvm --global + } + if ("${{ matrix.compiler }}" -eq "gcc") { + # Chocolatey GCC is broken on the windows-2019 image. + # See: https://github.com/DaanDeMeyer/doctest/runs/231595515 + # See: https://github.community/t5/GitHub-Actions/Something-is-wrong-with-the-chocolatey-installed-version-of-gcc/td-p/32413 + scoop install gcc --global + echo "::set-env name=CC::gcc" + echo "::set-env name=CXX::g++" + } elseif ("${{ matrix.compiler }}" -eq "clang") { + echo "::set-env name=CC::clang" + echo "::set-env name=CXX::clang++" + } else { + echo "::set-env name=CC::${{ matrix.compiler }}" + echo "::set-env name=CXX::${{ matrix.compiler }}" + } + # Scoop modifies the PATH so we make the modified PATH global. + echo "::set-env name=PATH::$env:PATH" + - name: Build (Windows) + if: runner.os == 'Windows' + run: | + cmake -E remove_directory build + echo "BOOST_ROOT_1_72_0: ${env:BOOST_ROOT_1_72_0}" + cmake -B build -S . -DGTSAM_BUILD_EXAMPLES_ALWAYS=OFF -DBOOST_ROOT="${env:BOOST_ROOT_1_72_0}" -DBOOST_INCLUDEDIR="${env:BOOST_ROOT_1_72_0}\boost\include" -DBOOST_LIBRARYDIR="${env:BOOST_ROOT_1_72_0}\lib" + cmake --build build --config ${{ matrix.build_type }} --target gtsam + cmake --build build --config ${{ matrix.build_type }} --target gtsam_unstable + cmake --build build --config ${{ matrix.build_type }} --target wrap + cmake --build build --config ${{ matrix.build_type }} --target check.base + cmake --build build --config ${{ matrix.build_type }} --target check.base_unstable + cmake --build build --config ${{ matrix.build_type }} --target check.linear \ No newline at end of file diff --git a/.travis.sh b/.travis.sh index 7777e9919..35b964222 100755 --- a/.travis.sh +++ b/.travis.sh @@ -71,7 +71,7 @@ function configure() function finish () { # Print ccache stats - ccache -s + [ -x "$(command -v ccache)" ] && ccache -s cd $SOURCE_DIR } diff --git a/cython/gtsam/utils/visual_data_generator.py b/cython/gtsam/utils/visual_data_generator.py index f04588e70..5ce72fe68 100644 --- a/cython/gtsam/utils/visual_data_generator.py +++ b/cython/gtsam/utils/visual_data_generator.py @@ -30,8 +30,8 @@ class GroundTruth: def __init__(self, K=Cal3_S2(), nrCameras=3, nrPoints=4): self.K = K - self.cameras = [Pose3()] * nrCameras - self.points = [Point3()] * nrPoints + self.cameras = [gtsam.Pose3()] * nrCameras + self.points = [gtsam.Point3(0, 0, 0)] * nrPoints def print_(self, s=""): print(s) @@ -99,11 +99,11 @@ def generate_data(options): r = 40 for i in range(options.nrCameras): theta = i * 2 * np.pi / options.nrCameras - t = Point3(r * np.cos(theta), r * np.sin(theta), height) - truth.cameras[i] = PinholeCameraCal3_S2.Lookat(t, - Point3(), - Point3(0, 0, 1), - truth.K) + t = gtsam.Point3(r * np.cos(theta), r * np.sin(theta), height) + truth.cameras[i] = gtsam.SimpleCamera.Lookat(t, + gtsam.Point3(0, 0, 0), + gtsam.Point3(0, 0, 1), + truth.K) # Create measurements for j in range(nrPoints): # All landmarks seen in every frame diff --git a/gtsam/base/GenericValue.h b/gtsam/base/GenericValue.h index dc205b47f..0e928765f 100644 --- a/gtsam/base/GenericValue.h +++ b/gtsam/base/GenericValue.h @@ -30,6 +30,14 @@ #include #include // operator typeid +#ifdef _WIN32 +#define GENERICVALUE_VISIBILITY +#else +// This will trigger a LNKxxxx on MSVC, so disable for MSVC build +// Please refer to https://github.com/borglab/gtsam/blob/develop/Using-GTSAM-EXPORT.md +#define GENERICVALUE_VISIBILITY GTSAM_EXPORT +#endif + namespace gtsam { /** diff --git a/gtsam/slam/BetweenFactor.h b/gtsam/slam/BetweenFactor.h index 9afc2f72b..a594e95d5 100644 --- a/gtsam/slam/BetweenFactor.h +++ b/gtsam/slam/BetweenFactor.h @@ -21,6 +21,14 @@ #include #include +#ifdef _WIN32 +#define BETWEENFACTOR_VISIBILITY +#else +// This will trigger a LNKxxxx on MSVC, so disable for MSVC build +// Please refer to https://github.com/borglab/gtsam/blob/develop/Using-GTSAM-EXPORT.md +#define BETWEENFACTOR_VISIBILITY GTSAM_EXPORT +#endif + namespace gtsam { /** From 10754080fc34220503ae66f23bf3268a84c35322 Mon Sep 17 00:00:00 2001 From: Fan Jiang Date: Fri, 14 Aug 2020 10:03:40 -0400 Subject: [PATCH 354/869] Remove travis and appveyor --- .travis.yml | 140 --------------------------------------------------- appveyor.yml | 33 ------------ 2 files changed, 173 deletions(-) delete mode 100644 .travis.yml delete mode 100644 appveyor.yml diff --git a/.travis.yml b/.travis.yml deleted file mode 100644 index 986e86cc2..000000000 --- a/.travis.yml +++ /dev/null @@ -1,140 +0,0 @@ -language: cpp -cache: ccache -dist: xenial - -addons: - apt: - sources: - - ubuntu-toolchain-r-test - - sourceline: 'deb http://apt.llvm.org/xenial/ llvm-toolchain-xenial-9 main' - key_url: 'https://apt.llvm.org/llvm-snapshot.gpg.key' - packages: - - g++-9 - - clang-9 - - build-essential pkg-config - - cmake - - python3-dev libpython-dev - - python3-numpy - - libboost-all-dev - -# before_install: - # - if [ "$TRAVIS_OS_NAME" == "osx" ]; then brew update; fi - -install: - - if [ "$TRAVIS_OS_NAME" == "osx" ]; then HOMEBREW_NO_AUTO_UPDATE=1 brew install ccache ; fi - - if [ "$TRAVIS_OS_NAME" == "osx" ]; then export PATH="/usr/local/opt/ccache/libexec:$PATH" ; fi - -# We first do the compile stage specified below, then the matrix expansion specified after. -stages: - - compile - - test - - special - -env: - global: - - MAKEFLAGS="-j3" - - CCACHE_SLOPPINESS=pch_defines,time_macros - -# Compile stage without building examples/tests to populate the caches. -jobs: -# -------- STAGE 1: COMPILE ----------- - include: -# on Mac, GCC - - stage: compile - os: osx - compiler: gcc - env: CMAKE_BUILD_TYPE=Debug GTSAM_BUILD_UNSTABLE=OFF - script: bash .travis.sh -b - - stage: compile - os: osx - compiler: gcc - env: CMAKE_BUILD_TYPE=Release - script: bash .travis.sh -b -# on Mac, CLANG - - stage: compile - os: osx - compiler: clang - env: CMAKE_BUILD_TYPE=Debug GTSAM_BUILD_UNSTABLE=OFF - script: bash .travis.sh -b - - stage: compile - os: osx - compiler: clang - env: CMAKE_BUILD_TYPE=Release - script: bash .travis.sh -b -# on Linux, GCC - - stage: compile - os: linux - compiler: gcc - env: CMAKE_BUILD_TYPE=Debug GTSAM_BUILD_UNSTABLE=OFF - script: bash .travis.sh -b - - stage: compile - os: linux - compiler: gcc - env: CMAKE_BUILD_TYPE=Release - script: bash .travis.sh -b -# on Linux, CLANG - - stage: compile - os: linux - compiler: clang - env: CC=clang-9 CXX=clang++-9 CMAKE_BUILD_TYPE=Debug GTSAM_BUILD_UNSTABLE=OFF - script: bash .travis.sh -b - - stage: compile - os: linux - compiler: clang - env: CC=clang-9 CXX=clang++-9 CMAKE_BUILD_TYPE=Release - script: bash .travis.sh -b -# on Linux, with deprecated ON to make sure that path still compiles/tests - - stage: special - os: linux - compiler: clang - env: CC=clang-9 CXX=clang++-9 CMAKE_BUILD_TYPE=Debug GTSAM_BUILD_UNSTABLE=OFF GTSAM_ALLOW_DEPRECATED_SINCE_V41=ON - script: bash .travis.sh -b -# on Linux, with GTSAM_WITH_TBB on to make sure GTSAM still compiles/tests - # - stage: special - # os: linux - # compiler: gcc - # env: CMAKE_BUILD_TYPE=Debug GTSAM_BUILD_UNSTABLE=OFF GTSAM_WITH_TBB=ON - # script: bash .travis.sh -t -# -------- STAGE 2: TESTS ----------- -# on Mac, GCC - - stage: test - os: osx - compiler: clang - env: CMAKE_BUILD_TYPE=Release - script: bash .travis.sh -t - - stage: test - os: osx - compiler: clang - env: CMAKE_BUILD_TYPE=Debug GTSAM_BUILD_UNSTABLE=OFF - script: bash .travis.sh -t - - stage: test - os: linux - compiler: gcc - env: CMAKE_BUILD_TYPE=Release - script: bash .travis.sh -t - - stage: test - os: linux - compiler: gcc - env: CMAKE_BUILD_TYPE=Debug GTSAM_BUILD_UNSTABLE=OFF - script: bash .travis.sh -t - - stage: test - os: linux - compiler: clang - env: CC=clang-9 CXX=clang++-9 CMAKE_BUILD_TYPE=Release - script: bash .travis.sh -t -# on Linux, with quaternions ON to make sure that path still compiles/tests - - stage: special - os: linux - compiler: clang - env: CC=clang-9 CXX=clang++-9 CMAKE_BUILD_TYPE=Release GTSAM_BUILD_UNSTABLE=OFF GTSAM_USE_QUATERNIONS=ON - script: bash .travis.sh -t - - stage: special - os: linux - compiler: gcc - env: PYTHON_VERSION=3 - script: bash .travis.python.sh - - stage: special - os: osx - compiler: clang - env: PYTHON_VERSION=3 - script: bash .travis.python.sh diff --git a/appveyor.yml b/appveyor.yml deleted file mode 100644 index 3747354cf..000000000 --- a/appveyor.yml +++ /dev/null @@ -1,33 +0,0 @@ -# version format -version: 4.0.3-{branch}-build{build} - -os: Visual Studio 2019 - -clone_folder: c:\projects\gtsam - -platform: x64 -configuration: Release - -environment: - CTEST_OUTPUT_ON_FAILURE: 1 - BOOST_ROOT: C:/Libraries/boost_1_71_0 - -build_script: - - cd c:\projects\gtsam\build - # As of Dec 2019, not all unit tests build cleanly for MSVC, so we'll just - # check that parts of GTSAM build correctly: - #- cmake --build . - - cmake --build . --config Release --target gtsam - - cmake --build . --config Release --target gtsam_unstable - - cmake --build . --config Release --target wrap - #- cmake --build . --target check - - cmake --build . --config Release --target check.base - - cmake --build . --config Release --target check.base_unstable - - cmake --build . --config Release --target check.linear - -before_build: - - cd c:\projects\gtsam - - mkdir build - - cd build - # Disable examples to avoid AppVeyor timeout - - cmake -G "Visual Studio 16 2019" .. -DGTSAM_BUILD_EXAMPLES_ALWAYS=OFF From d43d8b7c6959ddd3e4232110a7beb4acbaedfc9e Mon Sep 17 00:00:00 2001 From: Fan Jiang Date: Fri, 14 Aug 2020 10:03:56 -0400 Subject: [PATCH 355/869] Limit python triggering --- .github/workflows/trigger-python.yml | 5 ++++- 1 file changed, 4 insertions(+), 1 deletion(-) diff --git a/.github/workflows/trigger-python.yml b/.github/workflows/trigger-python.yml index 8fad9e7ca..94527e732 100644 --- a/.github/workflows/trigger-python.yml +++ b/.github/workflows/trigger-python.yml @@ -1,6 +1,9 @@ # This triggers Cython builds on `gtsam-manylinux-build` name: Trigger Python Builds -on: push +on: + push: + branches: + - develop jobs: triggerCython: runs-on: ubuntu-latest From 96169665b0644c64bd62e88cb3f35bdb74709934 Mon Sep 17 00:00:00 2001 From: Fan Jiang Date: Fri, 14 Aug 2020 10:06:00 -0400 Subject: [PATCH 356/869] Remove pybind build --- .github/workflows/build-python.yml | 96 ------------------------------ 1 file changed, 96 deletions(-) delete mode 100644 .github/workflows/build-python.yml diff --git a/.github/workflows/build-python.yml b/.github/workflows/build-python.yml deleted file mode 100644 index 2dc98f05d..000000000 --- a/.github/workflows/build-python.yml +++ /dev/null @@ -1,96 +0,0 @@ -name: Python CI - -on: [pull_request] - -jobs: - build: - name: ${{ matrix.name }} ${{ matrix.build_type }} ${{ matrix.python_version }} - runs-on: ${{ matrix.os }} - - env: - CTEST_OUTPUT_ON_FAILURE: ON - CTEST_PARALLEL_LEVEL: 2 - CMAKE_BUILD_TYPE: ${{ matrix.build_type }} - PYTHON_VERSION: ${{ matrix.python_version }} - WRAPPER: ${{ matrix.wrapper }} - strategy: - fail-fast: false - matrix: - # Github Actions requires a single row to be added to the build matrix. - # See https://help.github.com/en/articles/workflow-syntax-for-github-actions. - name: [ - ubuntu-18.04-gcc-5, - ubuntu-18.04-gcc-9, - ubuntu-18.04-clang-9, - macOS-10.15-xcode-11.3.1, - ] - - build_type: [Debug, Release] - python_version: [3] - wrapper: [pybind] - include: - - name: ubuntu-18.04-gcc-5 - os: ubuntu-18.04 - compiler: gcc - version: "5" - - - name: ubuntu-18.04-gcc-9 - os: ubuntu-18.04 - compiler: gcc - version: "9" - - - name: ubuntu-18.04-clang-9 - os: ubuntu-18.04 - compiler: clang - version: "9" - - - name: macOS-10.15-xcode-11.3.1 - os: macOS-10.15 - compiler: xcode - version: "11.3.1" - - steps: - - name: Checkout - uses: actions/checkout@master - - name: Install (Linux) - if: runner.os == 'Linux' - run: | - # LLVM 9 is not in Bionic's repositories so we add the official LLVM repository. - if [ "${{ matrix.compiler }}" = "clang" ] && [ "${{ matrix.version }}" = "9" ]; then - sudo add-apt-repository "deb http://apt.llvm.org/bionic/ llvm-toolchain-bionic-9 main" - fi - sudo apt-get -y update - sudo apt-get -y upgrade - - sudo apt install cmake g++-9 clang-9 build-essential pkg-config libpython-dev python-numpy libboost-all-dev - - if [ "${{ matrix.compiler }}" = "gcc" ]; then - sudo apt-get install -y g++-${{ matrix.version }} g++-${{ matrix.version }}-multilib - echo "::set-env name=CC::gcc-${{ matrix.version }}" - echo "::set-env name=CXX::g++-${{ matrix.version }}" - else - sudo apt-get install -y clang-${{ matrix.version }} g++-multilib - echo "::set-env name=CC::clang-${{ matrix.version }}" - echo "::set-env name=CXX::clang++-${{ matrix.version }}" - fi - - name: Install (macOS) - if: runner.os == 'macOS' - run: | - brew install cmake ninja boost - if [ "${{ matrix.compiler }}" = "gcc" ]; then - brew install gcc@${{ matrix.version }} - echo "::set-env name=CC::gcc-${{ matrix.version }}" - echo "::set-env name=CXX::g++-${{ matrix.version }}" - else - sudo xcode-select -switch /Applications/Xcode_${{ matrix.version }}.app - echo "::set-env name=CC::clang" - echo "::set-env name=CXX::clang++" - fi - - name: Build (Linux) - if: runner.os == 'Linux' - run: | - bash .travis.python.sh - - name: Build (macOS) - if: runner.os == 'macOS' - run: | - bash .travis.python.sh \ No newline at end of file From a5b722d237c58c2354c081de169b7345b2a48b09 Mon Sep 17 00:00:00 2001 From: Fan Jiang Date: Fri, 14 Aug 2020 10:48:17 -0400 Subject: [PATCH 357/869] Correct .travis.sh --- .travis.python.sh | 60 ++++++++++++++++++++++++++++++++++++++--------- .travis.sh | 16 ++++++------- 2 files changed, 57 insertions(+), 19 deletions(-) diff --git a/.travis.python.sh b/.travis.python.sh index 99506e749..7ccf56dd1 100644 --- a/.travis.python.sh +++ b/.travis.python.sh @@ -6,6 +6,11 @@ if [ -z ${PYTHON_VERSION+x} ]; then exit 127 fi +if [ -z ${WRAPPER+x} ]; then + echo "Please provide the wrapper to build!" + exit 126 +fi + PYTHON="python${PYTHON_VERSION}" if [[ $(uname) == "Darwin" ]]; then @@ -15,9 +20,29 @@ else sudo apt-get install wget libicu-dev python3-pip python3-setuptools fi -CURRDIR=$(pwd) +PATH=$PATH:$($PYTHON -c "import site; print(site.USER_BASE)")/bin -sudo $PYTHON -m pip install -r ./cython/requirements.txt +case $WRAPPER in +"cython") + BUILD_CYTHON="ON" + BUILD_PYBIND="OFF" + TYPEDEF_POINTS_TO_VECTORS="OFF" + + $PYTHON -m pip install --user -r ./cython/requirements.txt + ;; +"pybind") + BUILD_CYTHON="OFF" + BUILD_PYBIND="ON" + TYPEDEF_POINTS_TO_VECTORS="ON" + + $PYTHON -m pip install --user -r ./wrap/python/requirements.txt + ;; +*) + exit 126 + ;; +esac + +CURRDIR=$(pwd) mkdir $CURRDIR/build cd $CURRDIR/build @@ -27,17 +52,30 @@ cmake $CURRDIR -DCMAKE_BUILD_TYPE=Release \ -DGTSAM_USE_QUATERNIONS=OFF \ -DGTSAM_BUILD_EXAMPLES_ALWAYS=OFF \ -DGTSAM_BUILD_WITH_MARCH_NATIVE=OFF \ - -DGTSAM_INSTALL_CYTHON_TOOLBOX=ON \ + -DGTSAM_INSTALL_CYTHON_TOOLBOX=${BUILD_CYTHON} \ + -DGTSAM_BUILD_PYTHON=${BUILD_PYBIND} \ + -DGTSAM_TYPEDEF_POINTS_TO_VECTORS=${TYPEDEF_POINTS_TO_VECTORS} \ -DGTSAM_PYTHON_VERSION=$PYTHON_VERSION \ - -DGTSAM_ALLOW_DEPRECATED_SINCE_V41=OFF \ + -DGTSAM_ALLOW_DEPRECATED_SINCE_V4=OFF \ + -DPYTHON_EXECUTABLE:FILEPATH=$(which $PYTHON) \ -DCMAKE_INSTALL_PREFIX=$CURRDIR/../gtsam_install make -j$(nproc) install -cd cython - -sudo $PYTHON setup.py install - -cd $CURRDIR/cython/gtsam/tests - -$PYTHON -m unittest discover \ No newline at end of file +case $WRAPPER in +"cython") + cd $CURRDIR/../gtsam_install/cython + $PYTHON setup.py install --user --prefix= + cd $CURRDIR/cython/gtsam/tests + $PYTHON -m unittest discover + ;; +"pybind") + $PYTHON setup.py install --user --prefix= + cd $CURRDIR/wrap/python/gtsam_py/tests + $PYTHON -m unittest discover + ;; +*) + echo "THIS SHOULD NEVER HAPPEN!" + exit 125 + ;; +esac diff --git a/.travis.sh b/.travis.sh index 35b964222..422f68065 100755 --- a/.travis.sh +++ b/.travis.sh @@ -4,17 +4,17 @@ function install_tbb() { TBB_BASEURL=https://github.com/oneapi-src/oneTBB/releases/download - TBB_VERSION=4.4.2 - TBB_DIR=tbb44_20151115oss + TBB_VERSION=4.4.5 + TBB_DIR=tbb44_20160526oss TBB_SAVEPATH="/tmp/tbb.tgz" - if [ "$TRAVIS_OS_NAME" == "linux" ]; then + if [ "$(uname)" == "Linux" ]; then OS_SHORT="lin" TBB_LIB_DIR="intel64/gcc4.4" SUDO="sudo" - elif [ "$TRAVIS_OS_NAME" == "osx" ]; then - OS_SHORT="lin" + elif [ "$(uname)" == "Darwin" ]; then + OS_SHORT="osx" TBB_LIB_DIR="" SUDO="" @@ -46,7 +46,7 @@ function configure() rm -fr $BUILD_DIR || true mkdir $BUILD_DIR && cd $BUILD_DIR - install_tbb + [ "${GTSAM_WITH_TBB:-OFF}" = "ON" ] && install_tbb if [ ! -z "$GCC_VERSION" ]; then export CC=gcc-$GCC_VERSION @@ -61,9 +61,9 @@ function configure() -DGTSAM_WITH_TBB=${GTSAM_WITH_TBB:-OFF} \ -DGTSAM_USE_QUATERNIONS=${GTSAM_USE_QUATERNIONS:-OFF} \ -DGTSAM_BUILD_EXAMPLES_ALWAYS=${GTSAM_BUILD_EXAMPLES_ALWAYS:-ON} \ - -DGTSAM_ALLOW_DEPRECATED_SINCE_V4=${GTSAM_ALLOW_DEPRECATED_SINCE_V41:-OFF} \ + -DGTSAM_ALLOW_DEPRECATED_SINCE_V4=${GTSAM_ALLOW_DEPRECATED_SINCE_V4:-OFF} \ -DGTSAM_BUILD_WITH_MARCH_NATIVE=OFF \ - -DCMAKE_VERBOSE_MAKEFILE=OFF + -DCMAKE_VERBOSE_MAKEFILE=ON } From bb0de4f63b3aac40dd419f0c39c1b48cbf9ecc10 Mon Sep 17 00:00:00 2001 From: Fan Jiang Date: Sat, 15 Aug 2020 11:51:56 -0400 Subject: [PATCH 358/869] switch to boost 1.69.0 --- .github/workflows/build-linux.yml | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/.github/workflows/build-linux.yml b/.github/workflows/build-linux.yml index f58fe5f37..eab879e2e 100644 --- a/.github/workflows/build-linux.yml +++ b/.github/workflows/build-linux.yml @@ -54,7 +54,7 @@ jobs: sudo apt-get -y update sudo apt-get -y upgrade - sudo apt install cmake g++-9 clang-9 build-essential pkg-config libpython-dev python-numpy libboost-all-dev + sudo apt install cmake g++-9 clang-9 build-essential pkg-config libpython-dev python-numpy if [ "${{ matrix.compiler }}" = "gcc" ]; then sudo apt-get install -y g++-${{ matrix.version }} g++-${{ matrix.version }}-multilib @@ -64,6 +64,8 @@ jobs: sudo apt-get install -y clang-${{ matrix.version }} g++-multilib echo "::set-env name=CC::clang-${{ matrix.version }}" echo "::set-env name=CXX::clang++-${{ matrix.version }}" + echo "::set-env name=BOOST_ROOT:$BOOST_ROOT_1_69_0" + echo "BOOST_ROOT env set to $BOOST_ROOT" fi - name: Build (Linux) if: runner.os == 'Linux' From b3caa6de8363605dee4caf34dc7b54a392161b12 Mon Sep 17 00:00:00 2001 From: Fan Jiang Date: Sat, 15 Aug 2020 12:06:07 -0400 Subject: [PATCH 359/869] typo --- .github/workflows/build-linux.yml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/.github/workflows/build-linux.yml b/.github/workflows/build-linux.yml index eab879e2e..fbf7d7cd1 100644 --- a/.github/workflows/build-linux.yml +++ b/.github/workflows/build-linux.yml @@ -64,7 +64,7 @@ jobs: sudo apt-get install -y clang-${{ matrix.version }} g++-multilib echo "::set-env name=CC::clang-${{ matrix.version }}" echo "::set-env name=CXX::clang++-${{ matrix.version }}" - echo "::set-env name=BOOST_ROOT:$BOOST_ROOT_1_69_0" + echo "::set-env name=BOOST_ROOT::$BOOST_ROOT_1_69_0" echo "BOOST_ROOT env set to $BOOST_ROOT" fi - name: Build (Linux) From 288195ba169456d9f5e89525f2554475b3cde231 Mon Sep 17 00:00:00 2001 From: Fan Jiang Date: Sat, 15 Aug 2020 12:54:31 -0400 Subject: [PATCH 360/869] Add a display for current boost version --- .github/workflows/build-linux.yml | 8 ++++++-- 1 file changed, 6 insertions(+), 2 deletions(-) diff --git a/.github/workflows/build-linux.yml b/.github/workflows/build-linux.yml index fbf7d7cd1..837d0b174 100644 --- a/.github/workflows/build-linux.yml +++ b/.github/workflows/build-linux.yml @@ -56,6 +56,8 @@ jobs: sudo apt install cmake g++-9 clang-9 build-essential pkg-config libpython-dev python-numpy + echo "::set-env name=BOOST_ROOT::$(echo $BOOST_ROOT_1_69_0)" + if [ "${{ matrix.compiler }}" = "gcc" ]; then sudo apt-get install -y g++-${{ matrix.version }} g++-${{ matrix.version }}-multilib echo "::set-env name=CC::gcc-${{ matrix.version }}" @@ -64,9 +66,11 @@ jobs: sudo apt-get install -y clang-${{ matrix.version }} g++-multilib echo "::set-env name=CC::clang-${{ matrix.version }}" echo "::set-env name=CXX::clang++-${{ matrix.version }}" - echo "::set-env name=BOOST_ROOT::$BOOST_ROOT_1_69_0" - echo "BOOST_ROOT env set to $BOOST_ROOT" fi + - name: Check Boost version + if: runner.os == 'Linux' + run: | + echo "BOOST_ROOT = $BOOST_ROOT" - name: Build (Linux) if: runner.os == 'Linux' run: | From b9f4f28e1aec4b4e1659785def4cbb7d7e931f86 Mon Sep 17 00:00:00 2001 From: Fan Jiang Date: Sat, 15 Aug 2020 13:05:53 -0400 Subject: [PATCH 361/869] Manually specify BOOST_ROOT --- .travis.sh | 1 + 1 file changed, 1 insertion(+) diff --git a/.travis.sh b/.travis.sh index 422f68065..c2b4e0590 100755 --- a/.travis.sh +++ b/.travis.sh @@ -64,6 +64,7 @@ function configure() -DGTSAM_ALLOW_DEPRECATED_SINCE_V4=${GTSAM_ALLOW_DEPRECATED_SINCE_V4:-OFF} \ -DGTSAM_BUILD_WITH_MARCH_NATIVE=OFF \ -DCMAKE_VERBOSE_MAKEFILE=ON + -DBOOST_ROOT=$BOOST_ROOT } From b1e3b5495ce5c969d76f9363b6bb0828b9f250c1 Mon Sep 17 00:00:00 2001 From: Frank Dellaert Date: Sat, 15 Aug 2020 13:05:58 -0400 Subject: [PATCH 362/869] Some behavior changes. - maxIndex now does what it says - id = size_t, Key is only for Values and Graph) - re-admitted methods needed for wrapper. --- examples/Data/example_with_vertices.g2o | 32 +-- gtsam/slam/dataset.cpp | 268 +++++++++++++----------- gtsam/slam/dataset.h | 71 ++++--- gtsam/slam/tests/testDataset.cpp | 46 ++-- tests/testNonlinearISAM.cpp | 2 +- 5 files changed, 229 insertions(+), 190 deletions(-) diff --git a/examples/Data/example_with_vertices.g2o b/examples/Data/example_with_vertices.g2o index 6c2f1a530..ca7cd86df 100644 --- a/examples/Data/example_with_vertices.g2o +++ b/examples/Data/example_with_vertices.g2o @@ -1,16 +1,16 @@ -VERTEX_SE3:QUAT 8646911284551352320 40 -1.15443e-13 10 0.557345 0.557345 -0.435162 -0.435162 -VERTEX_SE3:QUAT 8646911284551352321 28.2843 28.2843 10 0.301633 0.728207 -0.568567 -0.235508 -VERTEX_SE3:QUAT 8646911284551352322 -1.6986e-08 40 10 -3.89609e-10 0.788205 -0.615412 -2.07622e-10 -VERTEX_SE3:QUAT 8646911284551352323 -28.2843 28.2843 10 -0.301633 0.728207 -0.568567 0.235508 -VERTEX_SE3:QUAT 8646911284551352324 -40 -2.32554e-10 10 -0.557345 0.557345 -0.435162 0.435162 -VERTEX_SE3:QUAT 8646911284551352325 -28.2843 -28.2843 10 -0.728207 0.301633 -0.235508 0.568567 -VERTEX_SE3:QUAT 8646911284551352326 -2.53531e-09 -40 10 -0.788205 -1.25891e-11 -3.82742e-13 0.615412 -VERTEX_SE3:QUAT 8646911284551352327 28.2843 -28.2843 10 -0.728207 -0.301633 0.235508 0.568567 -VERTEX_TRACKXYZ 7782220156096217088 10 10 10 -VERTEX_TRACKXYZ 7782220156096217089 -10 10 10 -VERTEX_TRACKXYZ 7782220156096217090 -10 -10 10 -VERTEX_TRACKXYZ 7782220156096217091 10 -10 10 -VERTEX_TRACKXYZ 7782220156096217092 10 10 -10 -VERTEX_TRACKXYZ 7782220156096217093 -10 10 -10 -VERTEX_TRACKXYZ 7782220156096217094 -10 -10 -10 -VERTEX_TRACKXYZ 7782220156096217095 10 -10 -10 +VERTEX_SE3:QUAT 0 40 -1.15443e-13 10 0.557345 0.557345 -0.435162 -0.435162 +VERTEX_SE3:QUAT 1 28.2843 28.2843 10 0.301633 0.728207 -0.568567 -0.235508 +VERTEX_SE3:QUAT 2 -1.6986e-08 40 10 -3.89609e-10 0.788205 -0.615412 -2.07622e-10 +VERTEX_SE3:QUAT 3 -28.2843 28.2843 10 -0.301633 0.728207 -0.568567 0.235508 +VERTEX_SE3:QUAT 4 -40 -2.32554e-10 10 -0.557345 0.557345 -0.435162 0.435162 +VERTEX_SE3:QUAT 5 -28.2843 -28.2843 10 -0.728207 0.301633 -0.235508 0.568567 +VERTEX_SE3:QUAT 6 -2.53531e-09 -40 10 -0.788205 -1.25891e-11 -3.82742e-13 0.615412 +VERTEX_SE3:QUAT 7 28.2843 -28.2843 10 -0.728207 -0.301633 0.235508 0.568567 +VERTEX_TRACKXYZ 0 10 10 10 +VERTEX_TRACKXYZ 1 -10 10 10 +VERTEX_TRACKXYZ 2 -10 -10 10 +VERTEX_TRACKXYZ 3 10 -10 10 +VERTEX_TRACKXYZ 4 10 10 -10 +VERTEX_TRACKXYZ 5 -10 10 -10 +VERTEX_TRACKXYZ 6 -10 -10 -10 +VERTEX_TRACKXYZ 7 10 -10 -10 diff --git a/gtsam/slam/dataset.cpp b/gtsam/slam/dataset.cpp index 2aac939d9..9cc814245 100644 --- a/gtsam/slam/dataset.cpp +++ b/gtsam/slam/dataset.cpp @@ -53,7 +53,9 @@ using namespace std; namespace fs = boost::filesystem; -using namespace gtsam::symbol_shorthand; +using gtsam::symbol_shorthand::L; +using gtsam::symbol_shorthand::P; +using gtsam::symbol_shorthand::X; #define LINESIZE 81920 @@ -127,19 +129,16 @@ static void parseLines(const string &filename, Parser parse) { } /* ************************************************************************* */ -// Parse types T into a Key-indexed map +// Parse types T into a size_t-indexed map template -map parseToMap(const string &filename, Parser> parse, - Key maxKey) { - ifstream is(filename.c_str()); - if (!is) - throw invalid_argument("parse: can not find file " + filename); - - map result; - Parser> emplace = [&result, parse](istream &is, - const string &tag) { - if (auto t = parse(is, tag)) - result.emplace(*t); +map parseToMap(const string &filename, Parser> parse, + size_t maxIndex) { + map result; + Parser> emplace = [&](istream &is, const string &tag) { + if (auto t = parse(is, tag)) { + if (!maxIndex || t->first <= maxIndex) + result.emplace(*t); + } return boost::none; }; parseLines(filename, emplace); @@ -148,7 +147,6 @@ map parseToMap(const string &filename, Parser> parse, /* ************************************************************************* */ // Parse a file and push results on a vector -// TODO(frank): do we need this *and* parseMeasurements? template static vector parseToVector(const string &filename, Parser parse) { vector result; @@ -164,7 +162,7 @@ static vector parseToVector(const string &filename, Parser parse) { /* ************************************************************************* */ boost::optional parseVertexPose(istream &is, const string &tag) { if ((tag == "VERTEX2") || (tag == "VERTEX_SE2") || (tag == "VERTEX")) { - Key id; + size_t id; double x, y, yaw; is >> id >> x >> y >> yaw; return IndexedPose(id, Pose2(x, y, yaw)); @@ -174,16 +172,16 @@ boost::optional parseVertexPose(istream &is, const string &tag) { } template <> -std::map parseVariables(const std::string &filename, - Key maxKey) { - return parseToMap(filename, parseVertexPose, maxKey); +std::map parseVariables(const std::string &filename, + size_t maxIndex) { + return parseToMap(filename, parseVertexPose, maxIndex); } /* ************************************************************************* */ boost::optional parseVertexLandmark(istream &is, const string &tag) { if (tag == "VERTEX_XY") { - Key id; + size_t id; double x, y; is >> id >> x >> y; return IndexedLandmark(id, Point2(x, y)); @@ -193,9 +191,9 @@ boost::optional parseVertexLandmark(istream &is, } template <> -std::map parseVariables(const std::string &filename, - Key maxKey) { - return parseToMap(filename, parseVertexLandmark, maxKey); +std::map parseVariables(const std::string &filename, + size_t maxIndex) { + return parseToMap(filename, parseVertexLandmark, maxIndex); } /* ************************************************************************* */ @@ -287,10 +285,10 @@ boost::optional parseEdge(istream &is, const string &tag) { if ((tag == "EDGE2") || (tag == "EDGE") || (tag == "EDGE_SE2") || (tag == "ODOMETRY")) { - Key id1, id2; + size_t id1, id2; double x, y, yaw; is >> id1 >> id2 >> x >> y >> yaw; - return IndexedEdge(pair(id1, id2), Pose2(x, y, yaw)); + return IndexedEdge({id1, id2}, Pose2(x, y, yaw)); } else { return boost::none; } @@ -323,7 +321,7 @@ template struct ParseFactor : ParseMeasurement { template <> struct ParseMeasurement { // The arguments boost::shared_ptr sampler; - Key maxKey; + size_t maxIndex; // For noise model creation bool smart; @@ -345,9 +343,9 @@ template <> struct ParseMeasurement { is >> v(0) >> v(1) >> v(2) >> v(3) >> v(4) >> v(5); // optional filter - Key id1, id2; + size_t id1, id2; tie(id1, id2) = edge->first; - if (maxKey && (id1 >= maxKey || id2 >= maxKey)) + if (maxIndex && (id1 > maxIndex || id2 > maxIndex)) return boost::none; // Get pose and optionally add noise @@ -378,9 +376,11 @@ boost::shared_ptr createSampler(const SharedNoiseModel &model) { template <> std::vector> parseMeasurements(const std::string &filename, - const noiseModel::Diagonal::shared_ptr &model, Key maxKey) { - ParseMeasurement parse{model ? createSampler(model) : nullptr, maxKey, - true, NoiseFormatAUTO, KernelFunctionTypeNONE}; + const noiseModel::Diagonal::shared_ptr &model, + size_t maxIndex) { + ParseMeasurement parse{model ? createSampler(model) : nullptr, + maxIndex, true, NoiseFormatAUTO, + KernelFunctionTypeNONE}; return parseToVector>(filename, parse); } @@ -403,8 +403,9 @@ static BinaryMeasurement convert(const BinaryMeasurement &p) { template <> std::vector> parseMeasurements(const std::string &filename, - const noiseModel::Diagonal::shared_ptr &model, Key maxKey) { - auto poses = parseMeasurements(filename, model, maxKey); + const noiseModel::Diagonal::shared_ptr &model, + size_t maxIndex) { + auto poses = parseMeasurements(filename, model, maxIndex); std::vector> result; result.reserve(poses.size()); for (const auto &p : poses) @@ -417,8 +418,9 @@ parseMeasurements(const std::string &filename, template <> std::vector::shared_ptr> parseFactors(const std::string &filename, - const noiseModel::Diagonal::shared_ptr &model, Key maxKey) { - ParseFactor parse({model ? createSampler(model) : nullptr, maxKey, + const noiseModel::Diagonal::shared_ptr &model, + size_t maxIndex) { + ParseFactor parse({model ? createSampler(model) : nullptr, maxIndex, true, NoiseFormatAUTO, KernelFunctionTypeNONE, nullptr}); return parseToVector::shared_ptr>(filename, parse); @@ -429,7 +431,7 @@ using BearingRange2D = BearingRange; template <> struct ParseMeasurement { // arguments - Key maxKey; + size_t maxIndex; // The actual parser boost::optional> @@ -437,7 +439,7 @@ template <> struct ParseMeasurement { if (tag != "BR" && tag != "LANDMARK") return boost::none; - Key id1, id2; + size_t id1, id2; is >> id1 >> id2; double bearing, range, bearing_std, range_std; @@ -470,7 +472,7 @@ template <> struct ParseMeasurement { } // optional filter - if (maxKey && id1 >= maxKey) + if (maxIndex && id1 > maxIndex) return boost::none; // Create noise model @@ -484,30 +486,37 @@ template <> struct ParseMeasurement { /* ************************************************************************* */ GraphAndValues load2D(const string &filename, SharedNoiseModel model, - Key maxKey, bool addNoise, bool smart, + size_t maxIndex, bool addNoise, bool smart, NoiseFormat noiseFormat, KernelFunctionType kernelFunctionType) { - auto graph = boost::make_shared(); + // Single pass for poses and landmarks. auto initial = boost::make_shared(); + Parser insert = [maxIndex, &initial](istream &is, const string &tag) { + if (auto indexedPose = parseVertexPose(is, tag)) { + if (!maxIndex || indexedPose->first <= maxIndex) + initial->insert(indexedPose->first, indexedPose->second); + } else if (auto indexedLandmark = parseVertexLandmark(is, tag)) { + if (!maxIndex || indexedLandmark->first <= maxIndex) + initial->insert(L(indexedLandmark->first), indexedLandmark->second); + } + return 0; + }; + parseLines(filename, insert); - // TODO(frank): do a single pass - const auto poses = parseVariables(filename, maxKey); - for (const auto &key_pose : poses) { - initial->insert(key_pose.first, key_pose.second); - } + // Single pass for Pose2 and bearing-range factors. + auto graph = boost::make_shared(); - const auto landmarks = parseVariables(filename, maxKey); - for (const auto &key_landmark : landmarks) { - initial->insert(L(key_landmark.first), key_landmark.second); - } - - // Create parser for Pose2 and bearing/range + // Instantiate factor parser ParseFactor parseBetweenFactor( - {addNoise ? createSampler(model) : nullptr, maxKey, smart, noiseFormat, + {addNoise ? createSampler(model) : nullptr, maxIndex, smart, noiseFormat, kernelFunctionType, model}); - ParseMeasurement parseBearingRange{maxKey}; + // Instantiate bearing-range parser + ParseMeasurement parseBearingRange{maxIndex}; + + // Combine in a single parser that adds factors to `graph`, but also inserts + // new variables into `initial` when needed. Parser parse = [&](istream &is, const string &tag) { if (auto f = parseBetweenFactor(is, tag)) { graph->push_back(*f); @@ -537,23 +546,24 @@ GraphAndValues load2D(const string &filename, SharedNoiseModel model, return 0; }; - parseLines(filename, parse); + parseLines(filename, parse); return make_pair(graph, initial); } /* ************************************************************************* */ -GraphAndValues load2D(pair dataset, Key maxKey, +GraphAndValues load2D(pair dataset, size_t maxIndex, bool addNoise, bool smart, NoiseFormat noiseFormat, KernelFunctionType kernelFunctionType) { - return load2D(dataset.first, dataset.second, maxKey, addNoise, smart, + return load2D(dataset.first, dataset.second, maxIndex, addNoise, smart, noiseFormat, kernelFunctionType); } /* ************************************************************************* */ GraphAndValues load2D_robust(const string &filename, - noiseModel::Base::shared_ptr &model, Key maxKey) { - return load2D(filename, model, maxKey); + noiseModel::Base::shared_ptr &model, + size_t maxIndex) { + return load2D(filename, model, maxIndex); } /* ************************************************************************* */ @@ -596,10 +606,10 @@ GraphAndValues readG2o(const string &g2oFile, const bool is3D, return load3D(g2oFile); } else { // just call load2D - Key maxKey = 0; + size_t maxIndex = 0; bool addNoise = false; bool smart = true; - return load2D(g2oFile, SharedNoiseModel(), maxKey, addNoise, smart, + return load2D(g2oFile, SharedNoiseModel(), maxIndex, addNoise, smart, NoiseFormatG2O, kernelFunctionType); } } @@ -609,13 +619,16 @@ void writeG2o(const NonlinearFactorGraph &graph, const Values &estimate, const string &filename) { fstream stream(filename.c_str(), fstream::out); + // Use a lambda here to more easily modify behavior in future. + auto index = [](gtsam::Key key) { return Symbol(key).index(); }; + // save 2D poses for (const auto key_value : estimate) { auto p = dynamic_cast *>(&key_value.value); if (!p) continue; const Pose2 &pose = p->value(); - stream << "VERTEX_SE2 " << key_value.key << " " << pose.x() << " " + stream << "VERTEX_SE2 " << index(key_value.key) << " " << pose.x() << " " << pose.y() << " " << pose.theta() << endl; } @@ -627,7 +640,7 @@ void writeG2o(const NonlinearFactorGraph &graph, const Values &estimate, const Pose3 &pose = p->value(); const Point3 t = pose.translation(); const auto q = pose.rotation().toQuaternion(); - stream << "VERTEX_SE3:QUAT " << key_value.key << " " << t.x() << " " + stream << "VERTEX_SE3:QUAT " << index(key_value.key) << " " << t.x() << " " << t.y() << " " << t.z() << " " << q.x() << " " << q.y() << " " << q.z() << " " << q.w() << endl; } @@ -638,7 +651,7 @@ void writeG2o(const NonlinearFactorGraph &graph, const Values &estimate, if (!p) continue; const Point2 &point = p->value(); - stream << "VERTEX_XY " << key_value.key << " " << point.x() << " " + stream << "VERTEX_XY " << index(key_value.key) << " " << point.x() << " " << point.y() << endl; } @@ -648,26 +661,25 @@ void writeG2o(const NonlinearFactorGraph &graph, const Values &estimate, if (!p) continue; const Point3 &point = p->value(); - stream << "VERTEX_TRACKXYZ " << key_value.key << " " << point.x() << " " - << point.y() << " " << point.z() << endl; + stream << "VERTEX_TRACKXYZ " << index(key_value.key) << " " << point.x() + << " " << point.y() << " " << point.z() << endl; } // save edges (2D or 3D) for (const auto &factor_ : graph) { - boost::shared_ptr> factor = - boost::dynamic_pointer_cast>(factor_); + auto factor = boost::dynamic_pointer_cast>(factor_); if (factor) { SharedNoiseModel model = factor->noiseModel(); - boost::shared_ptr gaussianModel = - boost::dynamic_pointer_cast(model); + auto gaussianModel = boost::dynamic_pointer_cast(model); if (!gaussianModel) { model->print("model\n"); throw invalid_argument("writeG2o: invalid noise model!"); } Matrix3 Info = gaussianModel->R().transpose() * gaussianModel->R(); Pose2 pose = factor->measured(); //.inverse(); - stream << "EDGE_SE2 " << factor->key1() << " " << factor->key2() << " " - << pose.x() << " " << pose.y() << " " << pose.theta(); + stream << "EDGE_SE2 " << index(factor->key1()) << " " + << index(factor->key2()) << " " << pose.x() << " " << pose.y() + << " " << pose.theta(); for (size_t i = 0; i < 3; i++) { for (size_t j = i; j < 3; j++) { stream << " " << Info(i, j); @@ -676,8 +688,7 @@ void writeG2o(const NonlinearFactorGraph &graph, const Values &estimate, stream << endl; } - boost::shared_ptr> factor3D = - boost::dynamic_pointer_cast>(factor_); + auto factor3D = boost::dynamic_pointer_cast>(factor_); if (factor3D) { SharedNoiseModel model = factor3D->noiseModel(); @@ -692,9 +703,10 @@ void writeG2o(const NonlinearFactorGraph &graph, const Values &estimate, const Pose3 pose3D = factor3D->measured(); const Point3 p = pose3D.translation(); const auto q = pose3D.rotation().toQuaternion(); - stream << "EDGE_SE3:QUAT " << factor3D->key1() << " " << factor3D->key2() - << " " << p.x() << " " << p.y() << " " << p.z() << " " << q.x() - << " " << q.y() << " " << q.z() << " " << q.w(); + stream << "EDGE_SE3:QUAT " << index(factor3D->key1()) << " " + << index(factor3D->key2()) << " " << p.x() << " " << p.y() << " " + << p.z() << " " << q.x() << " " << q.y() << " " << q.z() << " " + << q.w(); Matrix6 InfoG2o = I_6x6; InfoG2o.block<3, 3>(0, 0) = Info.block<3, 3>(3, 3); // cov translation @@ -733,16 +745,16 @@ istream &operator>>(istream &is, Rot3 &R) { } /* ************************************************************************* */ -boost::optional> parseVertexPose3(istream &is, - const string &tag) { +boost::optional> parseVertexPose3(istream &is, + const string &tag) { if (tag == "VERTEX3") { - Key id; + size_t id; double x, y, z; Rot3 R; is >> id >> x >> y >> z >> R; return make_pair(id, Pose3(R, {x, y, z})); } else if (tag == "VERTEX_SE3:QUAT") { - Key id; + size_t id; double x, y, z; Quaternion q; is >> id >> x >> y >> z >> q; @@ -752,16 +764,16 @@ boost::optional> parseVertexPose3(istream &is, } template <> -std::map parseVariables(const std::string &filename, - Key maxKey) { - return parseToMap(filename, parseVertexPose3, maxKey); +std::map parseVariables(const std::string &filename, + size_t maxIndex) { + return parseToMap(filename, parseVertexPose3, maxIndex); } /* ************************************************************************* */ -boost::optional> parseVertexPoint3(istream &is, - const string &tag) { +boost::optional> parseVertexPoint3(istream &is, + const string &tag) { if (tag == "VERTEX_TRACKXYZ") { - Key id; + size_t id; double x, y, z; is >> id >> x >> y >> z; return make_pair(id, Point3(x, y, z)); @@ -770,9 +782,9 @@ boost::optional> parseVertexPoint3(istream &is, } template <> -std::map parseVariables(const std::string &filename, - Key maxKey) { - return parseToMap(filename, parseVertexPoint3, maxKey); +std::map parseVariables(const std::string &filename, + size_t maxIndex) { + return parseToMap(filename, parseVertexPoint3, maxIndex); } /* ************************************************************************* */ @@ -791,7 +803,7 @@ istream &operator>>(istream &is, Matrix6 &m) { template <> struct ParseMeasurement { // The arguments boost::shared_ptr sampler; - Key maxKey; + size_t maxIndex; // The actual parser boost::optional> operator()(istream &is, @@ -800,9 +812,9 @@ template <> struct ParseMeasurement { return boost::none; // parse ids and optionally filter - Key id1, id2; + size_t id1, id2; is >> id1 >> id2; - if (maxKey && (id1 >= maxKey || id2 >= maxKey)) + if (maxIndex && (id1 > maxIndex || id2 > maxIndex)) return boost::none; Matrix6 m; @@ -847,8 +859,10 @@ template <> struct ParseMeasurement { template <> std::vector> parseMeasurements(const std::string &filename, - const noiseModel::Diagonal::shared_ptr &model, Key maxKey) { - ParseMeasurement parse{model ? createSampler(model) : nullptr, maxKey}; + const noiseModel::Diagonal::shared_ptr &model, + size_t maxIndex) { + ParseMeasurement parse{model ? createSampler(model) : nullptr, + maxIndex}; return parseToVector>(filename, parse); } @@ -872,8 +886,9 @@ static BinaryMeasurement convert(const BinaryMeasurement &p) { template <> std::vector> parseMeasurements(const std::string &filename, - const noiseModel::Diagonal::shared_ptr &model, Key maxKey) { - auto poses = parseMeasurements(filename, model, maxKey); + const noiseModel::Diagonal::shared_ptr &model, + size_t maxIndex) { + auto poses = parseMeasurements(filename, model, maxIndex); std::vector> result; result.reserve(poses.size()); for (const auto &p : poses) @@ -886,8 +901,9 @@ parseMeasurements(const std::string &filename, template <> std::vector::shared_ptr> parseFactors(const std::string &filename, - const noiseModel::Diagonal::shared_ptr &model, Key maxKey) { - ParseFactor parse({model ? createSampler(model) : nullptr, maxKey}); + const noiseModel::Diagonal::shared_ptr &model, + size_t maxIndex) { + ParseFactor parse({model ? createSampler(model) : nullptr, maxIndex}); return parseToVector::shared_ptr>(filename, parse); } @@ -896,21 +912,22 @@ GraphAndValues load3D(const string &filename) { auto graph = boost::make_shared(); auto initial = boost::make_shared(); - // TODO(frank): do a single pass - const auto factors = parseFactors(filename); - for (const auto &factor : factors) { - graph->push_back(factor); - } + // Instantiate factor parser. maxIndex is always zero for load3D. + ParseFactor parseFactor({nullptr, 0}); - const auto poses = parseVariables(filename); - for (const auto &key_pose : poses) { - initial->insert(key_pose.first, key_pose.second); - } - - const auto landmarks = parseVariables(filename); - for (const auto &key_landmark : landmarks) { - initial->insert(key_landmark.first, key_landmark.second); - } + // Single pass for variables and factors. Unlike 2D version, does *not* insert + // variables into `initial` if referenced but not present. + Parser parse = [&](istream &is, const string &tag) { + if (auto indexedPose = parseVertexPose3(is, tag)) { + initial->insert(indexedPose->first, indexedPose->second); + } else if (auto indexedLandmark = parseVertexPoint3(is, tag)) { + initial->insert(L(indexedLandmark->first), indexedLandmark->second); + } else if (auto factor = parseFactor(is, tag)) { + graph->push_back(*factor); + } + return 0; + }; + parseLines(filename, parse); return make_pair(graph, initial); } @@ -1187,8 +1204,7 @@ bool writeBALfromValues(const string &filename, const SfmData &data, dataValues.number_cameras()) { // we only estimated camera poses for (size_t i = 0; i < dataValues.number_cameras(); i++) { // for each camera - Key poseKey = symbol('x', i); - Pose3 pose = values.at(poseKey); + Pose3 pose = values.at(X(i)); Cal3Bundler K = dataValues.cameras[i].calibration(); Camera camera(pose, K); dataValues.cameras[i] = camera; @@ -1255,20 +1271,22 @@ Values initialCamerasAndPointsEstimate(const SfmData &db) { return initial; } -#ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V41 -std::map parse3DPoses(const std::string &filename, Key maxKey) { - return parseVariables(filename, maxKey); -} - -std::map parse3DLandmarks(const std::string &filename, - Key maxKey) { - return parseVariables(filename, maxKey); -} - +// To be deprecated when pybind wrapper is merged: BetweenFactorPose3s parse3DFactors(const std::string &filename, - const noiseModel::Diagonal::shared_ptr &model, Key maxKey) { - return parseFactors(filename, model, maxKey); + const noiseModel::Diagonal::shared_ptr &model, size_t maxIndex) { + return parseFactors(filename, model, maxIndex); +} + +#ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V41 +std::map parse3DPoses(const std::string &filename, + size_t maxIndex) { + return parseVariables(filename, maxIndex); +} + +std::map parse3DLandmarks(const std::string &filename, + size_t maxIndex) { + return parseVariables(filename, maxIndex); } #endif } // namespace gtsam diff --git a/gtsam/slam/dataset.h b/gtsam/slam/dataset.h index 38ddfd1dc..7bdf6728d 100644 --- a/gtsam/slam/dataset.h +++ b/gtsam/slam/dataset.h @@ -74,37 +74,41 @@ enum KernelFunctionType { }; /** - * Parse variables in 2D g2o graph file into a map. - * Instantiated in .cpp T equal to Pose2, Pose3 + * Parse variables in a line-based text format (like g2o) into a map. + * Instantiated in .cpp Pose2, Point2, Pose3, and Point3. + * Note the map keys are integer indices, *not* gtsam::Keys. This is is + * different below where landmarks will use be L(index) symbols. */ template -GTSAM_EXPORT std::map parseVariables(const std::string &filename, - Key maxKey = 0); +GTSAM_EXPORT std::map parseVariables(const std::string &filename, + size_t maxIndex = 0); /** - * Parse edges in 2D g2o graph file into a set of binary measuremnts. - * Instantiated in .cpp for T equal to Pose2, Pose3 + * Parse binary measurements in a line-based text format (like g2o) into a + * vector. Instantiated in .cpp for Pose2, Rot2, Pose3, and Rot3. The rotation + * versions parse poses and extract only the rotation part, using the marginal + * covariance as noise model. */ template GTSAM_EXPORT std::vector> parseMeasurements(const std::string &filename, - const noiseModel::Diagonal::shared_ptr &model = nullptr, - Key maxKey = 0); + const noiseModel::Diagonal::shared_ptr &model = nullptr, + size_t maxIndex = 0); /** - * Parse edges in 2D g2o graph file into a set of BetweenFactors. - * Instantiated in .cpp T equal to Pose2, Pose3 + * Parse BetweenFactors in a line-based text format (like g2o) into a vector of + * shared pointers. Instantiated in .cpp T equal to Pose2 and Pose3. */ template GTSAM_EXPORT std::vector::shared_ptr> parseFactors(const std::string &filename, const noiseModel::Diagonal::shared_ptr &model = nullptr, - Key maxKey = 0); + size_t maxIndex = 0); /// Return type for auxiliary functions -typedef std::pair IndexedPose; -typedef std::pair IndexedLandmark; -typedef std::pair, Pose2> IndexedEdge; +typedef std::pair IndexedPose; +typedef std::pair IndexedLandmark; +typedef std::pair, Pose2> IndexedEdge; /** * Parse TORO/G2O vertex "id x y yaw" @@ -130,19 +134,21 @@ GTSAM_EXPORT boost::optional parseVertexLandmark(std::istream& GTSAM_EXPORT boost::optional parseEdge(std::istream& is, const std::string& tag); -/// Return type for load functions +/// Return type for load functions, which return a graph and initial values. For +/// landmarks, the gtsam::Symbol L(index) is used to insert into the Values. +/// Bearing-range measurements also refer tio landmarks with L(index). using GraphAndValues = std::pair; /** * Load TORO 2D Graph * @param dataset/model pair as constructed by [dataset] - * @param maxKey if non-zero cut out vertices >= maxKey + * @param maxIndex if non-zero cut out vertices >= maxIndex * @param addNoise add noise to the edges * @param smart try to reduce complexity of covariance to cheapest model */ GTSAM_EXPORT GraphAndValues load2D( - std::pair dataset, Key maxKey = 0, + std::pair dataset, size_t maxIndex = 0, bool addNoise = false, bool smart = true, // NoiseFormat noiseFormat = NoiseFormatAUTO, @@ -152,7 +158,7 @@ GTSAM_EXPORT GraphAndValues load2D( * Load TORO/G2O style graph files * @param filename * @param model optional noise model to use instead of one specified by file - * @param maxKey if non-zero cut out vertices >= maxKey + * @param maxIndex if non-zero cut out vertices >= maxIndex * @param addNoise add noise to the edges * @param smart try to reduce complexity of covariance to cheapest model * @param noiseFormat how noise parameters are stored @@ -160,13 +166,13 @@ GTSAM_EXPORT GraphAndValues load2D( * @return graph and initial values */ GTSAM_EXPORT GraphAndValues load2D(const std::string& filename, - SharedNoiseModel model = SharedNoiseModel(), Key maxKey = 0, bool addNoise = + SharedNoiseModel model = SharedNoiseModel(), size_t maxIndex = 0, bool addNoise = false, bool smart = true, NoiseFormat noiseFormat = NoiseFormatAUTO, // KernelFunctionType kernelFunctionType = KernelFunctionTypeNONE); /// @deprecated load2D now allows for arbitrary models and wrapping a robust kernel GTSAM_EXPORT GraphAndValues load2D_robust(const std::string& filename, - noiseModel::Base::shared_ptr& model, Key maxKey = 0); + noiseModel::Base::shared_ptr& model, size_t maxIndex = 0); /** save 2d graph */ GTSAM_EXPORT void save2D(const NonlinearFactorGraph& graph, @@ -190,6 +196,11 @@ GTSAM_EXPORT GraphAndValues readG2o(const std::string& g2oFile, const bool is3D * @param filename The name of the g2o file to write * @param graph NonlinearFactor graph storing the measurements * @param estimate Values + * + * Note:behavior change in PR #471: to be consistent with load2D and load3D, we + * write the *indices* to file and not the full Keys. This change really only + * affects landmarks, which get read as indices but stored in values with the + * symbol L(index). */ GTSAM_EXPORT void writeG2o(const NonlinearFactorGraph& graph, const Values& estimate, const std::string& filename); @@ -330,22 +341,24 @@ GTSAM_EXPORT Values initialCamerasEstimate(const SfmData& db); */ GTSAM_EXPORT Values initialCamerasAndPointsEstimate(const SfmData& db); +// To be deprecated when pybind wrapper is merged: +using BetweenFactorPose3s = std::vector::shared_ptr>; +GTSAM_EXPORT BetweenFactorPose3s +parse3DFactors(const std::string &filename, + const noiseModel::Diagonal::shared_ptr &model = nullptr, + size_t maxIndex = 0); + #ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V41 inline boost::optional parseVertex(std::istream &is, const std::string &tag) { return parseVertexPose(is, tag); } -GTSAM_EXPORT std::map parse3DPoses(const std::string &filename, - Key maxKey = 0); +GTSAM_EXPORT std::map parse3DPoses(const std::string &filename, + size_t maxIndex = 0); -GTSAM_EXPORT std::map parse3DLandmarks(const std::string &filename, - Key maxKey = 0); - -using BetweenFactorPose3s = std::vector::shared_ptr>; -GTSAM_EXPORT BetweenFactorPose3s parse3DFactors( - const std::string &filename, - const noiseModel::Diagonal::shared_ptr &model = nullptr, Key maxKey = 0); +GTSAM_EXPORT std::map +parse3DLandmarks(const std::string &filename, size_t maxIndex = 0); #endif } // namespace gtsam diff --git a/gtsam/slam/tests/testDataset.cpp b/gtsam/slam/tests/testDataset.cpp index 3e804b6b0..aad9124c5 100644 --- a/gtsam/slam/tests/testDataset.cpp +++ b/gtsam/slam/tests/testDataset.cpp @@ -82,7 +82,7 @@ TEST( dataSet, parseEdge) const auto actual = parseEdge(is, tag); EXPECT(actual); if (actual) { - pair expected(0, 1); + pair expected(0, 1); EXPECT(expected == actual->first); EXPECT(assert_equal(Pose2(2, 3, 4), actual->second)); } @@ -105,8 +105,9 @@ TEST(dataSet, load2D) { EXPECT(assert_equal(expected, *actual)); // Check binary measurements, Pose2 - auto measurements = parseMeasurements(filename, nullptr, 5); - EXPECT_LONGS_EQUAL(4, measurements.size()); + size_t maxIndex = 5; + auto measurements = parseMeasurements(filename, nullptr, maxIndex); + EXPECT_LONGS_EQUAL(5, measurements.size()); // Check binary measurements, Rot2 auto measurements2 = parseMeasurements(filename); @@ -132,14 +133,22 @@ TEST(dataSet, load2D) { } /* ************************************************************************* */ -TEST( dataSet, load2DVictoriaPark) -{ +TEST(dataSet, load2DVictoriaPark) { const string filename = findExampleDataFile("victoria_park.txt"); NonlinearFactorGraph::shared_ptr graph; Values::shared_ptr initial; + + // Load all boost::tie(graph, initial) = load2D(filename); - EXPECT_LONGS_EQUAL(10608,graph->size()); - EXPECT_LONGS_EQUAL(7120,initial->size()); + EXPECT_LONGS_EQUAL(10608, graph->size()); + EXPECT_LONGS_EQUAL(7120, initial->size()); + + // Restrict keys + size_t maxIndex = 5; + boost::tie(graph, initial) = load2D(filename, nullptr, maxIndex); + EXPECT_LONGS_EQUAL(5, graph->size()); + EXPECT_LONGS_EQUAL(6, initial->size()); // file has 0 as well + EXPECT_LONGS_EQUAL(L(5), graph->at(4)->keys()[1]); } /* ************************************************************************* */ @@ -293,13 +302,13 @@ TEST(dataSet, readG2oCheckDeterminants) { } // Check determinants in initial values - const map poses = parseVariables(g2oFile); + const map poses = parseVariables(g2oFile); EXPECT_LONGS_EQUAL(5, poses.size()); for (const auto& key_value : poses) { const Rot3 R = key_value.second.rotation(); EXPECT_DOUBLES_EQUAL(1.0, R.matrix().determinant(), 1e-9); } - const map landmarks = parseVariables(g2oFile); + const map landmarks = parseVariables(g2oFile); EXPECT_LONGS_EQUAL(0, landmarks.size()); } @@ -308,10 +317,13 @@ TEST(dataSet, readG2oLandmarks) { const string g2oFile = findExampleDataFile("example_with_vertices.g2o"); // Check number of poses and landmarks. Should be 8 each. - const map poses = parseVariables(g2oFile); + const map poses = parseVariables(g2oFile); EXPECT_LONGS_EQUAL(8, poses.size()); - const map landmarks = parseVariables(g2oFile); + const map landmarks = parseVariables(g2oFile); EXPECT_LONGS_EQUAL(8, landmarks.size()); + + auto graphAndValues = load3D(g2oFile); + EXPECT(graphAndValues.second->exists(L(0))); } /* ************************************************************************* */ @@ -564,14 +576,12 @@ TEST( dataSet, writeBALfromValues_Dubrovnik){ Values value; for(size_t i=0; i < readData.number_cameras(); i++){ // for each camera - Key poseKey = symbol('x',i); Pose3 pose = poseChange.compose(readData.cameras[i].pose()); - value.insert(poseKey, pose); + value.insert(X(i), pose); } for(size_t j=0; j < readData.number_tracks(); j++){ // for each point - Key pointKey = P(j); Point3 point = poseChange.transformFrom( readData.tracks[j].p ); - value.insert(pointKey, point); + value.insert(P(j), point); } // Write values and readData to a file @@ -596,13 +606,11 @@ TEST( dataSet, writeBALfromValues_Dubrovnik){ EXPECT(assert_equal(expected,actual,12)); Pose3 expectedPose = camera0.pose(); - Key poseKey = symbol('x',0); - Pose3 actualPose = value.at(poseKey); + Pose3 actualPose = value.at(X(0)); EXPECT(assert_equal(expectedPose,actualPose, 1e-7)); Point3 expectedPoint = track0.p; - Key pointKey = P(0); - Point3 actualPoint = value.at(pointKey); + Point3 actualPoint = value.at(P(0)); EXPECT(assert_equal(expectedPoint,actualPoint, 1e-6)); } diff --git a/tests/testNonlinearISAM.cpp b/tests/testNonlinearISAM.cpp index 974806612..4249f5bc4 100644 --- a/tests/testNonlinearISAM.cpp +++ b/tests/testNonlinearISAM.cpp @@ -308,7 +308,7 @@ TEST(testNonlinearISAM, loop_closures ) { // check if edge const auto betweenPose = parseEdge(is, tag); if (betweenPose) { - Key id1, id2; + size_t id1, id2; tie(id1, id2) = betweenPose->first; graph.emplace_shared >(Symbol('x', id2), Symbol('x', id1), betweenPose->second, model); From bfae5561684de0a8c63ff56499f61e5fa868b237 Mon Sep 17 00:00:00 2001 From: Fan Jiang Date: Sat, 15 Aug 2020 13:33:00 -0400 Subject: [PATCH 363/869] typo --- .travis.sh | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/.travis.sh b/.travis.sh index c2b4e0590..7f5a58d0e 100755 --- a/.travis.sh +++ b/.travis.sh @@ -63,7 +63,7 @@ function configure() -DGTSAM_BUILD_EXAMPLES_ALWAYS=${GTSAM_BUILD_EXAMPLES_ALWAYS:-ON} \ -DGTSAM_ALLOW_DEPRECATED_SINCE_V4=${GTSAM_ALLOW_DEPRECATED_SINCE_V4:-OFF} \ -DGTSAM_BUILD_WITH_MARCH_NATIVE=OFF \ - -DCMAKE_VERBOSE_MAKEFILE=ON + -DCMAKE_VERBOSE_MAKEFILE=ON \ -DBOOST_ROOT=$BOOST_ROOT } From 2d7fb05f6cf2bd944aee8afb8a067fcfb3af7caf Mon Sep 17 00:00:00 2001 From: Fan Jiang Date: Sat, 15 Aug 2020 13:54:02 -0400 Subject: [PATCH 364/869] Ignore system boost --- .travis.sh | 5 ++++- 1 file changed, 4 insertions(+), 1 deletion(-) diff --git a/.travis.sh b/.travis.sh index 7f5a58d0e..c4ac675bd 100755 --- a/.travis.sh +++ b/.travis.sh @@ -64,7 +64,10 @@ function configure() -DGTSAM_ALLOW_DEPRECATED_SINCE_V4=${GTSAM_ALLOW_DEPRECATED_SINCE_V4:-OFF} \ -DGTSAM_BUILD_WITH_MARCH_NATIVE=OFF \ -DCMAKE_VERBOSE_MAKEFILE=ON \ - -DBOOST_ROOT=$BOOST_ROOT + -DBOOST_ROOT=$BOOST_ROOT \ + -DBoost_NO_SYSTEM_PATHS=ON \ + -DBOOST_INCLUDEDIR="$BOOST_ROOT/boost/include" \ + -DBOOST_LIBRARYDIR="$BOOST_ROOT/lib" } From ae341c83a46508c92f24f0dcba6a798713df2d7b Mon Sep 17 00:00:00 2001 From: Fan Jiang Date: Sat, 15 Aug 2020 14:13:07 -0400 Subject: [PATCH 365/869] Fix wrong include path --- .travis.sh | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/.travis.sh b/.travis.sh index c4ac675bd..6aa4c6da6 100755 --- a/.travis.sh +++ b/.travis.sh @@ -66,7 +66,7 @@ function configure() -DCMAKE_VERBOSE_MAKEFILE=ON \ -DBOOST_ROOT=$BOOST_ROOT \ -DBoost_NO_SYSTEM_PATHS=ON \ - -DBOOST_INCLUDEDIR="$BOOST_ROOT/boost/include" \ + -DBOOST_INCLUDEDIR="$BOOST_ROOT/include" \ -DBOOST_LIBRARYDIR="$BOOST_ROOT/lib" } From 799486b2f3d761e2cb991d377de5cb622f728f0d Mon Sep 17 00:00:00 2001 From: Fan Jiang Date: Sat, 15 Aug 2020 14:45:58 -0400 Subject: [PATCH 366/869] Do not search for the cmake boost file --- .travis.sh | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/.travis.sh b/.travis.sh index 6aa4c6da6..eae460b2d 100755 --- a/.travis.sh +++ b/.travis.sh @@ -67,7 +67,8 @@ function configure() -DBOOST_ROOT=$BOOST_ROOT \ -DBoost_NO_SYSTEM_PATHS=ON \ -DBOOST_INCLUDEDIR="$BOOST_ROOT/include" \ - -DBOOST_LIBRARYDIR="$BOOST_ROOT/lib" + -DBOOST_LIBRARYDIR="$BOOST_ROOT/lib" \ + -DBoost_NO_BOOST_CMAKE=ON } From 7f7bf563f693f082a0d19ef7b6116ffd1084f97d Mon Sep 17 00:00:00 2001 From: Fan Jiang Date: Sat, 15 Aug 2020 15:28:56 -0400 Subject: [PATCH 367/869] Real reason why cannot find boost --- .travis.sh | 4 +--- 1 file changed, 1 insertion(+), 3 deletions(-) diff --git a/.travis.sh b/.travis.sh index eae460b2d..30713cac2 100755 --- a/.travis.sh +++ b/.travis.sh @@ -66,9 +66,7 @@ function configure() -DCMAKE_VERBOSE_MAKEFILE=ON \ -DBOOST_ROOT=$BOOST_ROOT \ -DBoost_NO_SYSTEM_PATHS=ON \ - -DBOOST_INCLUDEDIR="$BOOST_ROOT/include" \ - -DBOOST_LIBRARYDIR="$BOOST_ROOT/lib" \ - -DBoost_NO_BOOST_CMAKE=ON + -DBoost_ARCHITECTURE=-x64 } From 635c6f89b05105a1160d81bb736e39218fbb3ee4 Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Sat, 15 Aug 2020 15:44:22 -0500 Subject: [PATCH 368/869] renamed from build-cython to build-python --- .github/workflows/{build-cython.yml => build-python.yml} | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) rename .github/workflows/{build-cython.yml => build-python.yml} (98%) diff --git a/.github/workflows/build-cython.yml b/.github/workflows/build-python.yml similarity index 98% rename from .github/workflows/build-cython.yml rename to .github/workflows/build-python.yml index c159a60fc..497272411 100644 --- a/.github/workflows/build-cython.yml +++ b/.github/workflows/build-python.yml @@ -1,4 +1,4 @@ -name: Cython CI +name: Python CI on: [pull_request] From d9f5c1ebb7556da6b6ef8d0c40952a4b47207504 Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Sat, 15 Aug 2020 15:50:10 -0500 Subject: [PATCH 369/869] remove travis.python.sh and instead add script in .github folder --- .../scripts/python.sh | 36 +++++++++++-------- 1 file changed, 22 insertions(+), 14 deletions(-) rename .travis.python.sh => .github/scripts/python.sh (63%) diff --git a/.travis.python.sh b/.github/scripts/python.sh similarity index 63% rename from .travis.python.sh rename to .github/scripts/python.sh index 7ccf56dd1..70a5f46e4 100644 --- a/.travis.python.sh +++ b/.github/scripts/python.sh @@ -17,7 +17,7 @@ if [[ $(uname) == "Darwin" ]]; then brew install wget else # Install a system package required by our library - sudo apt-get install wget libicu-dev python3-pip python3-setuptools + sudo apt-get install -y wget libicu-dev python3-pip python3-setuptools fi PATH=$PATH:$($PYTHON -c "import site; print(site.USER_BASE)")/bin @@ -28,26 +28,26 @@ case $WRAPPER in BUILD_PYBIND="OFF" TYPEDEF_POINTS_TO_VECTORS="OFF" - $PYTHON -m pip install --user -r ./cython/requirements.txt + sudo $PYTHON -m pip install -r $GITHUB_WORKSPACE/cython/requirements.txt ;; "pybind") BUILD_CYTHON="OFF" BUILD_PYBIND="ON" TYPEDEF_POINTS_TO_VECTORS="ON" - $PYTHON -m pip install --user -r ./wrap/python/requirements.txt + sudo $PYTHON -m pip install -r $GITHUB_WORKSPACE/python/requirements.txt ;; *) exit 126 ;; esac -CURRDIR=$(pwd) +git submodule update --init --recursive -mkdir $CURRDIR/build -cd $CURRDIR/build +mkdir $GITHUB_WORKSPACE/build +cd $GITHUB_WORKSPACE/build -cmake $CURRDIR -DCMAKE_BUILD_TYPE=Release \ +cmake $GITHUB_WORKSPACE -DCMAKE_BUILD_TYPE=Release \ -DGTSAM_BUILD_TESTS=OFF -DGTSAM_BUILD_UNSTABLE=ON \ -DGTSAM_USE_QUATERNIONS=OFF \ -DGTSAM_BUILD_EXAMPLES_ALWAYS=OFF \ @@ -56,26 +56,34 @@ cmake $CURRDIR -DCMAKE_BUILD_TYPE=Release \ -DGTSAM_BUILD_PYTHON=${BUILD_PYBIND} \ -DGTSAM_TYPEDEF_POINTS_TO_VECTORS=${TYPEDEF_POINTS_TO_VECTORS} \ -DGTSAM_PYTHON_VERSION=$PYTHON_VERSION \ - -DGTSAM_ALLOW_DEPRECATED_SINCE_V4=OFF \ -DPYTHON_EXECUTABLE:FILEPATH=$(which $PYTHON) \ - -DCMAKE_INSTALL_PREFIX=$CURRDIR/../gtsam_install + -DGTSAM_ALLOW_DEPRECATED_SINCE_V41=OFF \ + -DCMAKE_INSTALL_PREFIX=$GITHUB_WORKSPACE/gtsam_install -make -j$(nproc) install +make -j$(nproc) install & + +while ps -p $! > /dev/null +do + sleep 60 + now=$(date +%s) + printf "%d seconds have elapsed\n" $(( (now - start) )) +done case $WRAPPER in "cython") - cd $CURRDIR/../gtsam_install/cython + cd $GITHUB_WORKSPACE/gtsam_install/cython $PYTHON setup.py install --user --prefix= - cd $CURRDIR/cython/gtsam/tests + cd $GITHUB_WORKSPACE/gtsam_install/cython/gtsam/tests $PYTHON -m unittest discover ;; "pybind") + cd python $PYTHON setup.py install --user --prefix= - cd $CURRDIR/wrap/python/gtsam_py/tests + cd $GITHUB_WORKSPACE/wrap/python/gtsam_py/tests $PYTHON -m unittest discover ;; *) echo "THIS SHOULD NEVER HAPPEN!" exit 125 ;; -esac +esac \ No newline at end of file From 0172cd3c8c7348abca9cc42b5d77da3da38adf34 Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Sat, 15 Aug 2020 15:50:59 -0500 Subject: [PATCH 370/869] updates to python CI yml file --- .github/workflows/build-python.yml | 7 +++---- .github/workflows/build-windows.yml | 2 +- 2 files changed, 4 insertions(+), 5 deletions(-) diff --git a/.github/workflows/build-python.yml b/.github/workflows/build-python.yml index 497272411..9edd1c24d 100644 --- a/.github/workflows/build-python.yml +++ b/.github/workflows/build-python.yml @@ -60,9 +60,8 @@ jobs: sudo add-apt-repository "deb http://apt.llvm.org/bionic/ llvm-toolchain-bionic-9 main" fi sudo apt-get -y update - sudo apt-get -y upgrade - sudo apt install cmake g++-9 clang-9 build-essential pkg-config libpython-dev python-numpy libboost-all-dev + sudo apt install cmake build-essential pkg-config libpython-dev python-numpy libboost-all-dev if [ "${{ matrix.compiler }}" = "gcc" ]; then sudo apt-get install -y g++-${{ matrix.version }} g++-${{ matrix.version }}-multilib @@ -89,8 +88,8 @@ jobs: - name: Build (Linux) if: runner.os == 'Linux' run: | - bash .travis.python.sh + bash .github/scripts/python.sh - name: Build (macOS) if: runner.os == 'macOS' run: | - bash .travis.python.sh \ No newline at end of file + bash .github/scripts/python.sh \ No newline at end of file diff --git a/.github/workflows/build-windows.yml b/.github/workflows/build-windows.yml index 516e67e1d..f7c5dbcce 100644 --- a/.github/workflows/build-windows.yml +++ b/.github/workflows/build-windows.yml @@ -1,4 +1,4 @@ -name: CI Windows +name: Windows CI on: [pull_request] From 808c043e733f1691bf0b09336434649497868cdd Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Sat, 15 Aug 2020 16:01:24 -0500 Subject: [PATCH 371/869] moved CI script for unix based systems --- .travis.sh => .github/scripts/unix.sh | 12 ++++++------ 1 file changed, 6 insertions(+), 6 deletions(-) rename .travis.sh => .github/scripts/unix.sh (92%) mode change 100755 => 100644 diff --git a/.travis.sh b/.github/scripts/unix.sh old mode 100755 new mode 100644 similarity index 92% rename from .travis.sh rename to .github/scripts/unix.sh index 30713cac2..4f6d926fb --- a/.travis.sh +++ b/.github/scripts/unix.sh @@ -25,7 +25,7 @@ function install_tbb() TBBROOT=/tmp/$TBB_DIR # Copy the needed files to the correct places. - # This works correctly for travis builds, instead of setting path variables. + # This works correctly for CI builds, instead of setting path variables. # This is what Homebrew does to install TBB on Macs $SUDO cp -R $TBBROOT/lib/$TBB_LIB_DIR/* /usr/local/lib/ $SUDO cp -R $TBBROOT/include/ /usr/local/include/ @@ -38,11 +38,11 @@ function configure() set -e # Make sure any error makes the script to return an error code set -x # echo - SOURCE_DIR=`pwd` - BUILD_DIR=build + SOURCE_DIR=$GITHUB_WORKSPACE + BUILD_DIR=$GITHUB_WORKSPACE/build #env - git clean -fd || true + git submodule update --init --recursive rm -fr $BUILD_DIR || true mkdir $BUILD_DIR && cd $BUILD_DIR @@ -61,7 +61,7 @@ function configure() -DGTSAM_WITH_TBB=${GTSAM_WITH_TBB:-OFF} \ -DGTSAM_USE_QUATERNIONS=${GTSAM_USE_QUATERNIONS:-OFF} \ -DGTSAM_BUILD_EXAMPLES_ALWAYS=${GTSAM_BUILD_EXAMPLES_ALWAYS:-ON} \ - -DGTSAM_ALLOW_DEPRECATED_SINCE_V4=${GTSAM_ALLOW_DEPRECATED_SINCE_V4:-OFF} \ + -DGTSAM_ALLOW_DEPRECATED_SINCE_V4=${GTSAM_ALLOW_DEPRECATED_SINCE_V41:-OFF} \ -DGTSAM_BUILD_WITH_MARCH_NATIVE=OFF \ -DCMAKE_VERBOSE_MAKEFILE=ON \ -DBOOST_ROOT=$BOOST_ROOT \ @@ -114,4 +114,4 @@ case $1 in -t) test ;; -esac +esac \ No newline at end of file From 1e3ca015f0e7822e8c3c417a71651f04c204df93 Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Sat, 15 Aug 2020 16:01:40 -0500 Subject: [PATCH 372/869] updates to macOS and Linux CIs --- .github/workflows/build-linux.yml | 5 ++--- .github/workflows/build-macos.yml | 4 ++-- 2 files changed, 4 insertions(+), 5 deletions(-) diff --git a/.github/workflows/build-linux.yml b/.github/workflows/build-linux.yml index 837d0b174..0ab87cbeb 100644 --- a/.github/workflows/build-linux.yml +++ b/.github/workflows/build-linux.yml @@ -52,9 +52,8 @@ jobs: sudo add-apt-repository "deb http://apt.llvm.org/bionic/ llvm-toolchain-bionic-9 main" fi sudo apt-get -y update - sudo apt-get -y upgrade - sudo apt install cmake g++-9 clang-9 build-essential pkg-config libpython-dev python-numpy + sudo apt install cmake build-essential pkg-config libpython-dev python-numpy echo "::set-env name=BOOST_ROOT::$(echo $BOOST_ROOT_1_69_0)" @@ -74,4 +73,4 @@ jobs: - name: Build (Linux) if: runner.os == 'Linux' run: | - bash .travis.sh -t \ No newline at end of file + bash .github/scripts/nix.sh -t \ No newline at end of file diff --git a/.github/workflows/build-macos.yml b/.github/workflows/build-macos.yml index 2ab2e63c5..2feb02eb5 100644 --- a/.github/workflows/build-macos.yml +++ b/.github/workflows/build-macos.yml @@ -1,4 +1,4 @@ -name: CI macOS +name: macOS CI on: [pull_request] @@ -48,4 +48,4 @@ jobs: - name: Build (macOS) if: runner.os == 'macOS' run: | - bash .travis.sh -t \ No newline at end of file + bash .github/scripts/nix.sh -t \ No newline at end of file From de2344fc2e97d87808365bdf3091953f33cf5f69 Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Sat, 15 Aug 2020 16:03:44 -0500 Subject: [PATCH 373/869] fix script name --- .github/workflows/build-linux.yml | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/.github/workflows/build-linux.yml b/.github/workflows/build-linux.yml index 0ab87cbeb..5b02cb254 100644 --- a/.github/workflows/build-linux.yml +++ b/.github/workflows/build-linux.yml @@ -1,4 +1,4 @@ -name: CI Linux +name: Linux CI on: [push, pull_request] @@ -73,4 +73,4 @@ jobs: - name: Build (Linux) if: runner.os == 'Linux' run: | - bash .github/scripts/nix.sh -t \ No newline at end of file + bash .github/scripts/unix.sh -t \ No newline at end of file From 7f0767e85fb149f14dc7f42d2b3e9cc391737838 Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Sat, 15 Aug 2020 16:22:01 -0500 Subject: [PATCH 374/869] fix cython path --- .github/scripts/python.sh | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/.github/scripts/python.sh b/.github/scripts/python.sh index 70a5f46e4..4321f4c64 100644 --- a/.github/scripts/python.sh +++ b/.github/scripts/python.sh @@ -71,9 +71,9 @@ done case $WRAPPER in "cython") - cd $GITHUB_WORKSPACE/gtsam_install/cython + cd $GITHUB_WORKSPACE/build/cython $PYTHON setup.py install --user --prefix= - cd $GITHUB_WORKSPACE/gtsam_install/cython/gtsam/tests + cd $GITHUB_WORKSPACE/build/cython/gtsam/tests $PYTHON -m unittest discover ;; "pybind") From 4f28a0b88d39e53c8e1ed64e719dcc75a6b35f3c Mon Sep 17 00:00:00 2001 From: Frank Dellaert Date: Sat, 15 Aug 2020 17:54:45 -0400 Subject: [PATCH 375/869] Fixed covariance bug --- gtsam/slam/dataset.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/gtsam/slam/dataset.cpp b/gtsam/slam/dataset.cpp index 9cc814245..12147adf2 100644 --- a/gtsam/slam/dataset.cpp +++ b/gtsam/slam/dataset.cpp @@ -880,7 +880,7 @@ static BinaryMeasurement convert(const BinaryMeasurement &p) { const Matrix6 M = gaussian->covariance(); return BinaryMeasurement( p.key1(), p.key2(), p.measured().rotation(), - noiseModel::Gaussian::Covariance(M.block<3, 3>(3, 3), true)); + noiseModel::Gaussian::Covariance(M.block<3, 3>(0, 0), true)); } template <> From ba6b18947dfeda49071b7489424a62424f1c7b9d Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Sat, 15 Aug 2020 18:45:18 -0500 Subject: [PATCH 376/869] fix build script --- .github/workflows/build-macos.yml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/.github/workflows/build-macos.yml b/.github/workflows/build-macos.yml index 2feb02eb5..1304d863e 100644 --- a/.github/workflows/build-macos.yml +++ b/.github/workflows/build-macos.yml @@ -48,4 +48,4 @@ jobs: - name: Build (macOS) if: runner.os == 'macOS' run: | - bash .github/scripts/nix.sh -t \ No newline at end of file + bash .github/scripts/unix.sh -t \ No newline at end of file From e04ef8494863143cce6d0d9f90ff5b70802b88ab Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Sat, 15 Aug 2020 18:45:31 -0500 Subject: [PATCH 377/869] set LD_LIBRARY_PATH --- .github/workflows/build-linux.yml | 2 ++ 1 file changed, 2 insertions(+) diff --git a/.github/workflows/build-linux.yml b/.github/workflows/build-linux.yml index 5b02cb254..267d995f8 100644 --- a/.github/workflows/build-linux.yml +++ b/.github/workflows/build-linux.yml @@ -12,6 +12,8 @@ jobs: CTEST_PARALLEL_LEVEL: 2 CMAKE_BUILD_TYPE: ${{ matrix.build_type }} GTSAM_BUILD_UNSTABLE: ${{ matrix.build_unstable }} + LD_LIBRARY_PATH: /usr/local/lib + strategy: fail-fast: false matrix: From 5315e3ed35b819c30c8367d5fbba40f8f569a5ae Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Sat, 15 Aug 2020 19:26:36 -0500 Subject: [PATCH 378/869] test LD_LIBRARY_PATH --- .github/workflows/build-linux.yml | 2 ++ 1 file changed, 2 insertions(+) diff --git a/.github/workflows/build-linux.yml b/.github/workflows/build-linux.yml index 267d995f8..bbdc22202 100644 --- a/.github/workflows/build-linux.yml +++ b/.github/workflows/build-linux.yml @@ -72,6 +72,8 @@ jobs: if: runner.os == 'Linux' run: | echo "BOOST_ROOT = $BOOST_ROOT" + echo "LD_LIBRARY_PATH = $LD_LIBRARY_PATH" + ls $LD_LIBRARY_PATH - name: Build (Linux) if: runner.os == 'Linux' run: | From 51b201988f77ac68ee943dbc0f187471779ea3b5 Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Sat, 15 Aug 2020 20:20:31 -0500 Subject: [PATCH 379/869] correctly add LD_LIBRARY_PATH boost lib directory --- .github/workflows/build-linux.yml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/.github/workflows/build-linux.yml b/.github/workflows/build-linux.yml index bbdc22202..24a1a2c96 100644 --- a/.github/workflows/build-linux.yml +++ b/.github/workflows/build-linux.yml @@ -12,7 +12,6 @@ jobs: CTEST_PARALLEL_LEVEL: 2 CMAKE_BUILD_TYPE: ${{ matrix.build_type }} GTSAM_BUILD_UNSTABLE: ${{ matrix.build_unstable }} - LD_LIBRARY_PATH: /usr/local/lib strategy: fail-fast: false @@ -58,6 +57,7 @@ jobs: sudo apt install cmake build-essential pkg-config libpython-dev python-numpy echo "::set-env name=BOOST_ROOT::$(echo $BOOST_ROOT_1_69_0)" + echo "::set-env name=LD_LIBRARY_PATH::$(echo $BOOST_ROOT_1_69_0/lib)" if [ "${{ matrix.compiler }}" = "gcc" ]; then sudo apt-get install -y g++-${{ matrix.version }} g++-${{ matrix.version }}-multilib From b23dd711b077529f969a10145e7c573b21566e67 Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Sat, 15 Aug 2020 23:40:43 -0500 Subject: [PATCH 380/869] remove unnecessary prints --- .github/workflows/build-linux.yml | 2 -- 1 file changed, 2 deletions(-) diff --git a/.github/workflows/build-linux.yml b/.github/workflows/build-linux.yml index 24a1a2c96..4fac0f7cc 100644 --- a/.github/workflows/build-linux.yml +++ b/.github/workflows/build-linux.yml @@ -72,8 +72,6 @@ jobs: if: runner.os == 'Linux' run: | echo "BOOST_ROOT = $BOOST_ROOT" - echo "LD_LIBRARY_PATH = $LD_LIBRARY_PATH" - ls $LD_LIBRARY_PATH - name: Build (Linux) if: runner.os == 'Linux' run: | From a2e748130085afa30f51c1e4c00ee9f216402dc3 Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Sun, 16 Aug 2020 08:31:44 -0500 Subject: [PATCH 381/869] add description for CI scripts --- .github/scripts/python.sh | 7 ++++++- .github/scripts/unix.sh | 5 +++++ 2 files changed, 11 insertions(+), 1 deletion(-) diff --git a/.github/scripts/python.sh b/.github/scripts/python.sh index 4321f4c64..5cc6ada24 100644 --- a/.github/scripts/python.sh +++ b/.github/scripts/python.sh @@ -1,4 +1,9 @@ #!/bin/bash + +########################################################## +# Build and test the GTSAM Python wrapper. +########################################################## + set -x -e if [ -z ${PYTHON_VERSION+x} ]; then @@ -77,7 +82,7 @@ case $WRAPPER in $PYTHON -m unittest discover ;; "pybind") - cd python + cd $GITHUB_WORKSPACE/python $PYTHON setup.py install --user --prefix= cd $GITHUB_WORKSPACE/wrap/python/gtsam_py/tests $PYTHON -m unittest discover diff --git a/.github/scripts/unix.sh b/.github/scripts/unix.sh index 4f6d926fb..aa6e49650 100644 --- a/.github/scripts/unix.sh +++ b/.github/scripts/unix.sh @@ -1,5 +1,10 @@ #!/bin/bash +########################################################## +# Build and test GTSAM for *nix based systems. +# Specifically Linux and macOS. +########################################################## + # install TBB with _debug.so files function install_tbb() { From 58ec261cd7ef1495bdaf7e953255f06a8cd65663 Mon Sep 17 00:00:00 2001 From: alexma3312 Date: Sun, 16 Aug 2020 13:00:27 -0400 Subject: [PATCH 382/869] Fix GTSAM_TYPEDEF_POINTS_TO_VECTORS. --- gtsam_unstable/geometry/Similarity3.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/gtsam_unstable/geometry/Similarity3.cpp b/gtsam_unstable/geometry/Similarity3.cpp index 4a330b15b..859db1c4a 100644 --- a/gtsam_unstable/geometry/Similarity3.cpp +++ b/gtsam_unstable/geometry/Similarity3.cpp @@ -87,7 +87,7 @@ Point3 Similarity3::transformFrom(const Point3& p, // Pose3 Similarity3::transformFrom(const Pose3& T) const { Rot3 R = R_.compose(T.rotation()); - Point3 t = Point3(s_ * (R_.matrix() * T.translation().vector() + t_.vector())); + Point3 t = Point3(s_ * (R_ * T.translation() + t_)); return Pose3(R, t); } From 8288b55d4e10181e3c2eaf2328815a69167b5671 Mon Sep 17 00:00:00 2001 From: Frank Dellaert Date: Sun, 16 Aug 2020 17:30:52 -0400 Subject: [PATCH 383/869] Addressed review comments --- gtsam/slam/dataset.cpp | 30 ++++++++++++++++++++---------- gtsam/slam/dataset.h | 4 ++-- timing/timeFrobeniusFactor.cpp | 4 ++-- 3 files changed, 24 insertions(+), 14 deletions(-) diff --git a/gtsam/slam/dataset.cpp b/gtsam/slam/dataset.cpp index 12147adf2..d7b067d70 100644 --- a/gtsam/slam/dataset.cpp +++ b/gtsam/slam/dataset.cpp @@ -110,19 +110,21 @@ string createRewrittenFileName(const string &name) { } /* ************************************************************************* */ -// Parse a file by calling the parse(is, tag) function for every line. +// Type for parser functions used in parseLines below. template using Parser = std::function(istream &is, const string &tag)>; +// Parse a file by calling the parse(is, tag) function for every line. +// The result of calling the function is ignored, so typically parse function +// works via a side effect, like adding a factor into a graph etc. template static void parseLines(const string &filename, Parser parse) { ifstream is(filename.c_str()); if (!is) throw invalid_argument("parse: can not find file " + filename); - while (!is.eof()) { - string tag; - is >> tag; + string tag; + while (is >> tag) { parse(is, tag); // ignore return value is.ignore(LINESIZE, '\n'); } @@ -164,7 +166,9 @@ boost::optional parseVertexPose(istream &is, const string &tag) { if ((tag == "VERTEX2") || (tag == "VERTEX_SE2") || (tag == "VERTEX")) { size_t id; double x, y, yaw; - is >> id >> x >> y >> yaw; + if (!(is >> id >> x >> y >> yaw)) { + throw std::runtime_error("parseVertexPose encountered malformed line"); + } return IndexedPose(id, Pose2(x, y, yaw)); } else { return boost::none; @@ -183,7 +187,10 @@ boost::optional parseVertexLandmark(istream &is, if (tag == "VERTEX_XY") { size_t id; double x, y; - is >> id >> x >> y; + if (!(is >> id >> x >> y)) { + throw std::runtime_error( + "parseVertexLandmark encountered malformed line"); + } return IndexedLandmark(id, Point2(x, y)); } else { return boost::none; @@ -287,7 +294,9 @@ boost::optional parseEdge(istream &is, const string &tag) { size_t id1, id2; double x, y, yaw; - is >> id1 >> id2 >> x >> y >> yaw; + if (!(is >> id1 >> id2 >> x >> y >> yaw)) { + throw std::runtime_error("parseEdge encountered malformed line"); + } return IndexedEdge({id1, id2}, Pose2(x, y, yaw)); } else { return boost::none; @@ -295,8 +304,8 @@ boost::optional parseEdge(istream &is, const string &tag) { } /* ************************************************************************* */ -// Measurement parsers are implemented as a functor, as they has several options -// to filter and create the measurement model. +// Measurement parsers are implemented as a functor, as they have several +// options to filter and create the measurement model. template struct ParseMeasurement; /* ************************************************************************* */ @@ -670,7 +679,8 @@ void writeG2o(const NonlinearFactorGraph &graph, const Values &estimate, auto factor = boost::dynamic_pointer_cast>(factor_); if (factor) { SharedNoiseModel model = factor->noiseModel(); - auto gaussianModel = boost::dynamic_pointer_cast(model); + auto gaussianModel = + boost::dynamic_pointer_cast(model); if (!gaussianModel) { model->print("model\n"); throw invalid_argument("writeG2o: invalid noise model!"); diff --git a/gtsam/slam/dataset.h b/gtsam/slam/dataset.h index 7bdf6728d..53abe55ba 100644 --- a/gtsam/slam/dataset.h +++ b/gtsam/slam/dataset.h @@ -77,7 +77,7 @@ enum KernelFunctionType { * Parse variables in a line-based text format (like g2o) into a map. * Instantiated in .cpp Pose2, Point2, Pose3, and Point3. * Note the map keys are integer indices, *not* gtsam::Keys. This is is - * different below where landmarks will use be L(index) symbols. + * different below where landmarks will use L(index) symbols. */ template GTSAM_EXPORT std::map parseVariables(const std::string &filename, @@ -136,7 +136,7 @@ GTSAM_EXPORT boost::optional parseEdge(std::istream& is, /// Return type for load functions, which return a graph and initial values. For /// landmarks, the gtsam::Symbol L(index) is used to insert into the Values. -/// Bearing-range measurements also refer tio landmarks with L(index). +/// Bearing-range measurements also refer to landmarks with L(index). using GraphAndValues = std::pair; diff --git a/timing/timeFrobeniusFactor.cpp b/timing/timeFrobeniusFactor.cpp index c0ac28ed9..924213a33 100644 --- a/timing/timeFrobeniusFactor.cpp +++ b/timing/timeFrobeniusFactor.cpp @@ -68,10 +68,10 @@ int main(int argc, char* argv[]) { auto G = boost::make_shared(SOn::VectorizedGenerators(4)); for (const auto &m : measurements) { const auto &keys = m.keys(); - const Rot3 &Tij = m.measured(); + const Rot3 &Rij = m.measured(); const auto &model = m.noiseModel(); graph.emplace_shared( - keys[0], keys[1], Tij, 4, model, G); + keys[0], keys[1], Rij, 4, model, G); } std::mt19937 rng(42); From 0d5ee3fbc6d6848884aaa83a9339973aca8b8adc Mon Sep 17 00:00:00 2001 From: Fan Jiang Date: Sun, 16 Aug 2020 19:50:01 -0400 Subject: [PATCH 384/869] Always build unstable --- .github/workflows/build-linux.yml | 4 ++-- .github/workflows/build-macos.yml | 4 ++-- .github/workflows/build-windows.yml | 4 ++-- 3 files changed, 6 insertions(+), 6 deletions(-) diff --git a/.github/workflows/build-linux.yml b/.github/workflows/build-linux.yml index 4fac0f7cc..911bec59c 100644 --- a/.github/workflows/build-linux.yml +++ b/.github/workflows/build-linux.yml @@ -4,7 +4,7 @@ on: [push, pull_request] jobs: build: - name: ${{ matrix.name }} ${{ matrix.build_type }} ${{ matrix.build_unstable }} + name: ${{ matrix.name }} ${{ matrix.build_type }} runs-on: ${{ matrix.os }} env: @@ -25,7 +25,7 @@ jobs: ] build_type: [Debug, Release] - build_unstable: [ON, OFF] + build_unstable: [ON] include: - name: ubuntu-18.04-gcc-5 os: ubuntu-18.04 diff --git a/.github/workflows/build-macos.yml b/.github/workflows/build-macos.yml index 1304d863e..55d9071ef 100644 --- a/.github/workflows/build-macos.yml +++ b/.github/workflows/build-macos.yml @@ -4,7 +4,7 @@ on: [pull_request] jobs: build: - name: ${{ matrix.name }} ${{ matrix.build_type }} ${{ matrix.build_unstable }} + name: ${{ matrix.name }} ${{ matrix.build_type }} runs-on: ${{ matrix.os }} env: @@ -22,7 +22,7 @@ jobs: ] build_type: [Debug, Release] - build_unstable: [ON, OFF] + build_unstable: [ON] include: - name: macOS-10.15-xcode-11.3.1 os: macOS-10.15 diff --git a/.github/workflows/build-windows.yml b/.github/workflows/build-windows.yml index f7c5dbcce..b3150a751 100644 --- a/.github/workflows/build-windows.yml +++ b/.github/workflows/build-windows.yml @@ -4,7 +4,7 @@ on: [pull_request] jobs: build: - name: ${{ matrix.name }} ${{ matrix.build_type }} ${{ matrix.build_unstable }} + name: ${{ matrix.name }} ${{ matrix.build_type }} runs-on: ${{ matrix.os }} env: @@ -23,7 +23,7 @@ jobs: ] build_type: [Debug, Release] - build_unstable: [ON, OFF] + build_unstable: [ON] include: - name: windows-2016-cl os: windows-2016 From 84049ebecffcd334a97cedf9479fe8afc2f50f46 Mon Sep 17 00:00:00 2001 From: Fan Jiang Date: Sun, 16 Aug 2020 20:02:35 -0400 Subject: [PATCH 385/869] Add Python to the name of CI --- .github/workflows/build-python.yml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/.github/workflows/build-python.yml b/.github/workflows/build-python.yml index 9edd1c24d..0b4a7f12f 100644 --- a/.github/workflows/build-python.yml +++ b/.github/workflows/build-python.yml @@ -4,7 +4,7 @@ on: [pull_request] jobs: build: - name: ${{ matrix.name }} ${{ matrix.build_type }} ${{ matrix.python_version }} + name: ${{ matrix.name }} ${{ matrix.build_type }} Python ${{ matrix.python_version }} runs-on: ${{ matrix.os }} env: From 84afc944582e1ee518908169f815ce05ea4768cc Mon Sep 17 00:00:00 2001 From: Frank Dellaert Date: Mon, 17 Aug 2020 07:43:10 -0400 Subject: [PATCH 386/869] Feature/shonan averaging (#473) Shonan Rotation Averaging. 199 commit messages below, many are obsolete as design has changed quite a bit over time, especially from the earlier period where I thought we only needed SO(4). * prototyping weighted sampler * Moved WeightedSampler into its own header * Random now uses std header . * Removed boost/random usage from linear and discrete directories * Made into class * Now using new WeightedSampler class * Inlined random direction generation * eradicated last vestiges of boost/random in gtsam_unstable * Added 3D example g2o file * Added Frobenius norm factors * Shonan averaging algorithm, using SOn class * Wrapping Frobenius and Shonan * Fixed issues with << * Use Builder parameters * Refactored Shonan interface * Fixed << issues as well as MATLAB segfault, using eval(), as discussed in issue #451 * ShonanAveragingParameters * New factor FrobeniusWormholeFactorP computes |Rj*P - Ri*P*Rij| * Fixed broken GetDimension for Lie groups with variable dimension. * Removed all but Shonan averaging factor and made everything work with new SOn * Just a single WormholeFactor, wrapped noise model * Use std * comments/todos * added timing script * add script to process ShonanAveraging timing results * Now producing a CSV file * Parse csv file and make combined plot * Fixed range * change p value and set two flags on * input file path, all the csv files proceeses at the same time * add check convergence rate part * csv file have name according to input data name * correct one mistake in initialization * generate the convergence rate for each p value * add yticks for the bar plot * add noises to the measurements * test add noise * Basic structure for checkOptimalityAt * change optimizer method to cholesky * buildQ now working. Tests should be better but visually inspected. * multiple test with cholesky * back * computeLambda now works * make combined plots while make bar plot * Calculate minimum eigenvalue - the very expensive version * Exposed computeMinEigenValue * make plots and bar togenter * method change to jacobi * add time for check optimality, min_eigen_value, sub_bound * updated plot min_eigen value and subounds * Adding Spectra headers * David's min eigenvalue code inserted and made to compile. * Made it work * Made "run" method work. * add rim.g2o name * Fixed bug in shifting eigenvalues * roundSolution which replaces projectFrom * removed extra arguments * Added to wrapper * Add SOn to template lists * roundSolution delete the extra arguement p * only calculate p=5 and change to the correct way computing f_R * Fixed conflict and made Google-style name changes * prototype descent code and unit test for initializeWithDescent * add averaging cost/time part in processing data * initializewithDescent success in test * Formatting and find example rather than hardcode * Removed accidentally checked in cmake files * give value to xi by block * correct gradient descent * correct xi * } * Fix wrapper * Make Hat/Vee have alternating signs * MakeATangentVector helpder function * Fixed cmake files * changed sign * add line search * unit test for line search * test real data with line search * correct comment * Fix boost::uniform_real * add save .dat file * correct test case * add explanation * delete redundant cout * add name to .dat output file * correct checkR * add get poses_ in shonan * add Vector Point type for savig data * Remove cmake file which magically re-appeared?? * Switched to std random library. * Prepare Klaus test * Add klaus3.g2o data. * fix comment * Fix derivatives * Fixed broken GetDimension for Lie groups with variable dimension. * Fix SOn tests to report correct dimension * Added tests for Klaus3 data * Add runWithRandomKlaus test for shonan. * Finish runWithRandomKlaus unittest. * Correct datafile. * Correct the format. * Added measured and keys methods * Shonan works on Klaus data * Create dense versions for wrappers, for testing * Now store D, Q, and L * Remove another cmake file incorrectly checked in. * Found and fixed the bug in ComputeLambda ! * Now using Q in Lambdas calculation, so Lambdas agree with Eriksson18cvpr. * Make FrobeniusFactor not use deprecated methods * FrobeniusWormholeFactor takes Rot3 as argument * Wrapped some more methods. * Wrapped more methods * Allow creating and populating BetweenFactorPose3s in python * New constructors for ShonanAveraging * add function of get measurements number * Remove option not to use noise model * wrap Use nrMeasurements * Made Logmap a bit more tolerant of slightly degenerate rotations (with trace < -1) * Allow for Anchor index * Fix anchor bug * Change outside view to Rot3 rather than SO3 * Add Lift in SOn class * Make comet working * Small fixes * Delete extra function * Add SOn::Lift * Removed hardcoded flag * Moved Frobenius factor to gtsam from unstable * Added new tests and made an old regression pass again * Cleaned up formatting and some comments, added EXPORT directives * Throw exception if wrongly dimensioned values are given * static_cast and other throw * Fixed run-time dimension * Added gauge-constraining factor * LM parameters now passed in, added Gauge fixing * 2D test scaffold * Comments * Pre-allocated generators * Document API * Add optional weight * New prior weeights infrastructure * Made d a template parameter * Recursive Hat and RetractJacobian test * Added Spectra 0.9.0 to 3rdparty * Enabling 2D averaging * Templatized Wormhole factor * ignore xcode folder * Fixed vec and VectorizedGenerators templates for fixed N!=3 or 4 * Simplifying constructors Moved file loading to tests (for now) All unit tests pass for d==3! * Templated some methods internally * Very generic parseToVector * refactored load2d * Very much improved FrobeniusWormholeFactor (Shonan) Jacobians * SO(2) averaging works ! * Templated parse methods * Switched to new Dataset paradigm * Moved Shonan to gtsam * Checked noise model is correctly gotten from file * Fixed covariance bug * Making Shonan wrapper work * Renamed FrobeniusWormholeFactor to ShonanFactor and moved into its own compilation unit in gtsam/sfm * Fixed wrong include * Simplified interface (removed irrelevant random inits) and fixed eigenvector test * Removed stray boost::none * Added citation as suggested by Jose * Made descent test deterministic * Fixed some comments, commented out flaky test Co-authored-by: Jing Wu Co-authored-by: jingwuOUO Co-authored-by: swang Co-authored-by: ss Co-authored-by: Fan Jiang --- .gitignore | 1 + cython/gtsam/tests/test_FrobeniusFactor.py | 4 +- examples/Data/Klaus3.g2o | 12 +- gtsam.h | 131 ++- gtsam/geometry/Rot2.cpp | 7 + gtsam/geometry/Rot2.h | 10 + gtsam/geometry/SOn-inl.h | 19 +- gtsam/geometry/SOn.cpp | 43 +- gtsam/geometry/SOn.h | 22 +- gtsam/geometry/tests/testSOn.cpp | 88 +- gtsam/nonlinear/NonlinearOptimizer.cpp | 2 +- gtsam/sfm/ShonanAveraging.cpp | 841 ++++++++++++++++++ gtsam/sfm/ShonanAveraging.h | 356 ++++++++ gtsam/sfm/ShonanFactor.cpp | 141 +++ gtsam/sfm/ShonanFactor.h | 91 ++ gtsam/sfm/ShonanGaugeFactor.h | 108 +++ gtsam/sfm/tests/testShonanAveraging.cpp | 360 ++++++++ gtsam/sfm/tests/testShonanFactor.cpp | 121 +++ gtsam/sfm/tests/testShonanGaugeFactor.cpp | 106 +++ gtsam/slam/FrobeniusFactor.cpp | 118 +-- gtsam/slam/FrobeniusFactor.h | 74 +- gtsam/slam/KarcherMeanFactor-inl.h | 18 +- gtsam/slam/KarcherMeanFactor.h | 43 +- gtsam/slam/tests/testFrobeniusFactor.cpp | 48 - gtsam_unstable/gtsam_unstable.h | 6 +- .../timing/process_shonan_timing_results.py | 215 +++++ gtsam_unstable/timing/timeShonanAveraging.cpp | 182 ++++ ...obeniusFactor.cpp => timeShonanFactor.cpp} | 10 +- 28 files changed, 2880 insertions(+), 297 deletions(-) create mode 100644 gtsam/sfm/ShonanAveraging.cpp create mode 100644 gtsam/sfm/ShonanAveraging.h create mode 100644 gtsam/sfm/ShonanFactor.cpp create mode 100644 gtsam/sfm/ShonanFactor.h create mode 100644 gtsam/sfm/ShonanGaugeFactor.h create mode 100644 gtsam/sfm/tests/testShonanAveraging.cpp create mode 100644 gtsam/sfm/tests/testShonanFactor.cpp create mode 100644 gtsam/sfm/tests/testShonanGaugeFactor.cpp create mode 100644 gtsam_unstable/timing/process_shonan_timing_results.py create mode 100644 gtsam_unstable/timing/timeShonanAveraging.cpp rename timing/{timeFrobeniusFactor.cpp => timeShonanFactor.cpp} (92%) diff --git a/.gitignore b/.gitignore index 1d89cac25..c2d6ce60f 100644 --- a/.gitignore +++ b/.gitignore @@ -21,3 +21,4 @@ cython/gtsam_wrapper.pxd /CMakeSettings.json # for QtCreator: CMakeLists.txt.user* +xcode/ diff --git a/cython/gtsam/tests/test_FrobeniusFactor.py b/cython/gtsam/tests/test_FrobeniusFactor.py index f3f5354bb..e808627f5 100644 --- a/cython/gtsam/tests/test_FrobeniusFactor.py +++ b/cython/gtsam/tests/test_FrobeniusFactor.py @@ -13,7 +13,7 @@ import unittest import numpy as np from gtsam import (Rot3, SO3, SO4, FrobeniusBetweenFactorSO4, FrobeniusFactorSO4, - FrobeniusWormholeFactor, SOn) + ShonanFactor3, SOn) id = SO4() v1 = np.array([0, 0, 0, 0.1, 0, 0]) @@ -43,7 +43,7 @@ class TestFrobeniusFactorSO4(unittest.TestCase): """Test creation of a factor that calculates Shonan error.""" R1 = SO3.Expmap(v1[3:]) R2 = SO3.Expmap(v2[3:]) - factor = FrobeniusWormholeFactor(1, 2, Rot3(R1.between(R2).matrix()), p=4) + factor = ShonanFactor3(1, 2, Rot3(R1.between(R2).matrix()), p=4) I4 = SOn(4) Q1 = I4.retract(v1) Q2 = I4.retract(v2) diff --git a/examples/Data/Klaus3.g2o b/examples/Data/Klaus3.g2o index 4c7233fa7..83a6e6fd2 100644 --- a/examples/Data/Klaus3.g2o +++ b/examples/Data/Klaus3.g2o @@ -1,6 +1,6 @@ -VERTEX_SE3:QUAT 0 -3.865747774038187 0.06639337702667497 -0.16064874691945374 0.024595211709139555 0.49179523413089893 -0.06279232989379242 0.8680954132776109 -VERTEX_SE3:QUAT 1 -3.614793159814815 0.04774490041587656 -0.2837650367985949 0.00991721787943912 0.4854918961891193 -0.042343290945895576 0.8731588132957809 -VERTEX_SE3:QUAT 2 -3.255096913553434 0.013296754286114112 -0.5339792269680574 -0.027851108010665374 0.585478168397957 -0.05088341463532465 0.8086102325762403 -EDGE_SE3:QUAT 0 1 0.2509546142233723 -0.01864847661079841 -0.12311628987914114 -0.022048798853273946 -0.01796327847857683 0.010210006313668573 0.9995433591728293 100.0 0.0 0.0 0.0 0.0 0.0 100.0 0.0 0.0 0.0 0.0 100.0 0.0 0.0 0.0 25.0 0.0 0.0 25.0 0.0 25.0 -EDGE_SE3:QUAT 0 2 0.6106508604847534 -0.05309662274056086 -0.3733304800486037 -0.054972994022992064 0.10432547598981769 -0.02221474884651081 0.9927742290779572 100.0 0.0 0.0 0.0 0.0 0.0 100.0 0.0 0.0 0.0 0.0 100.0 0.0 0.0 0.0 25.0 0.0 0.0 25.0 0.0 25.0 -EDGE_SE3:QUAT 1 2 0.3596962462613811 -0.03444814612976245 -0.25021419016946256 -0.03174661848656213 0.11646825423134777 -0.02951742735854383 0.9922479626852876 100.0 0.0 0.0 0.0 0.0 0.0 100.0 0.0 0.0 0.0 0.0 100.0 0.0 0.0 0.0 25.0 0.0 0.0 25.0 0.0 25.0 +VERTEX_SE3:QUAT 0 -1.6618596980158338 -0.5736497760548741 -3.3319774096611026 -0.02676080288219576 -0.024497002638379624 -0.015064701622500615 0.9992281076190063 +VERTEX_SE3:QUAT 1 -1.431820463019384 -0.549139761976065 -3.160677992237872 -0.049543805396343954 -0.03232420352077356 -0.004386230477751116 0.998239108728862 +VERTEX_SE3:QUAT 2 -1.0394840214436651 -0.5268841046291037 -2.972143862665523 -0.07993768981394891 0.0825062894866454 -0.04088089479075661 0.9925378735259738 +EDGE_SE3:QUAT 0 1 0.23003923499644974 0.02451001407880915 0.17129941742323052 -0.022048798853273946 -0.01796327847857683 0.010210006313668573 0.9995433591728293 100.0 0.0 0.0 0.0 0.0 0.0 100.0 0.0 0.0 0.0 0.0 100.0 0.0 0.0 0.0 25.0 0.0 0.0 25.0 0.0 25.0 +EDGE_SE3:QUAT 0 2 0.6223756765721686 0.04676567142577037 0.35983354699557957 -0.054972994022992064 0.10432547598981769 -0.02221474884651081 0.9927742290779572 100.0 0.0 0.0 0.0 0.0 0.0 100.0 0.0 0.0 0.0 0.0 100.0 0.0 0.0 0.0 25.0 0.0 0.0 25.0 0.0 25.0 +EDGE_SE3:QUAT 1 2 0.3923364415757189 0.022255657346961222 0.18853412957234905 -0.03174661848656213 0.11646825423134777 -0.02951742735854383 0.9922479626852876 100.0 0.0 0.0 0.0 0.0 0.0 100.0 0.0 0.0 0.0 0.0 100.0 0.0 0.0 0.0 25.0 0.0 0.0 25.0 0.0 25.0 diff --git a/gtsam.h b/gtsam.h index 86bfa05b7..c5d25b0e9 100644 --- a/gtsam.h +++ b/gtsam.h @@ -2855,7 +2855,7 @@ virtual class KarcherMeanFactor : gtsam::NonlinearFactor { }; #include -gtsam::noiseModel::Isotropic* ConvertPose3NoiseModel( +gtsam::noiseModel::Isotropic* ConvertNoiseModel( gtsam::noiseModel::Base* model, size_t d); template @@ -2874,12 +2874,14 @@ virtual class FrobeniusBetweenFactor : gtsam::NoiseModelFactor { Vector evaluateError(const T& R1, const T& R2); }; -virtual class FrobeniusWormholeFactor : gtsam::NoiseModelFactor { - FrobeniusWormholeFactor(size_t key1, size_t key2, const gtsam::Rot3& R12, +#include + +virtual class ShonanFactor3 : gtsam::NoiseModelFactor { + ShonanFactor(size_t key1, size_t key2, const gtsam::Rot3 &R12, size_t p); - FrobeniusWormholeFactor(size_t key1, size_t key2, const gtsam::Rot3& R12, - size_t p, gtsam::noiseModel::Base* model); - Vector evaluateError(const gtsam::SOn& Q1, const gtsam::SOn& Q2); + ShonanFactor(size_t key1, size_t key2, const gtsam::Rot3 &R12, + size_t p, gtsam::noiseModel::Base *model); + Vector evaluateError(const gtsam::SOn &Q1, const gtsam::SOn &Q2); }; #include @@ -2895,6 +2897,123 @@ class BinaryMeasurement { typedef gtsam::BinaryMeasurement BinaryMeasurementUnit3; typedef gtsam::BinaryMeasurement BinaryMeasurementRot3; +#include + +// TODO(frank): copy/pasta below until we have integer template paremeters in wrap! + +class ShonanAveragingParameters2 { + ShonanAveragingParameters2(const gtsam::LevenbergMarquardtParams& lm); + ShonanAveragingParameters2(const gtsam::LevenbergMarquardtParams& lm, string method); + gtsam::LevenbergMarquardtParams getLMParams() const; + void setOptimalityThreshold(double value); + double getOptimalityThreshold() const; + void setAnchor(size_t index, const gtsam::Rot2& value); + void setAnchorWeight(double value); + double getAnchorWeight() const; + void setKarcherWeight(double value); + double getKarcherWeight(); + void setGaugesWeight(double value); + double getGaugesWeight(); +}; + +class ShonanAveragingParameters3 { + ShonanAveragingParameters3(const gtsam::LevenbergMarquardtParams& lm); + ShonanAveragingParameters3(const gtsam::LevenbergMarquardtParams& lm, string method); + gtsam::LevenbergMarquardtParams getLMParams() const; + void setOptimalityThreshold(double value); + double getOptimalityThreshold() const; + void setAnchor(size_t index, const gtsam::Rot3& value); + void setAnchorWeight(double value); + double getAnchorWeight() const; + void setKarcherWeight(double value); + double getKarcherWeight(); + void setGaugesWeight(double value); + double getGaugesWeight(); +}; + +class ShonanAveraging2 { + ShonanAveraging2(string g2oFile); + ShonanAveraging2(string g2oFile, + const gtsam::ShonanAveragingParameters2 ¶meters); + + // Query properties + size_t nrUnknowns() const; + size_t nrMeasurements() const; + gtsam::Rot2 measured(size_t i); + gtsam::KeyVector keys(size_t i); + + // Matrix API (advanced use, debugging) + Matrix denseD() const; + Matrix denseQ() const; + Matrix denseL() const; + // Matrix computeLambda_(Matrix S) const; + Matrix computeLambda_(const gtsam::Values& values) const; + Matrix computeA_(const gtsam::Values& values) const; + double computeMinEigenValue(const gtsam::Values& values) const; + gtsam::Values initializeWithDescent(size_t p, const gtsam::Values& values, + const Vector& minEigenVector, double minEigenValue) const; + + // Advanced API + gtsam::NonlinearFactorGraph buildGraphAt(size_t p) const; + double costAt(size_t p, const gtsam::Values& values) const; + pair computeMinEigenVector(const gtsam::Values& values) const; + bool checkOptimality(const gtsam::Values& values) const; + gtsam::LevenbergMarquardtOptimizer* createOptimizerAt(size_t p, const gtsam::Values& initial); + // gtsam::Values tryOptimizingAt(size_t p) const; + gtsam::Values tryOptimizingAt(size_t p, const gtsam::Values& initial) const; + gtsam::Values projectFrom(size_t p, const gtsam::Values& values) const; + gtsam::Values roundSolution(const gtsam::Values& values) const; + + // Basic API + double cost(const gtsam::Values& values) const; + gtsam::Values initializeRandomly() const; + pair run(const gtsam::Values& initial, size_t min_p, size_t max_p) const; +}; + +class ShonanAveraging3 { + ShonanAveraging3(string g2oFile); + ShonanAveraging3(string g2oFile, + const gtsam::ShonanAveragingParameters3 ¶meters); + + // TODO(frank): deprecate once we land pybind wrapper + ShonanAveraging3(const gtsam::BetweenFactorPose3s &factors); + ShonanAveraging3(const gtsam::BetweenFactorPose3s &factors, + const gtsam::ShonanAveragingParameters3 ¶meters); + + // Query properties + size_t nrUnknowns() const; + size_t nrMeasurements() const; + gtsam::Rot3 measured(size_t i); + gtsam::KeyVector keys(size_t i); + + // Matrix API (advanced use, debugging) + Matrix denseD() const; + Matrix denseQ() const; + Matrix denseL() const; + // Matrix computeLambda_(Matrix S) const; + Matrix computeLambda_(const gtsam::Values& values) const; + Matrix computeA_(const gtsam::Values& values) const; + double computeMinEigenValue(const gtsam::Values& values) const; + gtsam::Values initializeWithDescent(size_t p, const gtsam::Values& values, + const Vector& minEigenVector, double minEigenValue) const; + + // Advanced API + gtsam::NonlinearFactorGraph buildGraphAt(size_t p) const; + double costAt(size_t p, const gtsam::Values& values) const; + pair computeMinEigenVector(const gtsam::Values& values) const; + bool checkOptimality(const gtsam::Values& values) const; + gtsam::LevenbergMarquardtOptimizer* createOptimizerAt(size_t p, const gtsam::Values& initial); + // gtsam::Values tryOptimizingAt(size_t p) const; + gtsam::Values tryOptimizingAt(size_t p, const gtsam::Values& initial) const; + gtsam::Values projectFrom(size_t p, const gtsam::Values& values) const; + gtsam::Values roundSolution(const gtsam::Values& values) const; + + // Basic API + double cost(const gtsam::Values& values) const; + gtsam::Values initializeRandomly() const; + pair run(const gtsam::Values& initial, size_t min_p, size_t max_p) const; +}; + //************************************************************************* // Navigation //************************************************************************* diff --git a/gtsam/geometry/Rot2.cpp b/gtsam/geometry/Rot2.cpp index 04ed16774..7502c4ccf 100644 --- a/gtsam/geometry/Rot2.cpp +++ b/gtsam/geometry/Rot2.cpp @@ -39,6 +39,13 @@ Rot2 Rot2::atan2(double y, double x) { return R.normalize(); } +/* ************************************************************************* */ +Rot2 Rot2::Random(std::mt19937& rng) { + uniform_real_distribution randomAngle(-M_PI, M_PI); + double angle = randomAngle(rng); + return fromAngle(angle); +} + /* ************************************************************************* */ void Rot2::print(const string& s) const { cout << s << ": " << theta() << endl; diff --git a/gtsam/geometry/Rot2.h b/gtsam/geometry/Rot2.h index f46f12540..8a361f558 100644 --- a/gtsam/geometry/Rot2.h +++ b/gtsam/geometry/Rot2.h @@ -22,6 +22,8 @@ #include #include +#include + namespace gtsam { /** @@ -79,6 +81,14 @@ namespace gtsam { /** Named constructor that behaves as atan2, i.e., y,x order (!) and normalizes */ static Rot2 atan2(double y, double x); + /** + * Random, generates random angle \in [-p,pi] + * Example: + * std::mt19937 engine(42); + * Unit3 unit = Unit3::Random(engine); + */ + static Rot2 Random(std::mt19937 & rng); + /// @} /// @name Testable /// @{ diff --git a/gtsam/geometry/SOn-inl.h b/gtsam/geometry/SOn-inl.h index 9edce8336..6180f4cc7 100644 --- a/gtsam/geometry/SOn-inl.h +++ b/gtsam/geometry/SOn-inl.h @@ -60,8 +60,9 @@ typename SO::TangentVector SO::ChartAtOrigin::Local(const SO& R, template typename SO::MatrixDD SO::AdjointMap() const { + if (N==2) return I_1x1; // SO(2) case throw std::runtime_error( - "SO::AdjointMap only implemented for SO3 and SO4."); + "SO::AdjointMap only implemented for SO2, SO3 and SO4."); } template @@ -84,26 +85,22 @@ typename SO::MatrixDD SO::LogmapDerivative(const TangentVector& omega) { throw std::runtime_error("O::LogmapDerivative only implemented for SO3."); } +// Default fixed size version (but specialized elsewehere for N=2,3,4) template typename SO::VectorN2 SO::vec( OptionalJacobian H) const { - const size_t n = rows(); - const size_t n2 = n * n; - // Vectorize - VectorN2 X(n2); - X << Eigen::Map(matrix_.data(), n2, 1); + VectorN2 X = Eigen::Map(matrix_.data()); // If requested, calculate H as (I \oplus Q) * P, // where Q is the N*N rotation matrix, and P is calculated below. if (H) { // Calculate P matrix of vectorized generators // TODO(duy): Should we refactor this as the jacobian of Hat? - Matrix P = VectorizedGenerators(n); - const size_t d = dim(); - H->resize(n2, d); - for (size_t i = 0; i < n; i++) { - H->block(i * n, 0, n, d) = matrix_ * P.block(i * n, 0, n, d); + Matrix P = SO::VectorizedGenerators(); + for (size_t i = 0; i < N; i++) { + H->block(i * N, 0, N, dimension) = + matrix_ * P.block(i * N, 0, N, dimension); } } return X; diff --git a/gtsam/geometry/SOn.cpp b/gtsam/geometry/SOn.cpp index 37b6c1784..c6cff4214 100644 --- a/gtsam/geometry/SOn.cpp +++ b/gtsam/geometry/SOn.cpp @@ -22,21 +22,18 @@ namespace gtsam { template <> -GTSAM_EXPORT -Matrix SOn::Hat(const Vector& xi) { +GTSAM_EXPORT void SOn::Hat(const Vector &xi, Eigen::Ref X) { size_t n = AmbientDim(xi.size()); - if (n < 2) throw std::invalid_argument("SO::Hat: n<2 not supported"); - - Matrix X(n, n); // allocate space for n*n skew-symmetric matrix - X.setZero(); - if (n == 2) { + if (n < 2) + throw std::invalid_argument("SO::Hat: n<2 not supported"); + else if (n == 2) { // Handle SO(2) case as recursion bottom assert(xi.size() == 1); X << 0, -xi(0), xi(0), 0; } else { // Recursively call SO(n-1) call for top-left block const size_t dmin = (n - 1) * (n - 2) / 2; - X.topLeftCorner(n - 1, n - 1) = Hat(xi.tail(dmin)); + Hat(xi.tail(dmin), X.topLeftCorner(n - 1, n - 1)); // determine sign of last element (signs alternate) double sign = pow(-1.0, xi.size()); @@ -47,7 +44,14 @@ Matrix SOn::Hat(const Vector& xi) { X(j, n - 1) = -X(n - 1, j); sign = -sign; } + X(n - 1, n - 1) = 0; // bottom-right } +} + +template <> GTSAM_EXPORT Matrix SOn::Hat(const Vector &xi) { + size_t n = AmbientDim(xi.size()); + Matrix X(n, n); // allocate space for n*n skew-symmetric matrix + SOn::Hat(xi, X); return X; } @@ -99,4 +103,27 @@ SOn LieGroup::between(const SOn& g, DynamicJacobian H1, return result; } +// Dynamic version of vec +template <> typename SOn::VectorN2 SOn::vec(DynamicJacobian H) const { + const size_t n = rows(), n2 = n * n; + + // Vectorize + VectorN2 X(n2); + X << Eigen::Map(matrix_.data(), n2, 1); + + // If requested, calculate H as (I \oplus Q) * P, + // where Q is the N*N rotation matrix, and P is calculated below. + if (H) { + // Calculate P matrix of vectorized generators + // TODO(duy): Should we refactor this as the jacobian of Hat? + Matrix P = SOn::VectorizedGenerators(n); + const size_t d = dim(); + H->resize(n2, d); + for (size_t i = 0; i < n; i++) { + H->block(i * n, 0, n, d) = matrix_ * P.block(i * n, 0, n, d); + } + } + return X; +} + } // namespace gtsam diff --git a/gtsam/geometry/SOn.h b/gtsam/geometry/SOn.h index 004569416..86b6019e1 100644 --- a/gtsam/geometry/SOn.h +++ b/gtsam/geometry/SOn.h @@ -98,8 +98,8 @@ class SO : public LieGroup, internal::DimensionSO(N)> { template > static SO Lift(size_t n, const Eigen::MatrixBase &R) { Matrix Q = Matrix::Identity(n, n); - size_t p = R.rows(); - assert(p < n && R.cols() == p); + const int p = R.rows(); + assert(p >= 0 && p <= static_cast(n) && R.cols() == p); Q.topLeftCorner(p, p) = R; return SO(Q); } @@ -208,7 +208,7 @@ class SO : public LieGroup, internal::DimensionSO(N)> { // Calculate run-time dimensionality of manifold. // Available as dimension or Dim() for fixed N. - size_t dim() const { return Dimension(matrix_.rows()); } + size_t dim() const { return Dimension(static_cast(matrix_.rows())); } /** * Hat operator creates Lie algebra element corresponding to d-vector, where d @@ -227,9 +227,10 @@ class SO : public LieGroup, internal::DimensionSO(N)> { */ static MatrixNN Hat(const TangentVector& xi); - /** - * Inverse of Hat. See note about xi element order in Hat. - */ + /// In-place version of Hat (see details there), implements recursion. + static void Hat(const Vector &xi, Eigen::Ref X); + + /// Inverse of Hat. See note about xi element order in Hat. static TangentVector Vee(const MatrixNN& X); // Chart at origin @@ -295,10 +296,10 @@ class SO : public LieGroup, internal::DimensionSO(N)> { template > static Matrix VectorizedGenerators() { constexpr size_t N2 = static_cast(N * N); - Matrix G(N2, dimension); + Eigen::Matrix G; for (size_t j = 0; j < dimension; j++) { const auto X = Hat(Vector::Unit(dimension, j)); - G.col(j) = Eigen::Map(X.data(), N2, 1); + G.col(j) = Eigen::Map(X.data()); } return G; } @@ -362,6 +363,11 @@ template <> SOn LieGroup::between(const SOn& g, DynamicJacobian H1, DynamicJacobian H2) const; +/* + * Specialize dynamic vec. + */ +template <> typename SOn::VectorN2 SOn::vec(DynamicJacobian H) const; + /** Serialization function */ template void serialize( diff --git a/gtsam/geometry/tests/testSOn.cpp b/gtsam/geometry/tests/testSOn.cpp index 1cf8caed2..4d0ed98b3 100644 --- a/gtsam/geometry/tests/testSOn.cpp +++ b/gtsam/geometry/tests/testSOn.cpp @@ -39,8 +39,8 @@ using namespace std; using namespace gtsam; //****************************************************************************** -// Test dhynamic with n=0 -TEST(SOn, SO0) { +// Test dynamic with n=0 +TEST(SOn, SOn0) { const auto R = SOn(0); EXPECT_LONGS_EQUAL(0, R.rows()); EXPECT_LONGS_EQUAL(Eigen::Dynamic, SOn::dimension); @@ -50,7 +50,8 @@ TEST(SOn, SO0) { } //****************************************************************************** -TEST(SOn, SO5) { +// Test dynamic with n=5 +TEST(SOn, SOn5) { const auto R = SOn(5); EXPECT_LONGS_EQUAL(5, R.rows()); EXPECT_LONGS_EQUAL(Eigen::Dynamic, SOn::dimension); @@ -59,6 +60,28 @@ TEST(SOn, SO5) { EXPECT_LONGS_EQUAL(10, traits::GetDimension(R)); } +//****************************************************************************** +// Test fixed with n=2 +TEST(SOn, SO0) { + const auto R = SO<2>(); + EXPECT_LONGS_EQUAL(2, R.rows()); + EXPECT_LONGS_EQUAL(1, SO<2>::dimension); + EXPECT_LONGS_EQUAL(1, SO<2>::Dim()); + EXPECT_LONGS_EQUAL(1, R.dim()); + EXPECT_LONGS_EQUAL(1, traits>::GetDimension(R)); +} + +//****************************************************************************** +// Test fixed with n=5 +TEST(SOn, SO5) { + const auto R = SO<5>(); + EXPECT_LONGS_EQUAL(5, R.rows()); + EXPECT_LONGS_EQUAL(10, SO<5>::dimension); + EXPECT_LONGS_EQUAL(10, SO<5>::Dim()); + EXPECT_LONGS_EQUAL(10, R.dim()); + EXPECT_LONGS_EQUAL(10, traits>::GetDimension(R)); +} + //****************************************************************************** TEST(SOn, Concept) { BOOST_CONCEPT_ASSERT((IsGroup)); @@ -105,29 +128,29 @@ TEST(SOn, HatVee) { EXPECT(assert_equal((Vector)v.head<1>(), SOn::Vee(actual2))); Matrix expected3(3, 3); - expected3 << 0, -3, 2, // - 3, 0, -1, // - -2, 1, 0; + expected3 << 0, -3, 2, // + 3, 0, -1, // + -2, 1, 0; const auto actual3 = SOn::Hat(v.head<3>()); EXPECT(assert_equal(expected3, actual3)); EXPECT(assert_equal(skewSymmetric(1, 2, 3), actual3)); EXPECT(assert_equal((Vector)v.head<3>(), SOn::Vee(actual3))); Matrix expected4(4, 4); - expected4 << 0, -6, 5, 3, // - 6, 0, -4, -2, // - -5, 4, 0, 1, // - -3, 2, -1, 0; + expected4 << 0, -6, 5, 3, // + 6, 0, -4, -2, // + -5, 4, 0, 1, // + -3, 2, -1, 0; const auto actual4 = SOn::Hat(v.head<6>()); EXPECT(assert_equal(expected4, actual4)); EXPECT(assert_equal((Vector)v.head<6>(), SOn::Vee(actual4))); Matrix expected5(5, 5); - expected5 << 0,-10, 9, 7, -4, // - 10, 0, -8, -6, 3, // - -9, 8, 0, 5, -2, // - -7, 6, -5, 0, 1, // - 4, -3, 2, -1, 0; + expected5 << 0, -10, 9, 7, -4, // + 10, 0, -8, -6, 3, // + -9, 8, 0, 5, -2, // + -7, 6, -5, 0, 1, // + 4, -3, 2, -1, 0; const auto actual5 = SOn::Hat(v); EXPECT(assert_equal(expected5, actual5)); EXPECT(assert_equal((Vector)v, SOn::Vee(actual5))); @@ -159,6 +182,22 @@ TEST(SOn, RetractLocal) { CHECK(assert_equal(v1, SOn::ChartAtOrigin::Local(Q1), 1e-7)); } +//****************************************************************************** + +Matrix RetractJacobian(size_t n) { return SOn::VectorizedGenerators(n); } + +/// Test Jacobian of Retract at origin +TEST(SOn, RetractJacobian) { + Matrix actualH = RetractJacobian(3); + boost::function h = [](const Vector &v) { + return SOn::ChartAtOrigin::Retract(v).matrix(); + }; + Vector3 v; + v.setZero(); + const Matrix expectedH = numericalDerivative11(h, v, 1e-5); + CHECK(assert_equal(expectedH, actualH)); +} + //****************************************************************************** TEST(SOn, vec) { Vector10 v; @@ -166,11 +205,28 @@ TEST(SOn, vec) { SOn Q = SOn::ChartAtOrigin::Retract(v); Matrix actualH; const Vector actual = Q.vec(actualH); - boost::function h = [](const SOn& Q) { return Q.vec(); }; + boost::function h = [](const SOn &Q) { return Q.vec(); }; const Matrix H = numericalDerivative11(h, Q, 1e-5); CHECK(assert_equal(H, actualH)); } +//****************************************************************************** +TEST(SOn, VectorizedGenerators) { + // Default fixed + auto actual2 = SO<2>::VectorizedGenerators(); + CHECK(actual2.rows()==4 && actual2.cols()==1) + + // Specialized + auto actual3 = SO<3>::VectorizedGenerators(); + CHECK(actual3.rows()==9 && actual3.cols()==3) + auto actual4 = SO<4>::VectorizedGenerators(); + CHECK(actual4.rows()==16 && actual4.cols()==6) + + // Dynamic + auto actual5 = SOn::VectorizedGenerators(5); + CHECK(actual5.rows()==25 && actual5.cols()==10) +} + //****************************************************************************** int main() { TestResult tr; diff --git a/gtsam/nonlinear/NonlinearOptimizer.cpp b/gtsam/nonlinear/NonlinearOptimizer.cpp index 328a3facf..9a9c487b6 100644 --- a/gtsam/nonlinear/NonlinearOptimizer.cpp +++ b/gtsam/nonlinear/NonlinearOptimizer.cpp @@ -90,7 +90,7 @@ void NonlinearOptimizer::defaultOptimize() { // Iterative loop do { // Do next iteration - currentError = error(); + currentError = error(); // TODO(frank): don't do this twice at first !? Computed above! iterate(); tictoc_finishedIteration(); diff --git a/gtsam/sfm/ShonanAveraging.cpp b/gtsam/sfm/ShonanAveraging.cpp new file mode 100644 index 000000000..d4f189b0b --- /dev/null +++ b/gtsam/sfm/ShonanAveraging.cpp @@ -0,0 +1,841 @@ +/* ---------------------------------------------------------------------------- + + * GTSAM Copyright 2010-2019, Georgia Tech Research Corporation, + * Atlanta, Georgia 30332-0415 + * All Rights Reserved + * Authors: Frank Dellaert, et al. (see THANKS for the full author list) + + * See LICENSE for the license information + + * -------------------------------------------------------------------------- */ + +/** + * @file ShonanAveraging.cpp + * @date March 2019 - August 2020 + * @author Frank Dellaert, David Rosen, and Jing Wu + * @brief Shonan Averaging algorithm + */ + +#include + +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#include +#include + +#include +#include +#include +#include +#include +#include + +namespace gtsam { + +// In Wrappers we have no access to this so have a default ready +static std::mt19937 kRandomNumberGenerator(42); + +using Sparse = Eigen::SparseMatrix; + +/* ************************************************************************* */ +template +ShonanAveragingParameters::ShonanAveragingParameters( + const LevenbergMarquardtParams &_lm, const std::string &method, + double optimalityThreshold, double alpha, double beta, double gamma) + : lm(_lm), optimalityThreshold(optimalityThreshold), alpha(alpha), + beta(beta), gamma(gamma) { + // By default, we will do conjugate gradient + lm.linearSolverType = LevenbergMarquardtParams::Iterative; + + // Create subgraph builder parameters + SubgraphBuilderParameters builderParameters; + builderParameters.skeletonType = SubgraphBuilderParameters::KRUSKAL; + builderParameters.skeletonWeight = SubgraphBuilderParameters::EQUAL; + builderParameters.augmentationWeight = SubgraphBuilderParameters::SKELETON; + builderParameters.augmentationFactor = 0.0; + + auto pcg = boost::make_shared(); + + // Choose optimization method + if (method == "SUBGRAPH") { + lm.iterativeParams = + boost::make_shared(builderParameters); + } else if (method == "SGPC") { + pcg->preconditioner_ = + boost::make_shared(builderParameters); + lm.iterativeParams = pcg; + } else if (method == "JACOBI") { + pcg->preconditioner_ = + boost::make_shared(); + lm.iterativeParams = pcg; + } else if (method == "QR") { + lm.setLinearSolverType("MULTIFRONTAL_QR"); + } else if (method == "CHOLESKY") { + lm.setLinearSolverType("MULTIFRONTAL_CHOLESKY"); + } else { + throw std::invalid_argument("ShonanAveragingParameters: unknown method"); + } +} + +/* ************************************************************************* */ +// Explicit instantiation for d=2 and d=3 +template struct ShonanAveragingParameters<2>; +template struct ShonanAveragingParameters<3>; + +/* ************************************************************************* */ +// Calculate number of unknown rotations referenced by measurements +template +static size_t +NrUnknowns(const typename ShonanAveraging::Measurements &measurements) { + std::set keys; + for (const auto &measurement : measurements) { + keys.insert(measurement.key1()); + keys.insert(measurement.key2()); + } + return keys.size(); +} + +/* ************************************************************************* */ +template +ShonanAveraging::ShonanAveraging(const Measurements &measurements, + const Parameters ¶meters) + : parameters_(parameters), measurements_(measurements), + nrUnknowns_(NrUnknowns(measurements)) { + for (const auto &measurement : measurements_) { + const auto &model = measurement.noiseModel(); + if (model && model->dim() != SO::dimension) { + measurement.print("Factor with incorrect noise model:\n"); + throw std::invalid_argument("ShonanAveraging: measurements passed to " + "constructor have incorrect dimension."); + } + } + Q_ = buildQ(); + D_ = buildD(); + L_ = D_ - Q_; +} + +/* ************************************************************************* */ +template +NonlinearFactorGraph ShonanAveraging::buildGraphAt(size_t p) const { + NonlinearFactorGraph graph; + auto G = boost::make_shared(SO<-1>::VectorizedGenerators(p)); + for (const auto &measurement : measurements_) { + const auto &keys = measurement.keys(); + const auto &Rij = measurement.measured(); + const auto &model = measurement.noiseModel(); + graph.emplace_shared>(keys[0], keys[1], Rij, p, model, G); + } + + // Possibly add Karcher prior + if (parameters_.beta > 0) { + const size_t dim = SOn::Dimension(p); + graph.emplace_shared>(graph.keys(), dim); + } + + // Possibly add gauge factors - they are probably useless as gradient is zero + if (parameters_.gamma > 0 && p > d + 1) { + for (auto key : graph.keys()) + graph.emplace_shared(key, p, d, parameters_.gamma); + } + + return graph; +} + +/* ************************************************************************* */ +template +double ShonanAveraging::costAt(size_t p, const Values &values) const { + const NonlinearFactorGraph graph = buildGraphAt(p); + return graph.error(values); +} + +/* ************************************************************************* */ +template +boost::shared_ptr +ShonanAveraging::createOptimizerAt(size_t p, const Values &initial) const { + // Build graph + NonlinearFactorGraph graph = buildGraphAt(p); + + // Anchor prior is added here as depends on initial value (and cost is zero) + if (parameters_.alpha > 0) { + size_t i; + Rot value; + const size_t dim = SOn::Dimension(p); + std::tie(i, value) = parameters_.anchor; + auto model = noiseModel::Isotropic::Precision(dim, parameters_.alpha); + graph.emplace_shared>(i, SOn::Lift(p, value.matrix()), + model); + } + + // Optimize + return boost::make_shared(graph, initial, + parameters_.lm); +} + +/* ************************************************************************* */ +template +Values ShonanAveraging::tryOptimizingAt(size_t p, + const Values &initial) const { + auto lm = createOptimizerAt(p, initial); + return lm->optimize(); +} + +/* ************************************************************************* */ +// Project to pxdN Stiefel manifold +template +Matrix ShonanAveraging::StiefelElementMatrix(const Values &values) { + const size_t N = values.size(); + const size_t p = values.at(0).rows(); + Matrix S(p, N * d); + for (const auto it : values.filter()) { + S.middleCols(it.key * d) = + it.value.matrix().leftCols(); // project Qj to Stiefel + } + return S; +} + +/* ************************************************************************* */ +template <> +Values ShonanAveraging<2>::projectFrom(size_t p, const Values &values) const { + Values result; + for (const auto it : values.filter()) { + assert(it.value.rows() == p); + const auto &M = it.value.matrix(); + const Rot2 R = Rot2::atan2(M(1, 0), M(0, 0)); + result.insert(it.key, R); + } + return result; +} + +template <> +Values ShonanAveraging<3>::projectFrom(size_t p, const Values &values) const { + Values result; + for (const auto it : values.filter()) { + assert(it.value.rows() == p); + const auto &M = it.value.matrix(); + const Rot3 R = Rot3::ClosestTo(M.topLeftCorner<3, 3>()); + result.insert(it.key, R); + } + return result; +} + +/* ************************************************************************* */ +template static Matrix RoundSolutionS(const Matrix &S) { + const size_t N = S.cols() / d; + // First, compute a thin SVD of S + Eigen::JacobiSVD svd(S, Eigen::ComputeThinV); + const Vector sigmas = svd.singularValues(); + + // Construct a diagonal matrix comprised of the first d singular values + using DiagonalMatrix = Eigen::DiagonalMatrix; + DiagonalMatrix Sigma_d; + Sigma_d.diagonal() = sigmas.head(); + + // Now, construct a rank-d truncated singular value decomposition for S + Matrix R = Sigma_d * svd.matrixV().leftCols().transpose(); + + // Count the number of blocks whose determinants have positive sign + size_t numPositiveBlocks = 0; + for (size_t i = 0; i < N; ++i) { + // Compute the determinant of the ith dxd block of R + double determinant = R.middleCols(d * i).determinant(); + if (determinant > 0) + ++numPositiveBlocks; + } + + if (numPositiveBlocks < N / 2) { + // Less than half of the total number of blocks have the correct sign. + // To reverse their orientations, multiply with a reflection matrix. + DiagonalMatrix reflector; + reflector.setIdentity(); + reflector.diagonal()(d - 1) = -1; + R = reflector * R; + } + + return R; +} + +/* ************************************************************************* */ +template <> Values ShonanAveraging<2>::roundSolutionS(const Matrix &S) const { + // Round to a 2*2N matrix + Matrix R = RoundSolutionS<2>(S); + + // Finally, project each dxd rotation block to SO(2) + Values values; + for (size_t j = 0; j < nrUnknowns(); ++j) { + const Rot2 Ri = Rot2::atan2(R(1, 2 * j), R(0, 2 * j)); + values.insert(j, Ri); + } + return values; +} + +template <> Values ShonanAveraging<3>::roundSolutionS(const Matrix &S) const { + // Round to a 3*3N matrix + Matrix R = RoundSolutionS<3>(S); + + // Finally, project each dxd rotation block to SO(3) + Values values; + for (size_t j = 0; j < nrUnknowns(); ++j) { + const Rot3 Ri = Rot3::ClosestTo(R.middleCols<3>(3 * j)); + values.insert(j, Ri); + } + return values; +} + +/* ************************************************************************* */ +template +Values ShonanAveraging::roundSolution(const Values &values) const { + // Project to pxdN Stiefel manifold... + Matrix S = StiefelElementMatrix(values); + // ...and call version above. + return roundSolutionS(S); +} + +/* ************************************************************************* */ +template +double ShonanAveraging::cost(const Values &values) const { + NonlinearFactorGraph graph; + for (const auto &measurement : measurements_) { + const auto &keys = measurement.keys(); + const auto &Rij = measurement.measured(); + const auto &model = measurement.noiseModel(); + graph.emplace_shared>>( + keys[0], keys[1], SO(Rij.matrix()), model); + } + // Finally, project each dxd rotation block to SO(d) + Values result; + for (const auto it : values.filter()) { + result.insert(it.key, SO(it.value.matrix())); + } + return graph.error(result); +} + +/* ************************************************************************* */ +// Get kappa from noise model +template +static double Kappa(const BinaryMeasurement &measurement) { + const auto &isotropic = boost::dynamic_pointer_cast( + measurement.noiseModel()); + if (!isotropic) { + throw std::invalid_argument( + "Shonan averaging noise models must be isotropic."); + } + const double sigma = isotropic->sigma(); + return 1.0 / (sigma * sigma); +} + +/* ************************************************************************* */ +template Sparse ShonanAveraging::buildD() const { + // Each measurement contributes 2*d elements along the diagonal of the + // degree matrix. + static constexpr size_t stride = 2 * d; + + // Reserve space for triplets + std::vector> triplets; + triplets.reserve(stride * measurements_.size()); + + for (const auto &measurement : measurements_) { + // Get pose keys + const auto &keys = measurement.keys(); + + // Get kappa from noise model + double kappa = Kappa(measurement); + + const size_t di = d * keys[0], dj = d * keys[1]; + for (size_t k = 0; k < d; k++) { + // Elements of ith block-diagonal + triplets.emplace_back(di + k, di + k, kappa); + // Elements of jth block-diagonal + triplets.emplace_back(dj + k, dj + k, kappa); + } + } + + // Construct and return a sparse matrix from these triplets + const size_t dN = d * nrUnknowns(); + Sparse D(dN, dN); + D.setFromTriplets(triplets.begin(), triplets.end()); + + return D; +} + +/* ************************************************************************* */ +template Sparse ShonanAveraging::buildQ() const { + // Each measurement contributes 2*d^2 elements on a pair of symmetric + // off-diagonal blocks + static constexpr size_t stride = 2 * d * d; + + // Reserve space for triplets + std::vector> triplets; + triplets.reserve(stride * measurements_.size()); + + for (const auto &measurement : measurements_) { + // Get pose keys + const auto &keys = measurement.keys(); + + // Extract rotation measurement + const auto Rij = measurement.measured().matrix(); + + // Get kappa from noise model + double kappa = Kappa(measurement); + + const size_t di = d * keys[0], dj = d * keys[1]; + for (size_t r = 0; r < d; r++) { + for (size_t c = 0; c < d; c++) { + // Elements of ij block + triplets.emplace_back(di + r, dj + c, kappa * Rij(r, c)); + // Elements of ji block + triplets.emplace_back(dj + r, di + c, kappa * Rij(c, r)); + } + } + } + + // Construct and return a sparse matrix from these triplets + const size_t dN = d * nrUnknowns(); + Sparse Q(dN, dN); + Q.setFromTriplets(triplets.begin(), triplets.end()); + + return Q; +} + +/* ************************************************************************* */ +template +Sparse ShonanAveraging::computeLambda(const Matrix &S) const { + // Each pose contributes 2*d elements along the diagonal of Lambda + static constexpr size_t stride = d * d; + + // Reserve space for triplets + const size_t N = nrUnknowns(); + std::vector> triplets; + triplets.reserve(stride * N); + + // Do sparse-dense multiply to get Q*S' + auto QSt = Q_ * S.transpose(); + + for (size_t j = 0; j < N; j++) { + // Compute B, the building block for the j^th diagonal block of Lambda + const size_t dj = d * j; + Matrix B = QSt.middleRows(dj, d) * S.middleCols(dj); + + // Elements of jth block-diagonal + for (size_t r = 0; r < d; r++) + for (size_t c = 0; c < d; c++) + triplets.emplace_back(dj + r, dj + c, 0.5 * (B(r, c) + B(c, r))); + } + + // Construct and return a sparse matrix from these triplets + Sparse Lambda(d * N, d * N); + Lambda.setFromTriplets(triplets.begin(), triplets.end()); + return Lambda; +} + +/* ************************************************************************* */ +template +Sparse ShonanAveraging::computeLambda(const Values &values) const { + // Project to pxdN Stiefel manifold... + Matrix S = StiefelElementMatrix(values); + // ...and call version above. + return computeLambda(S); +} + +/* ************************************************************************* */ +template +Sparse ShonanAveraging::computeA(const Values &values) const { + assert(values.size() == nrUnknowns()); + const Matrix S = StiefelElementMatrix(values); + auto Lambda = computeLambda(S); + return Lambda - Q_; +} + +/* ************************************************************************* */ +/// MINIMUM EIGENVALUE COMPUTATIONS + +/** This is a lightweight struct used in conjunction with Spectra to compute + * the minimum eigenvalue and eigenvector of a sparse matrix A; it has a single + * nontrivial function, perform_op(x,y), that computes and returns the product + * y = (A + sigma*I) x */ +struct MatrixProdFunctor { + // Const reference to an externally-held matrix whose minimum-eigenvalue we + // want to compute + const Sparse &A_; + + // Spectral shift + double sigma_; + + // Constructor + explicit MatrixProdFunctor(const Sparse &A, double sigma = 0) + : A_(A), sigma_(sigma) {} + + int rows() const { return A_.rows(); } + int cols() const { return A_.cols(); } + + // Matrix-vector multiplication operation + void perform_op(const double *x, double *y) const { + // Wrap the raw arrays as Eigen Vector types + Eigen::Map X(x, rows()); + Eigen::Map Y(y, rows()); + + // Do the multiplication using wrapped Eigen vectors + Y = A_ * X + sigma_ * X; + } +}; + +/// Function to compute the minimum eigenvalue of A using Lanczos in Spectra. +/// This does 2 things: +/// +/// (1) Quick (coarse) eigenvalue computation to estimate the largest-magnitude +/// eigenvalue (2) A second eigenvalue computation applied to A-sigma*I, where +/// sigma is chosen to make the minimum eigenvalue of A the extremal eigenvalue +/// of A-sigma*I +/// +/// Upon completion, this returns a boolean value indicating whether the minimum +/// eigenvalue was computed to the required precision -- if so, its sets the +/// values of minEigenValue and minEigenVector appropriately + +/// Note that in the following function signature, S is supposed to be the +/// block-row-matrix that is a critical point for the optimization algorithm; +/// either S (Stiefel manifold) or R (block rotations). We use this to +/// construct a starting vector v for the Lanczos process that will be close to +/// the minimum eigenvector we're looking for whenever the relaxation is exact +/// -- this is a key feature that helps to make this method fast. Note that +/// instead of passing in all of S, it would be enough to pass in one of S's +/// *rows*, if that's more convenient. + +// For the defaults, David Rosen says: +// - maxIterations refers to the max number of Lanczos iterations to run; +// ~1000 should be sufficiently large +// - We've been using 10^-4 for the nonnegativity tolerance +// - for numLanczosVectors, 20 is a good default value + +static bool +SparseMinimumEigenValue(const Sparse &A, const Matrix &S, double *minEigenValue, + Vector *minEigenVector = 0, size_t *numIterations = 0, + size_t maxIterations = 1000, + double minEigenvalueNonnegativityTolerance = 10e-4, + Eigen::Index numLanczosVectors = 20) { + // a. Estimate the largest-magnitude eigenvalue of this matrix using Lanczos + MatrixProdFunctor lmOperator(A); + Spectra::SymEigsSolver + lmEigenValueSolver(&lmOperator, 1, std::min(numLanczosVectors, A.rows())); + lmEigenValueSolver.init(); + + const int lmConverged = lmEigenValueSolver.compute( + maxIterations, 1e-4, Spectra::SELECT_EIGENVALUE::LARGEST_MAGN); + + // Check convergence and bail out if necessary + if (lmConverged != 1) + return false; + + const double lmEigenValue = lmEigenValueSolver.eigenvalues()(0); + + if (lmEigenValue < 0) { + // The largest-magnitude eigenvalue is negative, and therefore also the + // minimum eigenvalue, so just return this solution + *minEigenValue = lmEigenValue; + if (minEigenVector) { + *minEigenVector = lmEigenValueSolver.eigenvectors(1).col(0); + minEigenVector->normalize(); // Ensure that this is a unit vector + } + return true; + } + + // The largest-magnitude eigenvalue is positive, and is therefore the + // maximum eigenvalue. Therefore, after shifting the spectrum of A + // by -2*lmEigenValue (by forming A - 2*lambda_max*I), the shifted + // spectrum will lie in the interval [minEigenValue(A) - 2* lambda_max(A), + // -lambda_max*A]; in particular, the largest-magnitude eigenvalue of + // A - 2*lambda_max*I is minEigenValue - 2*lambda_max, with corresponding + // eigenvector v_min + + MatrixProdFunctor minShiftedOperator(A, -2 * lmEigenValue); + + Spectra::SymEigsSolver + minEigenValueSolver(&minShiftedOperator, 1, + std::min(numLanczosVectors, A.rows())); + + // If S is a critical point of F, then S^T is also in the null space of S - + // Lambda(S) (cf. Lemma 6 of the tech report), and therefore its rows are + // eigenvectors corresponding to the eigenvalue 0. In the case that the + // relaxation is exact, this is the *minimum* eigenvalue, and therefore the + // rows of S are exactly the eigenvectors that we're looking for. On the + // other hand, if the relaxation is *not* exact, then S - Lambda(S) has at + // least one strictly negative eigenvalue, and the rows of S are *unstable + // fixed points* for the Lanczos iterations. Thus, we will take a slightly + // "fuzzed" version of the first row of S as an initialization for the + // Lanczos iterations; this allows for rapid convergence in the case that + // the relaxation is exact (since are starting close to a solution), while + // simultaneously allowing the iterations to escape from this fixed point in + // the case that the relaxation is not exact. + Vector v0 = S.row(0).transpose(); + Vector perturbation(v0.size()); + perturbation.setRandom(); + perturbation.normalize(); + Vector xinit = v0 + (.03 * v0.norm()) * perturbation; // Perturb v0 by ~3% + + // Use this to initialize the eigensolver + minEigenValueSolver.init(xinit.data()); + + // Now determine the relative precision required in the Lanczos method in + // order to be able to estimate the smallest eigenvalue within an *absolute* + // tolerance of 'minEigenvalueNonnegativityTolerance' + const int minConverged = minEigenValueSolver.compute( + maxIterations, minEigenvalueNonnegativityTolerance / lmEigenValue, + Spectra::SELECT_EIGENVALUE::LARGEST_MAGN); + + if (minConverged != 1) + return false; + + *minEigenValue = minEigenValueSolver.eigenvalues()(0) + 2 * lmEigenValue; + if (minEigenVector) { + *minEigenVector = minEigenValueSolver.eigenvectors(1).col(0); + minEigenVector->normalize(); // Ensure that this is a unit vector + } + if (numIterations) + *numIterations = minEigenValueSolver.num_iterations(); + return true; +} + +/* ************************************************************************* */ +template Sparse ShonanAveraging::computeA(const Matrix &S) const { + auto Lambda = computeLambda(S); + return Lambda - Q_; +} + +/* ************************************************************************* */ +template +double ShonanAveraging::computeMinEigenValue(const Values &values, + Vector *minEigenVector) const { + assert(values.size() == nrUnknowns()); + const Matrix S = StiefelElementMatrix(values); + auto A = computeA(S); + + double minEigenValue; + bool success = SparseMinimumEigenValue(A, S, &minEigenValue, minEigenVector); + if (!success) { + throw std::runtime_error( + "SparseMinimumEigenValue failed to compute minimum eigenvalue."); + } + return minEigenValue; +} + +/* ************************************************************************* */ +template +std::pair +ShonanAveraging::computeMinEigenVector(const Values &values) const { + Vector minEigenVector; + double minEigenValue = computeMinEigenValue(values, &minEigenVector); + return std::make_pair(minEigenValue, minEigenVector); +} + +/* ************************************************************************* */ +template +bool ShonanAveraging::checkOptimality(const Values &values) const { + double minEigenValue = computeMinEigenValue(values); + return minEigenValue > parameters_.optimalityThreshold; +} + +/* ************************************************************************* */ +/// Create a tangent direction xi with eigenvector segment v_i +template +Vector ShonanAveraging::MakeATangentVector(size_t p, const Vector &v, + size_t i) { + // Create a tangent direction xi with eigenvector segment v_i + const size_t dimension = SOn::Dimension(p); + const auto v_i = v.segment(d * i); + Vector xi = Vector::Zero(dimension); + double sign = pow(-1.0, round((p + 1) / 2) + 1); + for (size_t j = 0; j < d; j++) { + xi(j + p - d - 1) = sign * v_i(d - j - 1); + sign = -sign; + } + return xi; +} + +/* ************************************************************************* */ +template +Matrix ShonanAveraging::riemannianGradient(size_t p, + const Values &values) const { + Matrix S_dot = StiefelElementMatrix(values); + // calculate the gradient of F(Q_dot) at Q_dot + Matrix euclideanGradient = 2 * (L_ * (S_dot.transpose())).transpose(); + // cout << "euclidean gradient rows and cols" << euclideanGradient.rows() << + // "\t" << euclideanGradient.cols() << endl; + + // project the gradient onto the entire euclidean space + Matrix symBlockDiagProduct(p, d * nrUnknowns()); + for (size_t i = 0; i < nrUnknowns(); i++) { + // Compute block product + const size_t di = d * i; + const Matrix P = S_dot.middleCols(di).transpose() * + euclideanGradient.middleCols(di); + // Symmetrize this block + Matrix S = .5 * (P + P.transpose()); + // Compute S_dot * S and set corresponding block + symBlockDiagProduct.middleCols(di) = S_dot.middleCols(di) * S; + } + Matrix riemannianGradient = euclideanGradient - symBlockDiagProduct; + return riemannianGradient; +} + +/* ************************************************************************* */ +template +Values ShonanAveraging::LiftwithDescent(size_t p, const Values &values, + const Vector &minEigenVector) { + Values lifted = LiftTo(p, values); + for (auto it : lifted.filter()) { + // Create a tangent direction xi with eigenvector segment v_i + // Assumes key is 0-based integer + const Vector xi = MakeATangentVector(p, minEigenVector, it.key); + // Move the old value in the descent direction + it.value = it.value.retract(xi); + } + return lifted; +} + +/* ************************************************************************* */ +template +Values ShonanAveraging::initializeWithDescent( + size_t p, const Values &values, const Vector &minEigenVector, + double minEigenValue, double gradienTolerance, + double preconditionedGradNormTolerance) const { + double funcVal = costAt(p - 1, values); + double alphaMin = 1e-2; + double alpha = + std::max(1024 * alphaMin, 10 * gradienTolerance / fabs(minEigenValue)); + vector alphas; + vector fvals; + // line search + while ((alpha >= alphaMin)) { + Values Qplus = LiftwithDescent(p, values, alpha * minEigenVector); + double funcValTest = costAt(p, Qplus); + Matrix gradTest = riemannianGradient(p, Qplus); + double gradTestNorm = gradTest.norm(); + // Record alpha and funcVal + alphas.push_back(alpha); + fvals.push_back(funcValTest); + if ((funcVal > funcValTest) && (gradTestNorm > gradienTolerance)) { + return Qplus; + } + alpha /= 2; + } + + auto fminIter = min_element(fvals.begin(), fvals.end()); + auto minIdx = distance(fvals.begin(), fminIter); + double fMin = fvals[minIdx]; + double aMin = alphas[minIdx]; + if (fMin < funcVal) { + Values Qplus = LiftwithDescent(p, values, aMin * minEigenVector); + return Qplus; + } + + return LiftwithDescent(p, values, alpha * minEigenVector); +} + +/* ************************************************************************* */ +template +Values ShonanAveraging::initializeRandomly(std::mt19937 &rng) const { + Values initial; + for (size_t j = 0; j < nrUnknowns(); j++) { + initial.insert(j, Rot::Random(rng)); + } + return initial; +} + +/* ************************************************************************* */ +template +Values ShonanAveraging::initializeRandomly() const { + return ShonanAveraging::initializeRandomly(kRandomNumberGenerator); +} + +/* ************************************************************************* */ +template +std::pair ShonanAveraging::run(const Values &initialEstimate, + size_t pMin, + size_t pMax) const { + Values Qstar; + Values initialSOp = LiftTo(pMin, initialEstimate); // lift to pMin! + for (size_t p = pMin; p <= pMax; p++) { + // Optimize until convergence at this level + Qstar = tryOptimizingAt(p, initialSOp); + + // Check certificate of global optimzality + Vector minEigenVector; + double minEigenValue = computeMinEigenValue(Qstar, &minEigenVector); + if (minEigenValue > parameters_.optimalityThreshold) { + // If at global optimum, round and return solution + const Values SO3Values = roundSolution(Qstar); + return std::make_pair(SO3Values, minEigenValue); + } + + // Not at global optimimum yet, so check whether we will go to next level + if (p != pMax) { + // Calculate initial estimate for next level by following minEigenVector + initialSOp = + initializeWithDescent(p + 1, Qstar, minEigenVector, minEigenValue); + } + } + throw std::runtime_error("Shonan::run did not converge for given pMax"); +} + +/* ************************************************************************* */ +// Explicit instantiation for d=2 +template class ShonanAveraging<2>; + +ShonanAveraging2::ShonanAveraging2(const Measurements &measurements, + const Parameters ¶meters) + : ShonanAveraging<2>(measurements, parameters) {} +ShonanAveraging2::ShonanAveraging2(string g2oFile, const Parameters ¶meters) + : ShonanAveraging<2>(parseMeasurements(g2oFile), parameters) {} + +/* ************************************************************************* */ +// Explicit instantiation for d=3 +template class ShonanAveraging<3>; + +ShonanAveraging3::ShonanAveraging3(const Measurements &measurements, + const Parameters ¶meters) + : ShonanAveraging<3>(measurements, parameters) {} + +ShonanAveraging3::ShonanAveraging3(string g2oFile, const Parameters ¶meters) + : ShonanAveraging<3>(parseMeasurements(g2oFile), parameters) {} + +// TODO(frank): Deprecate after we land pybind wrapper + +// Extract Rot3 measurement from Pose3 betweenfactors +// Modeled after similar function in dataset.cpp +static BinaryMeasurement +convert(const BetweenFactor::shared_ptr &f) { + auto gaussian = + boost::dynamic_pointer_cast(f->noiseModel()); + if (!gaussian) + throw std::invalid_argument( + "parseMeasurements can only convert Pose3 measurements " + "with Gaussian noise models."); + const Matrix6 M = gaussian->covariance(); + return BinaryMeasurement( + f->key1(), f->key2(), f->measured().rotation(), + noiseModel::Gaussian::Covariance(M.block<3, 3>(3, 3), true)); +} + +static ShonanAveraging3::Measurements +extractRot3Measurements(const BetweenFactorPose3s &factors) { + ShonanAveraging3::Measurements result; + result.reserve(factors.size()); + for (auto f : factors) + result.push_back(convert(f)); + return result; +} + +ShonanAveraging3::ShonanAveraging3(const BetweenFactorPose3s &factors, + const Parameters ¶meters) + : ShonanAveraging<3>(extractRot3Measurements(factors), parameters) {} + +/* ************************************************************************* */ +} // namespace gtsam diff --git a/gtsam/sfm/ShonanAveraging.h b/gtsam/sfm/ShonanAveraging.h new file mode 100644 index 000000000..90c0bda63 --- /dev/null +++ b/gtsam/sfm/ShonanAveraging.h @@ -0,0 +1,356 @@ +/* ---------------------------------------------------------------------------- + + * GTSAM Copyright 2010-2019, Georgia Tech Research Corporation, + * Atlanta, Georgia 30332-0415 + * All Rights Reserved + * Authors: Frank Dellaert, et al. (see THANKS for the full author list) + + * See LICENSE for the license information + + * -------------------------------------------------------------------------- */ + +/** + * @file ShonanAveraging.h + * @date March 2019 - August 2020 + * @author Frank Dellaert, David Rosen, and Jing Wu + * @brief Shonan Averaging algorithm + */ + +#pragma once + +#include +#include +#include +#include +#include +#include +#include +#include + +#include +#include +#include +#include +#include + +namespace gtsam { +class NonlinearFactorGraph; +class LevenbergMarquardtOptimizer; + +/// Parameters governing optimization etc. +template struct GTSAM_EXPORT ShonanAveragingParameters { + // Select Rot2 or Rot3 interface based template parameter d + using Rot = typename std::conditional::type; + using Anchor = std::pair; + + // Paremeters themselves: + LevenbergMarquardtParams lm; // LM parameters + double optimalityThreshold; // threshold used in checkOptimality + Anchor anchor; // pose to use as anchor if not Karcher + double alpha; // weight of anchor-based prior (default 0) + double beta; // weight of Karcher-based prior (default 1) + double gamma; // weight of gauge-fixing factors (default 0) + + ShonanAveragingParameters(const LevenbergMarquardtParams &lm = + LevenbergMarquardtParams::CeresDefaults(), + const std::string &method = "JACOBI", + double optimalityThreshold = -1e-4, + double alpha = 0.0, double beta = 1.0, + double gamma = 0.0); + + LevenbergMarquardtParams getLMParams() const { return lm; } + + void setOptimalityThreshold(double value) { optimalityThreshold = value; } + double getOptimalityThreshold() const { return optimalityThreshold; } + + void setAnchor(size_t index, const Rot &value) { anchor = {index, value}; } + + void setAnchorWeight(double value) { alpha = value; } + double getAnchorWeight() { return alpha; } + + void setKarcherWeight(double value) { beta = value; } + double getKarcherWeight() { return beta; } + + void setGaugesWeight(double value) { gamma = value; } + double getGaugesWeight() { return gamma; } +}; + +using ShonanAveragingParameters2 = ShonanAveragingParameters<2>; +using ShonanAveragingParameters3 = ShonanAveragingParameters<3>; + +/** + * Class that implements Shonan Averaging from our ECCV'20 paper. + * Note: The "basic" API uses all Rot values (Rot2 or Rot3, depending on value + * of d), whereas the different levels and "advanced" API at SO(p) needs Values + * of type SOn. + * + * The template parameter d can be 2 or 3. + * Both are specialized in the .cpp file. + * + * If you use this code in your work, please consider citing our paper: + * Shonan Rotation Averaging, Global Optimality by Surfing SO(p)^n + * Frank Dellaert, David M. Rosen, Jing Wu, Robert Mahony, and Luca Carlone, + * European Computer Vision Conference, 2020. + * You can view our ECCV spotlight video at https://youtu.be/5ppaqMyHtE0 + */ +template class GTSAM_EXPORT ShonanAveraging { +public: + using Sparse = Eigen::SparseMatrix; + + // Define the Parameters type and use its typedef of the rotation type: + using Parameters = ShonanAveragingParameters; + using Rot = typename Parameters::Rot; + + // We store SO(d) BetweenFactors to get noise model + // TODO(frank): use BinaryMeasurement? + using Measurements = std::vector>; + +private: + Parameters parameters_; + Measurements measurements_; + size_t nrUnknowns_; + Sparse D_; // Sparse (diagonal) degree matrix + Sparse Q_; // Sparse measurement matrix, == \tilde{R} in Eriksson18cvpr + Sparse L_; // connection Laplacian L = D - Q, needed for optimality check + + /** + * Build 3Nx3N sparse matrix consisting of rotation measurements, arranged as + * (i,j) and (j,i) blocks within a sparse matrix. + */ + Sparse buildQ() const; + + /// Build 3Nx3N sparse degree matrix D + Sparse buildD() const; + +public: + /// @name Standard Constructors + /// @{ + + /// Construct from set of relative measurements (given as BetweenFactor + /// for now) NoiseModel *must* be isotropic. + ShonanAveraging(const Measurements &measurements, + const Parameters ¶meters = Parameters()); + + /// @} + /// @name Query properties + /// @{ + + /// Return number of unknowns + size_t nrUnknowns() const { return nrUnknowns_; } + + /// Return number of measurements + size_t nrMeasurements() const { return measurements_.size(); } + + /// k^th binary measurement + const BinaryMeasurement &measurement(size_t k) const { + return measurements_[k]; + } + + /// k^th measurement, as a Rot. + const Rot &measured(size_t k) const { return measurements_[k].measured(); } + + /// Keys for k^th measurement, as a vector of Key values. + const KeyVector &keys(size_t k) const { return measurements_[k].keys(); } + + /// @} + /// @name Matrix API (advanced use, debugging) + /// @{ + + Sparse D() const { return D_; } ///< Sparse version of D + Matrix denseD() const { return Matrix(D_); } ///< Dense version of D + Sparse Q() const { return Q_; } ///< Sparse version of Q + Matrix denseQ() const { return Matrix(Q_); } ///< Dense version of Q + Sparse L() const { return L_; } ///< Sparse version of L + Matrix denseL() const { return Matrix(L_); } ///< Dense version of L + + /// Version that takes pxdN Stiefel manifold elements + Sparse computeLambda(const Matrix &S) const; + + /// Dense versions of computeLambda for wrapper/testing + Matrix computeLambda_(const Values &values) const { + return Matrix(computeLambda(values)); + } + + /// Dense versions of computeLambda for wrapper/testing + Matrix computeLambda_(const Matrix &S) const { + return Matrix(computeLambda(S)); + } + + /// Compute A matrix whose Eigenvalues we will examine + Sparse computeA(const Values &values) const; + + /// Version that takes pxdN Stiefel manifold elements + Sparse computeA(const Matrix &S) const; + + /// Dense version of computeA for wrapper/testing + Matrix computeA_(const Values &values) const { + return Matrix(computeA(values)); + } + + /// Project to pxdN Stiefel manifold + static Matrix StiefelElementMatrix(const Values &values); + + /** + * Compute minimum eigenvalue for optimality check. + * @param values: should be of type SOn + */ + double computeMinEigenValue(const Values &values, + Vector *minEigenVector = nullptr) const; + + /// Project pxdN Stiefel manifold matrix S to Rot3^N + Values roundSolutionS(const Matrix &S) const; + + /// Create a tangent direction xi with eigenvector segment v_i + static Vector MakeATangentVector(size_t p, const Vector &v, size_t i); + + /// Calculate the riemannian gradient of F(values) at values + Matrix riemannianGradient(size_t p, const Values &values) const; + + /** + * Lift up the dimension of values in type SO(p-1) with descent direction + * provided by minEigenVector and return new values in type SO(p) + */ + static Values LiftwithDescent(size_t p, const Values &values, + const Vector &minEigenVector); + + /** + * Given some values at p-1, return new values at p, by doing a line search + * along the descent direction, computed from the minimum eigenvector at p-1. + * @param values should be of type SO(p-1) + * @param minEigenVector corresponding to minEigenValue at level p-1 + * @return values of type SO(p) + */ + Values + initializeWithDescent(size_t p, const Values &values, + const Vector &minEigenVector, double minEigenValue, + double gradienTolerance = 1e-2, + double preconditionedGradNormTolerance = 1e-4) const; + /// @} + /// @name Advanced API + /// @{ + + /** + * Build graph for SO(p) + * @param p the dimensionality of the rotation manifold to optimize over + */ + NonlinearFactorGraph buildGraphAt(size_t p) const; + + /** + * Calculate cost for SO(p) + * Values should be of type SO(p) + */ + double costAt(size_t p, const Values &values) const; + + /** + * Given an estimated local minimum Yopt for the (possibly lifted) + * relaxation, this function computes and returns the block-diagonal elements + * of the corresponding Lagrange multiplier. + */ + Sparse computeLambda(const Values &values) const; + + /** + * Compute minimum eigenvalue for optimality check. + * @param values: should be of type SOn + * @return minEigenVector and minEigenValue + */ + std::pair computeMinEigenVector(const Values &values) const; + + /** + * Check optimality + * @param values: should be of type SOn + */ + bool checkOptimality(const Values &values) const; + + /** + * Try to create optimizer at SO(p) + * @param p the dimensionality of the rotation manifold to optimize over + * @param initial initial SO(p) values + * @return lm optimizer + */ + boost::shared_ptr createOptimizerAt( + size_t p, const Values &initial) const; + + /** + * Try to optimize at SO(p) + * @param p the dimensionality of the rotation manifold to optimize over + * @param initial initial SO(p) values + * @return SO(p) values + */ + Values tryOptimizingAt(size_t p, const Values &initial) const; + + /** + * Project from SO(p) to Rot2 or Rot3 + * Values should be of type SO(p) + */ + Values projectFrom(size_t p, const Values &values) const; + + /** + * Project from SO(p)^N to Rot2^N or Rot3^N + * Values should be of type SO(p) + */ + Values roundSolution(const Values &values) const; + + /// Lift Values of type T to SO(p) + template static Values LiftTo(size_t p, const Values &values) { + Values result; + for (const auto it : values.filter()) { + result.insert(it.key, SOn::Lift(p, it.value.matrix())); + } + return result; + } + + /// @} + /// @name Basic API + /// @{ + + /** + * Calculate cost for SO(3) + * Values should be of type Rot3 + */ + double cost(const Values &values) const; + + /** + * Initialize randomly at SO(d) + * @param rng random number generator + * Example: + * std::mt19937 rng(42); + * Values initial = initializeRandomly(rng, p); + */ + Values initializeRandomly(std::mt19937 &rng) const; + + /// Random initialization for wrapper, fixed random seed. + Values initializeRandomly() const; + + /** + * Optimize at different values of p until convergence. + * @param initial initial Rot3 values + * @param pMin value of p to start Riemanian staircase at (default: d). + * @param pMax maximum value of p to try (default: 10) + * @return (Rot3 values, minimum eigenvalue) + */ + std::pair run(const Values &initialEstimate, size_t pMin = d, + size_t pMax = 10) const; + /// @} +}; + +// Subclasses for d=2 and d=3 that explicitly instantiate, as well as provide a +// convenience interface with file access. + +class ShonanAveraging2 : public ShonanAveraging<2> { +public: + ShonanAveraging2(const Measurements &measurements, + const Parameters ¶meters = Parameters()); + ShonanAveraging2(string g2oFile, const Parameters ¶meters = Parameters()); +}; + +class ShonanAveraging3 : public ShonanAveraging<3> { +public: + ShonanAveraging3(const Measurements &measurements, + const Parameters ¶meters = Parameters()); + ShonanAveraging3(string g2oFile, const Parameters ¶meters = Parameters()); + + // TODO(frank): Deprecate after we land pybind wrapper + ShonanAveraging3(const BetweenFactorPose3s &factors, + const Parameters ¶meters = Parameters()); +}; +} // namespace gtsam diff --git a/gtsam/sfm/ShonanFactor.cpp b/gtsam/sfm/ShonanFactor.cpp new file mode 100644 index 000000000..b911fb5a4 --- /dev/null +++ b/gtsam/sfm/ShonanFactor.cpp @@ -0,0 +1,141 @@ +/* ---------------------------------------------------------------------------- + + * GTSAM Copyright 2010-2019, Georgia Tech Research Corporation, + * Atlanta, Georgia 30332-0415 + * All Rights Reserved + * Authors: Frank Dellaert, et al. (see THANKS for the full author list) + + * See LICENSE for the license information + + * -------------------------------------------------------------------------- */ + +/** + * @file FrobeniusFactor.cpp + * @date March 2019 + * @author Frank Dellaert + * @brief Various factors that minimize some Frobenius norm + */ + +#include + +#include +#include +#include + +#include +#include +#include + +using namespace std; + +namespace gtsam { + +//****************************************************************************** +template +ShonanFactor::ShonanFactor(Key j1, Key j2, const Rot &R12, size_t p, + const SharedNoiseModel &model, + const boost::shared_ptr &G) + : NoiseModelFactor2(ConvertNoiseModel(model, p * d), j1, j2), + M_(R12.matrix()), // d*d in all cases + p_(p), // 4 for SO(4) + pp_(p * p), // 16 for SO(4) + G_(G) { + if (noiseModel()->dim() != d * p_) + throw std::invalid_argument( + "ShonanFactor: model with incorrect dimension."); + if (!G) { + G_ = boost::make_shared(); + *G_ = SOn::VectorizedGenerators(p); // expensive! + } + if (static_cast(G_->rows()) != pp_ || + static_cast(G_->cols()) != SOn::Dimension(p)) + throw std::invalid_argument("ShonanFactor: passed in generators " + "of incorrect dimension."); +} + +//****************************************************************************** +template +void ShonanFactor::print(const std::string &s, + const KeyFormatter &keyFormatter) const { + std::cout << s << "ShonanFactor<" << p_ << ">(" << keyFormatter(key1()) << "," + << keyFormatter(key2()) << ")\n"; + traits::Print(M_, " M: "); + noiseModel_->print(" noise model: "); +} + +//****************************************************************************** +template +bool ShonanFactor::equals(const NonlinearFactor &expected, + double tol) const { + auto e = dynamic_cast(&expected); + return e != nullptr && NoiseModelFactor2::equals(*e, tol) && + p_ == e->p_ && M_ == e->M_; +} + +//****************************************************************************** +template +void ShonanFactor::fillJacobians(const Matrix &M1, const Matrix &M2, + boost::optional H1, + boost::optional H2) const { + gttic(ShonanFactor_Jacobians); + const size_t dim = p_ * d; // Stiefel manifold dimension + + if (H1) { + // If asked, calculate Jacobian H1 as as (M' \otimes M1) * G + // M' = dxd, M1 = pxp, G = (p*p)xDim(p), result should be dim x Dim(p) + // (M' \otimes M1) is dim*dim, but last pp-dim columns are zero + *H1 = Matrix::Zero(dim, G_->cols()); + for (size_t j = 0; j < d; j++) { + auto MG_j = M1 * G_->middleRows(j * p_, p_); // p_ * Dim(p) + for (size_t i = 0; i < d; i++) { + H1->middleRows(i * p_, p_) -= M_(j, i) * MG_j; + } + } + } + if (H2) { + // If asked, calculate Jacobian H2 as as (I_d \otimes M2) * G + // I_d = dxd, M2 = pxp, G = (p*p)xDim(p), result should be dim x Dim(p) + // (I_d \otimes M2) is dim*dim, but again last pp-dim columns are zero + H2->resize(dim, G_->cols()); + for (size_t i = 0; i < d; i++) { + H2->middleRows(i * p_, p_) = M2 * G_->middleRows(i * p_, p_); + } + } +} + +//****************************************************************************** +template +Vector ShonanFactor::evaluateError(const SOn &Q1, const SOn &Q2, + boost::optional H1, + boost::optional H2) const { + gttic(ShonanFactor_evaluateError); + + const Matrix &M1 = Q1.matrix(); + const Matrix &M2 = Q2.matrix(); + if (M1.rows() != static_cast(p_) || M2.rows() != static_cast(p_)) + throw std::invalid_argument("Invalid dimension SOn values passed to " + "ShonanFactor::evaluateError"); + + const size_t dim = p_ * d; // Stiefel manifold dimension + Vector fQ2(dim), hQ1(dim); + + // Vectorize and extract only d leftmost columns, i.e. vec(M2*P) + fQ2 << Eigen::Map(M2.data(), dim, 1); + + // Vectorize M1*P*R12 + const Matrix Q1PR12 = M1.leftCols() * M_; + hQ1 << Eigen::Map(Q1PR12.data(), dim, 1); + + this->fillJacobians(M1, M2, H1, H2); + + return fQ2 - hQ1; +} + +/* ************************************************************************* */ +// Explicit instantiation for d=2 and d=3 +template class ShonanFactor<2>; +template class ShonanFactor<3>; + +//****************************************************************************** + +} // namespace gtsam diff --git a/gtsam/sfm/ShonanFactor.h b/gtsam/sfm/ShonanFactor.h new file mode 100644 index 000000000..3c43c2c52 --- /dev/null +++ b/gtsam/sfm/ShonanFactor.h @@ -0,0 +1,91 @@ +/* ---------------------------------------------------------------------------- + + * GTSAM Copyright 2010-2019, Georgia Tech Research Corporation, + * Atlanta, Georgia 30332-0415 + * All Rights Reserved + * Authors: Frank Dellaert, et al. (see THANKS for the full author list) + + * See LICENSE for the license information + + * -------------------------------------------------------------------------- */ + +/** + * @file ShonanFactor.h + * @date March 2019 + * @author Frank Dellaert + * @brief Main factor type in Shonan averaging, on SO(n) pairs + */ + +#pragma once + +#include +#include +#include +#include + +#include + +namespace gtsam { + +/** + * ShonanFactor is a BetweenFactor that moves in SO(p), but will + * land on the SO(d) sub-manifold of SO(p) at the global minimum. It projects + * the SO(p) matrices down to a Stiefel manifold of p*d matrices. + */ +template +class GTSAM_EXPORT ShonanFactor : public NoiseModelFactor2 { + Matrix M_; ///< measured rotation between R1 and R2 + size_t p_, pp_; ///< dimensionality constants + boost::shared_ptr G_; ///< matrix of vectorized generators + + // Select Rot2 or Rot3 interface based template parameter d + using Rot = typename std::conditional::type; + +public: + /// @name Constructor + /// @{ + + /// Constructor. Note we convert to d*p-dimensional noise model. + /// To save memory and mallocs, pass in the vectorized Lie algebra generators: + /// G = boost::make_shared(SOn::VectorizedGenerators(p)); + ShonanFactor(Key j1, Key j2, const Rot &R12, size_t p, + const SharedNoiseModel &model = nullptr, + const boost::shared_ptr &G = nullptr); + + /// @} + /// @name Testable + /// @{ + + /// print with optional string + void + print(const std::string &s, + const KeyFormatter &keyFormatter = DefaultKeyFormatter) const override; + + /// assert equality up to a tolerance + bool equals(const NonlinearFactor &expected, + double tol = 1e-9) const override; + + /// @} + /// @name NoiseModelFactor2 methods + /// @{ + + /// Error is Frobenius norm between Q1*P*R12 and Q2*P, where P=[I_3x3;0] + /// projects down from SO(p) to the Stiefel manifold of px3 matrices. + Vector + evaluateError(const SOn &Q1, const SOn &Q2, + boost::optional H1 = boost::none, + boost::optional H2 = boost::none) const override; + /// @} + +private: + /// Calculate Jacobians if asked, Only implemented for d=2 and 3 in .cpp + void fillJacobians(const Matrix &M1, const Matrix &M2, + boost::optional H1, + boost::optional H2) const; +}; + +// Explicit instantiation for d=2 and d=3 in .cpp file: +using ShonanFactor2 = ShonanFactor<2>; +using ShonanFactor3 = ShonanFactor<3>; + +} // namespace gtsam diff --git a/gtsam/sfm/ShonanGaugeFactor.h b/gtsam/sfm/ShonanGaugeFactor.h new file mode 100644 index 000000000..4847c5d58 --- /dev/null +++ b/gtsam/sfm/ShonanGaugeFactor.h @@ -0,0 +1,108 @@ +/* ---------------------------------------------------------------------------- + + * GTSAM Copyright 2010-2019, Georgia Tech Research Corporation, + * Atlanta, Georgia 30332-0415 + * All Rights Reserved + * Authors: Frank Dellaert, et al. (see THANKS for the full author list) + + * See LICENSE for the license information + + * -------------------------------------------------------------------------- */ + +/** + * @file ShonanGaugeFactor.h + * @date March 2019 + * @author Frank Dellaert + * @brief Factor used in Shonan Averaging to clamp down gauge freedom + */ + +#pragma once + +#include +#include +#include + +#include + +namespace gtsam { +/** + * The ShonanGaugeFactor creates a constraint on a single SO(n) to avoid moving + * in the stabilizer. + * + * Details: SO(p) contains the p*3 Stiefel matrices of orthogonal frames: we + * take those to be the 3 columns on the left. + * The P*P skew-symmetric matrices associated with so(p) can be partitioned as + * (Appendix B in the ECCV paper): + * | [w] -K' | + * | K [g] | + * where w is the SO(3) space, K are the extra Stiefel diemnsions (wormhole!) + * and (g)amma are extra dimensions in SO(p) that do not modify the cost + * function. The latter corresponds to rotations SO(p-d), and so the first few + * values of p-d for d==3 with their corresponding dimensionality are {0:0, 1:0, + * 2:1, 3:3, ...} + * + * The ShonanGaugeFactor adds a unit Jacobian to these extra dimensions, + * essentially restricting the optimization to the Stiefel manifold. + */ +class GTSAM_EXPORT ShonanGaugeFactor : public NonlinearFactor { + // Row dimension, equal to the dimensionality of SO(p-d) + size_t rows_; + + /// Constant Jacobian + boost::shared_ptr whitenedJacobian_; + +public: + /** + * Construct from key for an SO(p) matrix, for base dimension d (2 or 3) + * If parameter gamma is given, it acts as a precision = 1/sigma^2, and + * the Jacobian will be multiplied with 1/sigma = sqrt(gamma). + */ + ShonanGaugeFactor(Key key, size_t p, size_t d = 3, + boost::optional gamma = boost::none) + : NonlinearFactor(boost::assign::cref_list_of<1>(key)) { + if (p < d) { + throw std::invalid_argument("ShonanGaugeFactor must have p>=d."); + } + // Calculate dimensions + size_t q = p - d; + size_t P = SOn::Dimension(p); // dimensionality of SO(p) + rows_ = SOn::Dimension(q); // dimensionality of SO(q), the gauge + + // Create constant Jacobian as a rows_*P matrix: there are rows_ penalized + // dimensions, but it is a bit tricky to find them among the P columns. + // The key is to look at how skew-symmetric matrices are laid out in SOn.h: + // the first tangent dimension will always be included, but beyond that we + // have to be careful. We always need to skip the d top-rows of the skew- + // symmetric matrix as they below to K, part of the Stiefel manifold. + Matrix A(rows_, P); + A.setZero(); + double invSigma = gamma ? std::sqrt(*gamma) : 1.0; + size_t i = 0, j = 0, n = p - 1 - d; + while (i < rows_) { + A.block(i, j, n, n) = invSigma * Matrix::Identity(n, n); + i += n; + j += n + d; // skip d columns + n -= 1; + } + // TODO(frank): assign the right one in the right columns + whitenedJacobian_ = + boost::make_shared(key, A, Vector::Zero(rows_)); + } + + /// Destructor + virtual ~ShonanGaugeFactor() {} + + /// Calculate the error of the factor: always zero + double error(const Values &c) const override { return 0; } + + /// get the dimension of the factor (number of rows on linearization) + size_t dim() const override { return rows_; } + + /// linearize to a GaussianFactor + boost::shared_ptr linearize(const Values &c) const override { + return whitenedJacobian_; + } +}; +// \ShonanGaugeFactor + +} // namespace gtsam \ No newline at end of file diff --git a/gtsam/sfm/tests/testShonanAveraging.cpp b/gtsam/sfm/tests/testShonanAveraging.cpp new file mode 100644 index 000000000..cc4319e15 --- /dev/null +++ b/gtsam/sfm/tests/testShonanAveraging.cpp @@ -0,0 +1,360 @@ +/* ---------------------------------------------------------------------------- + + * GTSAM Copyright 2010-2019, Georgia Tech Research Corporation, + * Atlanta, Georgia 30332-0415 + * All Rights Reserved + * Authors: Frank Dellaert, et al. (see THANKS for the full author list) + + * See LICENSE for the license information + + * -------------------------------------------------------------------------- */ + +/** + * @file testShonanAveraging.cpp + * @date March 2019 + * @author Frank Dellaert + * @brief Unit tests for Shonan Averaging algorithm + */ + +#include +#include +#include +#include + +#include +#include +#include +#include + +using namespace std; +using namespace gtsam; + +template +using Rot = typename std::conditional::type; + +template +using Pose = typename std::conditional::type; + +ShonanAveraging3 fromExampleName( + const std::string &name, + ShonanAveraging3::Parameters parameters = ShonanAveraging3::Parameters()) { + string g2oFile = findExampleDataFile(name); + return ShonanAveraging3(g2oFile, parameters); +} + +static const ShonanAveraging3 kShonan = fromExampleName("toyExample.g2o"); + +static std::mt19937 kRandomNumberGenerator(42); + +/* ************************************************************************* */ +TEST(ShonanAveraging3, checkConstructor) { + EXPECT_LONGS_EQUAL(5, kShonan.nrUnknowns()); + + EXPECT_LONGS_EQUAL(15, kShonan.D().rows()); + EXPECT_LONGS_EQUAL(15, kShonan.D().cols()); + auto D = kShonan.denseD(); + EXPECT_LONGS_EQUAL(15, D.rows()); + EXPECT_LONGS_EQUAL(15, D.cols()); + + EXPECT_LONGS_EQUAL(15, kShonan.Q().rows()); + EXPECT_LONGS_EQUAL(15, kShonan.Q().cols()); + auto Q = kShonan.denseQ(); + EXPECT_LONGS_EQUAL(15, Q.rows()); + EXPECT_LONGS_EQUAL(15, Q.cols()); + + EXPECT_LONGS_EQUAL(15, kShonan.L().rows()); + EXPECT_LONGS_EQUAL(15, kShonan.L().cols()); + auto L = kShonan.denseL(); + EXPECT_LONGS_EQUAL(15, L.rows()); + EXPECT_LONGS_EQUAL(15, L.cols()); +} + +/* ************************************************************************* */ +TEST(ShonanAveraging3, buildGraphAt) { + auto graph = kShonan.buildGraphAt(5); + EXPECT_LONGS_EQUAL(7, graph.size()); +} + +/* ************************************************************************* */ +TEST(ShonanAveraging3, checkOptimality) { + const Values randomRotations = kShonan.initializeRandomly(kRandomNumberGenerator); + Values random = ShonanAveraging3::LiftTo(4, randomRotations); // lift to 4! + auto Lambda = kShonan.computeLambda(random); + EXPECT_LONGS_EQUAL(15, Lambda.rows()); + EXPECT_LONGS_EQUAL(15, Lambda.cols()); + EXPECT_LONGS_EQUAL(45, Lambda.nonZeros()); + auto lambdaMin = kShonan.computeMinEigenValue(random); + // EXPECT_DOUBLES_EQUAL(-5.2964625490657866, lambdaMin, + // 1e-4); // Regression test + EXPECT_DOUBLES_EQUAL(-414.87376657555996, lambdaMin, + 1e-4); // Regression test + EXPECT(!kShonan.checkOptimality(random)); +} + +/* ************************************************************************* */ +TEST(ShonanAveraging3, tryOptimizingAt3) { + const Values randomRotations = kShonan.initializeRandomly(kRandomNumberGenerator); + Values initial = ShonanAveraging3::LiftTo(3, randomRotations); // convert to SOn + EXPECT(!kShonan.checkOptimality(initial)); + const Values result = kShonan.tryOptimizingAt(3, initial); + EXPECT(kShonan.checkOptimality(result)); + auto lambdaMin = kShonan.computeMinEigenValue(result); + EXPECT_DOUBLES_EQUAL(-5.427688831332745e-07, lambdaMin, + 1e-4); // Regression test + EXPECT_DOUBLES_EQUAL(0, kShonan.costAt(3, result), 1e-4); + const Values SO3Values = kShonan.roundSolution(result); + EXPECT_DOUBLES_EQUAL(0, kShonan.cost(SO3Values), 1e-4); +} + +/* ************************************************************************* */ +TEST(ShonanAveraging3, tryOptimizingAt4) { + const Values randomRotations = kShonan.initializeRandomly(kRandomNumberGenerator); + Values random = ShonanAveraging3::LiftTo(4, randomRotations); // lift to 4! + const Values result = kShonan.tryOptimizingAt(4, random); + EXPECT(kShonan.checkOptimality(result)); + EXPECT_DOUBLES_EQUAL(0, kShonan.costAt(4, result), 1e-3); + auto lambdaMin = kShonan.computeMinEigenValue(result); + EXPECT_DOUBLES_EQUAL(-5.427688831332745e-07, lambdaMin, + 1e-4); // Regression test + const Values SO3Values = kShonan.roundSolution(result); + EXPECT_DOUBLES_EQUAL(0, kShonan.cost(SO3Values), 1e-4); +} + +/* ************************************************************************* */ +TEST(ShonanAveraging3, MakeATangentVector) { + Vector9 v; + v << 1, 2, 3, 4, 5, 6, 7, 8, 9; + Matrix expected(5, 5); + expected << 0, 0, 0, 0, -4, // + 0, 0, 0, 0, -5, // + 0, 0, 0, 0, -6, // + 0, 0, 0, 0, 0, // + 4, 5, 6, 0, 0; + const Vector xi_1 = ShonanAveraging3::MakeATangentVector(5, v, 1); + const auto actual = SOn::Hat(xi_1); + CHECK(assert_equal(expected, actual)); +} + +/* ************************************************************************* */ +TEST(ShonanAveraging3, LiftTo) { + auto I = genericValue(Rot3()); + Values initial{{0, I}, {1, I}, {2, I}}; + Values lifted = ShonanAveraging3::LiftTo(5, initial); + EXPECT(assert_equal(SOn(5), lifted.at(0))); +} + +/* ************************************************************************* */ +TEST(ShonanAveraging3, CheckWithEigen) { + // control randomness + static std::mt19937 rng(0); + Vector descentDirection = Vector::Random(15); // for use below + const Values randomRotations = kShonan.initializeRandomly(rng); + Values random = ShonanAveraging3::LiftTo(3, randomRotations); + + // Optimize + const Values Qstar3 = kShonan.tryOptimizingAt(3, random); + + // Compute Eigenvalue with Spectra solver + double lambda = kShonan.computeMinEigenValue(Qstar3); + + // Check Eigenvalue with slow Eigen version, converts matrix A to dense matrix! + const Matrix S = ShonanAveraging3::StiefelElementMatrix(Qstar3); + auto A = kShonan.computeA(S); + bool computeEigenvectors = false; + Eigen::EigenSolver eigenSolver(Matrix(A), computeEigenvectors); + auto lambdas = eigenSolver.eigenvalues().real(); + double minEigenValue = lambdas(0); + for (int i = 1; i < lambdas.size(); i++) + minEigenValue = min(lambdas(i), minEigenValue); + + // Actual check + EXPECT_DOUBLES_EQUAL(minEigenValue, lambda, 1e-12); + + // Construct test descent direction (as minEigenVector is not predictable + // across platforms, being one from a basically flat 3d- subspace) + + // Check descent + Values initialQ4 = + ShonanAveraging3::LiftwithDescent(4, Qstar3, descentDirection); + EXPECT_LONGS_EQUAL(5, initialQ4.size()); + + // TODO(frank): uncomment this regression test: currently not repeatable + // across platforms. + // Matrix expected(4, 4); + // expected << 0.0459224, -0.688689, -0.216922, 0.690321, // + // 0.92381, 0.191931, 0.255854, 0.21042, // + // -0.376669, 0.301589, 0.687953, 0.542111, // + // -0.0508588, 0.630804, -0.643587, 0.43046; + // EXPECT(assert_equal(SOn(expected), initialQ4.at(0), 1e-5)); +} + +/* ************************************************************************* */ +TEST(ShonanAveraging3, initializeWithDescent) { + const Values randomRotations = kShonan.initializeRandomly(kRandomNumberGenerator); + Values random = ShonanAveraging3::LiftTo(3, randomRotations); + const Values Qstar3 = kShonan.tryOptimizingAt(3, random); + Vector minEigenVector; + double lambdaMin = kShonan.computeMinEigenValue(Qstar3, &minEigenVector); + Values initialQ4 = + kShonan.initializeWithDescent(4, Qstar3, minEigenVector, lambdaMin); + EXPECT_LONGS_EQUAL(5, initialQ4.size()); +} + +/* ************************************************************************* */ +TEST(ShonanAveraging3, run) { + auto initial = kShonan.initializeRandomly(kRandomNumberGenerator); + auto result = kShonan.run(initial, 5); + EXPECT_DOUBLES_EQUAL(0, kShonan.cost(result.first), 1e-3); + EXPECT_DOUBLES_EQUAL(-5.427688831332745e-07, result.second, + 1e-4); // Regression test +} + +/* ************************************************************************* */ +namespace klaus { +// The data in the file is the Colmap solution +const Rot3 wR0(0.9992281076190063, -0.02676080288219576, -0.024497002638379624, + -0.015064701622500615); +const Rot3 wR1(0.998239108728862, -0.049543805396343954, -0.03232420352077356, + -0.004386230477751116); +const Rot3 wR2(0.9925378735259738, -0.07993768981394891, 0.0825062894866454, + -0.04088089479075661); +} // namespace klaus + +TEST(ShonanAveraging3, runKlaus) { + using namespace klaus; + + // Initialize a Shonan instance without the Karcher mean + ShonanAveraging3::Parameters parameters; + parameters.setKarcherWeight(0); + + // Load 3 pose example taken in Klaus by Shicong + static const ShonanAveraging3 shonan = + fromExampleName("Klaus3.g2o", parameters); + + // Check nr poses + EXPECT_LONGS_EQUAL(3, shonan.nrUnknowns()); + + // Colmap uses the Y-down vision frame, and the first 3 rotations are close to + // identity. We check that below. Note tolerance is quite high. + static const Rot3 identity; + EXPECT(assert_equal(identity, wR0, 0.2)); + EXPECT(assert_equal(identity, wR1, 0.2)); + EXPECT(assert_equal(identity, wR2, 0.2)); + + // Get measurements + const Rot3 R01 = shonan.measured(0); + const Rot3 R12 = shonan.measured(1); + const Rot3 R02 = shonan.measured(2); + + // Regression test to make sure data did not change. + EXPECT(assert_equal(Rot3(0.9995433591728293, -0.022048798853273946, + -0.01796327847857683, 0.010210006313668573), + R01)); + + // Check Colmap solution agrees OK with relative rotation measurements. + EXPECT(assert_equal(R01, wR0.between(wR1), 0.1)); + EXPECT(assert_equal(R12, wR1.between(wR2), 0.1)); + EXPECT(assert_equal(R02, wR0.between(wR2), 0.1)); + + // Run Shonan (with prior on first rotation) + auto initial = shonan.initializeRandomly(kRandomNumberGenerator); + auto result = shonan.run(initial, 5); + EXPECT_DOUBLES_EQUAL(0, shonan.cost(result.first), 1e-2); + EXPECT_DOUBLES_EQUAL(-9.2259161494467889e-05, result.second, + 1e-4); // Regression + + // Get Shonan solution in new frame R (R for result) + const Rot3 rR0 = result.first.at(0); + const Rot3 rR1 = result.first.at(1); + const Rot3 rR2 = result.first.at(2); + + // rR0 = rRw * wR0 => rRw = rR0 * wR0.inverse() + // rR1 = rRw * wR1 + // rR2 = rRw * wR2 + + const Rot3 rRw = rR0 * wR0.inverse(); + EXPECT(assert_equal(rRw * wR1, rR1, 0.1)) + EXPECT(assert_equal(rRw * wR2, rR2, 0.1)) +} + +/* ************************************************************************* */ +TEST(ShonanAveraging3, runKlausKarcher) { + using namespace klaus; + + // Load 3 pose example taken in Klaus by Shicong + static const ShonanAveraging3 shonan = fromExampleName("Klaus3.g2o"); + + // Run Shonan (with Karcher mean prior) + auto initial = shonan.initializeRandomly(kRandomNumberGenerator); + auto result = shonan.run(initial, 5); + EXPECT_DOUBLES_EQUAL(0, shonan.cost(result.first), 1e-2); + EXPECT_DOUBLES_EQUAL(-1.361402670507772e-05, result.second, + 1e-4); // Regression test + + // Get Shonan solution in new frame R (R for result) + const Rot3 rR0 = result.first.at(0); + const Rot3 rR1 = result.first.at(1); + const Rot3 rR2 = result.first.at(2); + + const Rot3 rRw = rR0 * wR0.inverse(); + EXPECT(assert_equal(rRw * wR1, rR1, 0.1)) + EXPECT(assert_equal(rRw * wR2, rR2, 0.1)) +} + +/* ************************************************************************* */ +TEST(ShonanAveraging2, runKlausKarcher) { + // Load 2D toy example + auto lmParams = LevenbergMarquardtParams::CeresDefaults(); + // lmParams.setVerbosityLM("SUMMARY"); + string g2oFile = findExampleDataFile("noisyToyGraph.txt"); + ShonanAveraging2::Parameters parameters(lmParams); + auto measurements = parseMeasurements(g2oFile); + ShonanAveraging2 shonan(measurements, parameters); + EXPECT_LONGS_EQUAL(4, shonan.nrUnknowns()); + + // Check graph building + NonlinearFactorGraph graph = shonan.buildGraphAt(2); + EXPECT_LONGS_EQUAL(6, graph.size()); + auto initial = shonan.initializeRandomly(kRandomNumberGenerator); + auto result = shonan.run(initial, 2); + EXPECT_DOUBLES_EQUAL(0.0008211, shonan.cost(result.first), 1e-6); + EXPECT_DOUBLES_EQUAL(0, result.second, 1e-10); // certificate! +} + +/* ************************************************************************* */ +// Test alpha/beta/gamma prior weighting. +TEST(ShonanAveraging3, PriorWeights) { + auto lmParams = LevenbergMarquardtParams::CeresDefaults(); + ShonanAveraging3::Parameters params(lmParams); + EXPECT_DOUBLES_EQUAL(0, params.alpha, 1e-9); + EXPECT_DOUBLES_EQUAL(1, params.beta, 1e-9); + EXPECT_DOUBLES_EQUAL(0, params.gamma, 1e-9); + double alpha = 100.0, beta = 200.0, gamma = 300.0; + params.setAnchorWeight(alpha); + params.setKarcherWeight(beta); + params.setGaugesWeight(gamma); + EXPECT_DOUBLES_EQUAL(alpha, params.alpha, 1e-9); + EXPECT_DOUBLES_EQUAL(beta, params.beta, 1e-9); + EXPECT_DOUBLES_EQUAL(gamma, params.gamma, 1e-9); + params.setKarcherWeight(0); + static const ShonanAveraging3 shonan = fromExampleName("Klaus3.g2o", params); + for (auto i : {0,1,2}) { + const auto& m = shonan.measurement(i); + auto isotropic = + boost::static_pointer_cast(m.noiseModel()); + CHECK(isotropic != nullptr); + EXPECT_LONGS_EQUAL(3, isotropic->dim()); + EXPECT_DOUBLES_EQUAL(0.2, isotropic->sigma(), 1e-9); + } + auto I = genericValue(Rot3()); + Values initial{{0, I}, {1, I}, {2, I}}; + EXPECT_DOUBLES_EQUAL(3.0756, shonan.cost(initial), 1e-4); + auto result = shonan.run(initial, 3, 3); + EXPECT_DOUBLES_EQUAL(0.0015, shonan.cost(result.first), 1e-4); +} +/* ************************************************************************* */ +int main() { + TestResult tr; + return TestRegistry::runAllTests(tr); +} +/* ************************************************************************* */ diff --git a/gtsam/sfm/tests/testShonanFactor.cpp b/gtsam/sfm/tests/testShonanFactor.cpp new file mode 100644 index 000000000..ef94c5cf4 --- /dev/null +++ b/gtsam/sfm/tests/testShonanFactor.cpp @@ -0,0 +1,121 @@ +/* ---------------------------------------------------------------------------- + + * GTSAM Copyright 2010-2019, Georgia Tech Research Corporation, + * Atlanta, Georgia 30332-0415 + * All Rights Reserved + * Authors: Frank Dellaert, et al. (see THANKS for the full author list) + + * See LICENSE for the license information + + * -------------------------------------------------------------------------- */ + +/** + * testFrobeniusFactor.cpp + * + * @file testFrobeniusFactor.cpp + * @date March 2019 + * @author Frank Dellaert + * @brief Check evaluateError for various Frobenius norm + */ + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#include + +using namespace std; +using namespace gtsam; + +//****************************************************************************** +namespace so3 { +SO3 id; +Vector3 v1 = (Vector(3) << 0.1, 0, 0).finished(); +SO3 R1 = SO3::Expmap(v1); +Vector3 v2 = (Vector(3) << 0.01, 0.02, 0.03).finished(); +SO3 R2 = SO3::Expmap(v2); +SO3 R12 = R1.between(R2); +} // namespace so3 + +//****************************************************************************** +namespace submanifold { +SO4 id; +Vector6 v1 = (Vector(6) << 0, 0, 0, 0.1, 0, 0).finished(); +SO3 R1 = SO3::Expmap(v1.tail<3>()); +SO4 Q1 = SO4::Expmap(v1); +Vector6 v2 = (Vector(6) << 0, 0, 0, 0.01, 0.02, 0.03).finished(); +SO3 R2 = SO3::Expmap(v2.tail<3>()); +SO4 Q2 = SO4::Expmap(v2); +SO3 R12 = R1.between(R2); +} // namespace submanifold + +/* ************************************************************************* */ +TEST(ShonanFactor3, evaluateError) { + auto model = noiseModel::Isotropic::Sigma(3, 1.2); + for (const size_t p : {5, 4, 3}) { + Matrix M = Matrix::Identity(p, p); + M.topLeftCorner(3, 3) = submanifold::R1.matrix(); + SOn Q1(M); + M.topLeftCorner(3, 3) = submanifold::R2.matrix(); + SOn Q2(M); + auto factor = ShonanFactor3(1, 2, Rot3(::so3::R12.matrix()), p, model); + Matrix H1, H2; + factor.evaluateError(Q1, Q2, H1, H2); + + // Test derivatives + Values values; + values.insert(1, Q1); + values.insert(2, Q2); + EXPECT_CORRECT_FACTOR_JACOBIANS(factor, values, 1e-7, 1e-5); + } +} + +/* ************************************************************************* */ +TEST(ShonanFactor3, equivalenceToSO3) { + using namespace ::submanifold; + auto R12 = ::so3::R12.retract(Vector3(0.1, 0.2, -0.1)); + auto model = noiseModel::Isotropic::Sigma(6, 1.2); // wrong dimension + auto factor3 = FrobeniusBetweenFactor(1, 2, R12, model); + auto factor4 = ShonanFactor3(1, 2, Rot3(R12.matrix()), 4, model); + const Matrix3 E3(factor3.evaluateError(R1, R2).data()); + const Matrix43 E4( + factor4.evaluateError(SOn(Q1.matrix()), SOn(Q2.matrix())).data()); + EXPECT(assert_equal((Matrix)E4.topLeftCorner<3, 3>(), E3, 1e-9)); + EXPECT(assert_equal((Matrix)E4.row(3), Matrix13::Zero(), 1e-9)); +} + +/* ************************************************************************* */ +TEST(ShonanFactor2, evaluateError) { + auto model = noiseModel::Isotropic::Sigma(1, 1.2); + const Rot2 R1(0.3), R2(0.5), R12(0.2); + for (const size_t p : {5, 4, 3, 2}) { + Matrix M = Matrix::Identity(p, p); + M.topLeftCorner(2, 2) = R1.matrix(); + SOn Q1(M); + M.topLeftCorner(2, 2) = R2.matrix(); + SOn Q2(M); + auto factor = ShonanFactor2(1, 2, R12, p, model); + Matrix H1, H2; + factor.evaluateError(Q1, Q2, H1, H2); + + // Test derivatives + Values values; + values.insert(1, Q1); + values.insert(2, Q2); + EXPECT_CORRECT_FACTOR_JACOBIANS(factor, values, 1e-7, 1e-5); + } +} + +/* ************************************************************************* */ +int main() { + TestResult tr; + return TestRegistry::runAllTests(tr); +} +/* ************************************************************************* */ diff --git a/gtsam/sfm/tests/testShonanGaugeFactor.cpp b/gtsam/sfm/tests/testShonanGaugeFactor.cpp new file mode 100644 index 000000000..344394b9c --- /dev/null +++ b/gtsam/sfm/tests/testShonanGaugeFactor.cpp @@ -0,0 +1,106 @@ +/* ---------------------------------------------------------------------------- + + * GTSAM Copyright 2010-2019, Georgia Tech Research Corporation, + * Atlanta, Georgia 30332-0415 + * All Rights Reserved + * Authors: Frank Dellaert, et al. (see THANKS for the full author list) + + * See LICENSE for the license information + + * -------------------------------------------------------------------------- */ + +/** + * @file testShonanGaugeFactor.cpp + * @date March 2019 + * @author Frank Dellaert + * @brief Unit tests for ShonanGaugeFactor class + */ + +#include + +#include + +#include +#include + +using namespace std; +using namespace gtsam; + +/* ************************************************************************* */ +// Check dimensions of all low-dim GaugeFactors +TEST(ShonanAveraging, GaugeFactorLows) { + constexpr Key key(123); + EXPECT_LONGS_EQUAL(0, ShonanGaugeFactor(key, 2, 2).dim()); + EXPECT_LONGS_EQUAL(0, ShonanGaugeFactor(key, 3, 2).dim()); + EXPECT_LONGS_EQUAL(1, ShonanGaugeFactor(key, 4, 2).dim()); // SO(4-2) -> 1 + EXPECT_LONGS_EQUAL(3, ShonanGaugeFactor(key, 5, 2).dim()); // SO(5-2) -> 3 + + EXPECT_LONGS_EQUAL(0, ShonanGaugeFactor(key, 3, 3).dim()); + EXPECT_LONGS_EQUAL(0, ShonanGaugeFactor(key, 4, 3).dim()); + EXPECT_LONGS_EQUAL(1, ShonanGaugeFactor(key, 5, 3).dim()); // SO(5-3) -> 1 +} + +/* ************************************************************************* */ +// Check ShonanGaugeFactor for SO(6) +TEST(ShonanAveraging, GaugeFactorSO6) { + constexpr Key key(666); + ShonanGaugeFactor factor(key, 6); // For SO(6) + Matrix A = Matrix::Zero(3, 15); // SO(6-3) = SO(3) == 3-dimensional gauge + A(0, 0) = 1; // first 2 of 6^th skew column, which has 5 non-zero entries + A(1, 1) = 1; // then we skip 3 tangent dimensions + A(2, 5) = 1; // first of 5th skew colum, which has 4 non-zero entries above + // diagonal. + JacobianFactor linearized(key, A, Vector::Zero(3)); + Values values; + EXPECT_LONGS_EQUAL(3, factor.dim()); + EXPECT(assert_equal(linearized, *boost::dynamic_pointer_cast( + factor.linearize(values)))); +} + +/* ************************************************************************* */ +// Check ShonanGaugeFactor for SO(7) +TEST(ShonanAveraging, GaugeFactorSO7) { + constexpr Key key(777); + ShonanGaugeFactor factor(key, 7); // For SO(7) + Matrix A = Matrix::Zero(6, 21); // SO(7-3) = SO(4) == 6-dimensional gauge + A(0, 0) = 1; // first 3 of 7^th skew column, which has 6 non-zero entries + A(1, 1) = 1; + A(2, 2) = 1; // then we skip 3 tangent dimensions + A(3, 6) = 1; // first 2 of 6^th skew column, which has 5 non-zero entries + A(4, 7) = 1; // then we skip 3 tangent dimensions + A(5, 11) = 1; // first of 5th skew colum, which has 4 non-zero entries above + // diagonal. + JacobianFactor linearized(key, A, Vector::Zero(6)); + Values values; + EXPECT_LONGS_EQUAL(6, factor.dim()); + EXPECT(assert_equal(linearized, *boost::dynamic_pointer_cast( + factor.linearize(values)))); +} + +/* ************************************************************************* */ +// Check ShonanGaugeFactor for SO(6), with base SO(2) +TEST(ShonanAveraging, GaugeFactorSO6over2) { + constexpr Key key(602); + double gamma = 4; + ShonanGaugeFactor factor(key, 6, 2, gamma); // For SO(6), base SO(2) + Matrix A = Matrix::Zero(6, 15); // SO(6-2) = SO(4) == 6-dimensional gauge + A(0, 0) = 2; // first 3 of 6^th skew column, which has 5 non-zero entries + A(1, 1) = 2; + A(2, 2) = 2; // then we skip only 2 tangent dimensions + A(3, 5) = 2; // first 2 of 5^th skew column, which has 4 non-zero entries + A(4, 6) = 2; // then we skip only 2 tangent dimensions + A(5, 9) = 2; // first of 4th skew colum, which has 3 non-zero entries above + // diagonal. + JacobianFactor linearized(key, A, Vector::Zero(6)); + Values values; + EXPECT_LONGS_EQUAL(6, factor.dim()); + EXPECT(assert_equal(linearized, *boost::dynamic_pointer_cast( + factor.linearize(values)))); +} + +/* ************************************************************************* */ +int main() { + TestResult tr; + return TestRegistry::runAllTests(tr); +} +/* ************************************************************************* */ diff --git a/gtsam/slam/FrobeniusFactor.cpp b/gtsam/slam/FrobeniusFactor.cpp index 80aeea947..5697a0cd6 100644 --- a/gtsam/slam/FrobeniusFactor.cpp +++ b/gtsam/slam/FrobeniusFactor.cpp @@ -18,118 +18,38 @@ #include -#include -#include -#include - -#include -#include -#include - using namespace std; namespace gtsam { //****************************************************************************** -boost::shared_ptr ConvertPose3NoiseModel( - const SharedNoiseModel& model, size_t d, bool defaultToUnit) { +boost::shared_ptr +ConvertNoiseModel(const SharedNoiseModel &model, size_t d, bool defaultToUnit) { double sigma = 1.0; if (model != nullptr) { - if (model->dim() != 6) { - if (!defaultToUnit) - throw std::runtime_error("Can only convert Pose3 noise models"); - } else { - auto sigmas = model->sigmas().head(3).eval(); - if (sigmas(1) != sigmas(0) || sigmas(2) != sigmas(0)) { - if (!defaultToUnit) + auto sigmas = model->sigmas(); + size_t n = sigmas.size(); + if (n == 1) { + sigma = sigmas(0); // Rot2 + goto exit; + } + if (n == 3 || n == 6) { + sigma = sigmas(2); // Pose2, Rot3, or Pose3 + if (sigmas(0) != sigma || sigmas(1) != sigma) { + if (!defaultToUnit) { throw std::runtime_error("Can only convert isotropic rotation noise"); - } else { - sigma = sigmas(0); + } } + goto exit; + } + if (!defaultToUnit) { + throw std::runtime_error("Can only convert Pose2/Pose3 noise models"); } } +exit: return noiseModel::Isotropic::Sigma(d, sigma); } //****************************************************************************** -FrobeniusWormholeFactor::FrobeniusWormholeFactor( - Key j1, Key j2, const Rot3 &R12, size_t p, const SharedNoiseModel &model, - const boost::shared_ptr &G) - : NoiseModelFactor2(ConvertPose3NoiseModel(model, p * 3), j1, j2), - M_(R12.matrix()), // 3*3 in all cases - p_(p), // 4 for SO(4) - pp_(p * p), // 16 for SO(4) - G_(G) { - if (noiseModel()->dim() != 3 * p_) - throw std::invalid_argument( - "FrobeniusWormholeFactor: model with incorrect dimension."); - if (!G) { - G_ = boost::make_shared(); - *G_ = SOn::VectorizedGenerators(p); // expensive! - } - if (static_cast(G_->rows()) != pp_ || - static_cast(G_->cols()) != SOn::Dimension(p)) - throw std::invalid_argument("FrobeniusWormholeFactor: passed in generators " - "of incorrect dimension."); -} -//****************************************************************************** -void FrobeniusWormholeFactor::print(const std::string &s, const KeyFormatter &keyFormatter) const { - std::cout << s << "FrobeniusWormholeFactor<" << p_ << ">(" << keyFormatter(key1()) << "," - << keyFormatter(key2()) << ")\n"; - traits::Print(M_, " M: "); - noiseModel_->print(" noise model: "); -} - -//****************************************************************************** -bool FrobeniusWormholeFactor::equals(const NonlinearFactor &expected, - double tol) const { - auto e = dynamic_cast(&expected); - return e != nullptr && NoiseModelFactor2::equals(*e, tol) && - p_ == e->p_ && M_ == e->M_; -} - -//****************************************************************************** -Vector FrobeniusWormholeFactor::evaluateError( - const SOn& Q1, const SOn& Q2, boost::optional H1, - boost::optional H2) const { - gttic(FrobeniusWormholeFactorP_evaluateError); - - const Matrix& M1 = Q1.matrix(); - const Matrix& M2 = Q2.matrix(); - assert(M1.rows() == p_ && M2.rows() == p_); - - const size_t dim = 3 * p_; // Stiefel manifold dimension - Vector fQ2(dim), hQ1(dim); - - // Vectorize and extract only d leftmost columns, i.e. vec(M2*P) - fQ2 << Eigen::Map(M2.data(), dim, 1); - - // Vectorize M1*P*R12 - const Matrix Q1PR12 = M1.leftCols<3>() * M_; - hQ1 << Eigen::Map(Q1PR12.data(), dim, 1); - - // If asked, calculate Jacobian as (M \otimes M1) * G - if (H1) { - const size_t p2 = 2 * p_; - Matrix RPxQ = Matrix::Zero(dim, pp_); - RPxQ.block(0, 0, p_, dim) << M1 * M_(0, 0), M1 * M_(1, 0), M1 * M_(2, 0); - RPxQ.block(p_, 0, p_, dim) << M1 * M_(0, 1), M1 * M_(1, 1), M1 * M_(2, 1); - RPxQ.block(p2, 0, p_, dim) << M1 * M_(0, 2), M1 * M_(1, 2), M1 * M_(2, 2); - *H1 = -RPxQ * (*G_); - } - if (H2) { - const size_t p2 = 2 * p_; - Matrix PxQ = Matrix::Zero(dim, pp_); - PxQ.block(0, 0, p_, p_) = M2; - PxQ.block(p_, p_, p_, p_) = M2; - PxQ.block(p2, p2, p_, p_) = M2; - *H2 = PxQ * (*G_); - } - - return fQ2 - hQ1; -} - -//****************************************************************************** - -} // namespace gtsam +} // namespace gtsam diff --git a/gtsam/slam/FrobeniusFactor.h b/gtsam/slam/FrobeniusFactor.h index 474cf6143..1fc37c785 100644 --- a/gtsam/slam/FrobeniusFactor.h +++ b/gtsam/slam/FrobeniusFactor.h @@ -18,6 +18,7 @@ #pragma once +#include #include #include #include @@ -25,23 +26,24 @@ namespace gtsam { /** - * When creating (any) FrobeniusFactor we convert a 6-dimensional Pose3 - * BetweenFactor noise model into an 9 or 16-dimensional isotropic noise + * When creating (any) FrobeniusFactor we can convert a Rot/Pose + * BetweenFactor noise model into a n-dimensional isotropic noise * model used to weight the Frobenius norm. If the noise model passed is - * null we return a Dim-dimensional isotropic noise model with sigma=1.0. If - * not, we we check if the 3-dimensional noise model on rotations is - * isotropic. If it is, we extend to 'Dim' dimensions, otherwise we throw an + * null we return a n-dimensional isotropic noise model with sigma=1.0. If + * not, we we check if the d-dimensional noise model on rotations is + * isotropic. If it is, we extend to 'n' dimensions, otherwise we throw an * error. If defaultToUnit == false throws an exception on unexepcted input. */ - GTSAM_EXPORT boost::shared_ptr ConvertPose3NoiseModel( - const SharedNoiseModel& model, size_t d, bool defaultToUnit = true); +GTSAM_EXPORT boost::shared_ptr +ConvertNoiseModel(const SharedNoiseModel &model, size_t n, + bool defaultToUnit = true); /** * FrobeniusPrior calculates the Frobenius norm between a given matrix and an * element of SO(3) or SO(4). */ template -class FrobeniusPrior : public NoiseModelFactor1 { +class GTSAM_EXPORT FrobeniusPrior : public NoiseModelFactor1 { enum { Dim = Rot::VectorN2::RowsAtCompileTime }; using MatrixNN = typename Rot::MatrixNN; Eigen::Matrix vecM_; ///< vectorized matrix to approximate @@ -50,7 +52,7 @@ class FrobeniusPrior : public NoiseModelFactor1 { /// Constructor FrobeniusPrior(Key j, const MatrixNN& M, const SharedNoiseModel& model = nullptr) - : NoiseModelFactor1(ConvertPose3NoiseModel(model, Dim), j) { + : NoiseModelFactor1(ConvertNoiseModel(model, Dim), j) { vecM_ << Eigen::Map(M.data(), Dim, 1); } @@ -66,13 +68,13 @@ class FrobeniusPrior : public NoiseModelFactor1 { * The template argument can be any fixed-size SO. */ template -class FrobeniusFactor : public NoiseModelFactor2 { +class GTSAM_EXPORT FrobeniusFactor : public NoiseModelFactor2 { enum { Dim = Rot::VectorN2::RowsAtCompileTime }; public: /// Constructor FrobeniusFactor(Key j1, Key j2, const SharedNoiseModel& model = nullptr) - : NoiseModelFactor2(ConvertPose3NoiseModel(model, Dim), j1, + : NoiseModelFactor2(ConvertNoiseModel(model, Dim), j1, j2) {} /// Error is just Frobenius norm between rotation matrices. @@ -106,7 +108,7 @@ class GTSAM_EXPORT FrobeniusBetweenFactor : public NoiseModelFactor2 { FrobeniusBetweenFactor(Key j1, Key j2, const Rot& R12, const SharedNoiseModel& model = nullptr) : NoiseModelFactor2( - ConvertPose3NoiseModel(model, Dim), j1, j2), + ConvertNoiseModel(model, Dim), j1, j2), R12_(R12), R2hat_H_R1_(R12.inverse().AdjointMap()) {} @@ -150,52 +152,4 @@ class GTSAM_EXPORT FrobeniusBetweenFactor : public NoiseModelFactor2 { /// @} }; -/** - * FrobeniusWormholeFactor is a BetweenFactor that moves in SO(p), but will - * land on the SO(3) sub-manifold of SO(p) at the global minimum. It projects - * the SO(p) matrices down to a Stiefel manifold of p*d matrices. - * TODO(frank): template on D=2 or 3 - */ -class GTSAM_EXPORT FrobeniusWormholeFactor - : public NoiseModelFactor2 { - Matrix M_; ///< measured rotation between R1 and R2 - size_t p_, pp_; ///< dimensionality constants - boost::shared_ptr G_; ///< matrix of vectorized generators - -public: - /// @name Constructor - /// @{ - - /// Constructor. Note we convert to 3*p-dimensional noise model. - /// To save memory and mallocs, pass in the vectorized Lie algebra generators: - /// G = boost::make_shared(SOn::VectorizedGenerators(p)); - FrobeniusWormholeFactor(Key j1, Key j2, const Rot3 &R12, size_t p = 4, - const SharedNoiseModel &model = nullptr, - const boost::shared_ptr &G = nullptr); - - /// @} - /// @name Testable - /// @{ - - /// print with optional string - void - print(const std::string &s, - const KeyFormatter &keyFormatter = DefaultKeyFormatter) const override; - - /// assert equality up to a tolerance - bool equals(const NonlinearFactor &expected, - double tol = 1e-9) const override; - - /// @} - /// @name NoiseModelFactor2 methods - /// @{ - - /// Error is Frobenius norm between Q1*P*R12 and Q2*P, where P=[I_3x3;0] - /// projects down from SO(p) to the Stiefel manifold of px3 matrices. - Vector evaluateError(const SOn& Q1, const SOn& Q2, - boost::optional H1 = boost::none, - boost::optional H2 = boost::none) const override; - /// @} -}; - } // namespace gtsam diff --git a/gtsam/slam/KarcherMeanFactor-inl.h b/gtsam/slam/KarcherMeanFactor-inl.h index f10cc7e42..c81a9adc5 100644 --- a/gtsam/slam/KarcherMeanFactor-inl.h +++ b/gtsam/slam/KarcherMeanFactor-inl.h @@ -58,20 +58,22 @@ T FindKarcherMean(std::initializer_list&& rotations) { template template -KarcherMeanFactor::KarcherMeanFactor(const CONTAINER& keys, int d) - : NonlinearFactor(keys) { +KarcherMeanFactor::KarcherMeanFactor(const CONTAINER &keys, int d, + boost::optional beta) + : NonlinearFactor(keys), d_(static_cast(d)) { if (d <= 0) { throw std::invalid_argument( "KarcherMeanFactor needs dimension for dynamic types."); } - // Create the constant Jacobian made of D*D identity matrices, - // where D is the dimensionality of the manifold. - const auto I = Eigen::MatrixXd::Identity(d, d); + // Create the constant Jacobian made of d*d identity matrices, + // where d is the dimensionality of the manifold. + Matrix A = Matrix::Identity(d, d); + if (beta) A *= std::sqrt(*beta); std::map terms; for (Key j : keys) { - terms[j] = I; + terms[j] = A; } - jacobian_ = - boost::make_shared(terms, Eigen::VectorXd::Zero(d)); + whitenedJacobian_ = + boost::make_shared(terms, Vector::Zero(d)); } } // namespace gtsam \ No newline at end of file diff --git a/gtsam/slam/KarcherMeanFactor.h b/gtsam/slam/KarcherMeanFactor.h index 54b3930d4..b7cd3b11a 100644 --- a/gtsam/slam/KarcherMeanFactor.h +++ b/gtsam/slam/KarcherMeanFactor.h @@ -30,44 +30,51 @@ namespace gtsam { * PriorFactors. */ template -T FindKarcherMean(const std::vector>& rotations); +T FindKarcherMean(const std::vector> &rotations); -template -T FindKarcherMean(std::initializer_list&& rotations); +template T FindKarcherMean(std::initializer_list &&rotations); /** * The KarcherMeanFactor creates a constraint on all SO(n) variables with * given keys that the Karcher mean (see above) will stay the same. Note the * mean itself is irrelevant to the constraint and is not a parameter: the * constraint is implemented as enforcing that the sum of local updates is - * equal to zero, hence creating a rank-dim constraint. Note it is implemented as - * a soft constraint, as typically it is used to fix a gauge freedom. + * equal to zero, hence creating a rank-dim constraint. Note it is implemented + * as a soft constraint, as typically it is used to fix a gauge freedom. * */ -template -class KarcherMeanFactor : public NonlinearFactor { +template class KarcherMeanFactor : public NonlinearFactor { + // Compile time dimension: can be -1 + enum { D = traits::dimension }; + + // Runtime dimension: always >=0 + size_t d_; + /// Constant Jacobian made of d*d identity matrices - boost::shared_ptr jacobian_; + boost::shared_ptr whitenedJacobian_; - enum {D = traits::dimension}; - - public: - /// Construct from given keys. +public: + /** + * Construct from given keys. + * If parameter beta is given, it acts as a precision = 1/sigma^2, and + * the Jacobian will be multiplied with 1/sigma = sqrt(beta). + */ template - KarcherMeanFactor(const CONTAINER& keys, int d=D); + KarcherMeanFactor(const CONTAINER &keys, int d = D, + boost::optional beta = boost::none); /// Destructor virtual ~KarcherMeanFactor() {} /// Calculate the error of the factor: always zero - double error(const Values& c) const override { return 0; } + double error(const Values &c) const override { return 0; } /// get the dimension of the factor (number of rows on linearization) - size_t dim() const override { return D; } + size_t dim() const override { return d_; } /// linearize to a GaussianFactor - boost::shared_ptr linearize(const Values& c) const override { - return jacobian_; + boost::shared_ptr linearize(const Values &c) const override { + return whitenedJacobian_; } }; // \KarcherMeanFactor -} // namespace gtsam +} // namespace gtsam diff --git a/gtsam/slam/tests/testFrobeniusFactor.cpp b/gtsam/slam/tests/testFrobeniusFactor.cpp index 9cb0c19fa..321b54c86 100644 --- a/gtsam/slam/tests/testFrobeniusFactor.cpp +++ b/gtsam/slam/tests/testFrobeniusFactor.cpp @@ -188,54 +188,6 @@ TEST(FrobeniusBetweenFactorSO4, evaluateError) { EXPECT_CORRECT_FACTOR_JACOBIANS(factor, values, 1e-7, 1e-5); } -//****************************************************************************** -namespace submanifold { -SO4 id; -Vector6 v1 = (Vector(6) << 0, 0, 0, 0.1, 0, 0).finished(); -SO3 R1 = SO3::Expmap(v1.tail<3>()); -SO4 Q1 = SO4::Expmap(v1); -Vector6 v2 = (Vector(6) << 0, 0, 0, 0.01, 0.02, 0.03).finished(); -SO3 R2 = SO3::Expmap(v2.tail<3>()); -SO4 Q2 = SO4::Expmap(v2); -SO3 R12 = R1.between(R2); -} // namespace submanifold - -/* ************************************************************************* */ -TEST(FrobeniusWormholeFactor, evaluateError) { - auto model = noiseModel::Isotropic::Sigma(6, 1.2); // dimension = 6 not 16 - for (const size_t p : {5, 4, 3}) { - Matrix M = Matrix::Identity(p, p); - M.topLeftCorner(3, 3) = submanifold::R1.matrix(); - SOn Q1(M); - M.topLeftCorner(3, 3) = submanifold::R2.matrix(); - SOn Q2(M); - auto factor = - FrobeniusWormholeFactor(1, 2, Rot3(::so3::R12.matrix()), p, model); - Matrix H1, H2; - factor.evaluateError(Q1, Q2, H1, H2); - - // Test derivatives - Values values; - values.insert(1, Q1); - values.insert(2, Q2); - EXPECT_CORRECT_FACTOR_JACOBIANS(factor, values, 1e-7, 1e-5); - } -} - -/* ************************************************************************* */ -TEST(FrobeniusWormholeFactor, equivalenceToSO3) { - using namespace ::submanifold; - auto R12 = ::so3::R12.retract(Vector3(0.1, 0.2, -0.1)); - auto model = noiseModel::Isotropic::Sigma(6, 1.2); // wrong dimension - auto factor3 = FrobeniusBetweenFactor(1, 2, R12, model); - auto factor4 = FrobeniusWormholeFactor(1, 2, Rot3(R12.matrix()), 4, model); - const Matrix3 E3(factor3.evaluateError(R1, R2).data()); - const Matrix43 E4( - factor4.evaluateError(SOn(Q1.matrix()), SOn(Q2.matrix())).data()); - EXPECT(assert_equal((Matrix)E4.topLeftCorner<3, 3>(), E3, 1e-9)); - EXPECT(assert_equal((Matrix)E4.row(3), Matrix13::Zero(), 1e-9)); -} - /* ************************************************************************* */ int main() { TestResult tr; diff --git a/gtsam_unstable/gtsam_unstable.h b/gtsam_unstable/gtsam_unstable.h index ef2d16bf0..05b30bb0b 100644 --- a/gtsam_unstable/gtsam_unstable.h +++ b/gtsam_unstable/gtsam_unstable.h @@ -12,10 +12,14 @@ class gtsam::Point2Vector; class gtsam::Rot2; class gtsam::Pose2; class gtsam::Point3; +class gtsam::SO3; +class gtsam::SO4; +class gtsam::SOn; class gtsam::Rot3; class gtsam::Pose3; virtual class gtsam::noiseModel::Base; virtual class gtsam::noiseModel::Gaussian; +virtual class gtsam::noiseModel::Isotropic; virtual class gtsam::imuBias::ConstantBias; virtual class gtsam::NonlinearFactor; virtual class gtsam::NoiseModelFactor; @@ -39,6 +43,7 @@ class gtsam::KeyVector; class gtsam::LevenbergMarquardtParams; class gtsam::ISAM2Params; class gtsam::GaussianDensity; +class gtsam::LevenbergMarquardtOptimizer; namespace gtsam { @@ -282,7 +287,6 @@ virtual class PriorFactor : gtsam::NoiseModelFactor { void serializable() const; // enabling serialization functionality }; - #include template virtual class BetweenFactor : gtsam::NoiseModelFactor { diff --git a/gtsam_unstable/timing/process_shonan_timing_results.py b/gtsam_unstable/timing/process_shonan_timing_results.py new file mode 100644 index 000000000..9cf934dba --- /dev/null +++ b/gtsam_unstable/timing/process_shonan_timing_results.py @@ -0,0 +1,215 @@ +""" +Process timing results from timeShonanAveraging +""" + +import xlrd +import numpy as np +import matplotlib.pyplot as plt +from matplotlib.ticker import FuncFormatter +import heapq +from collections import Counter + +def make_combined_plot(name, p_values, times, costs, min_cost_range=10): + """ Make a plot that combines timing and SO(3) cost. + Arguments: + name: string of the plot title + p_values: list of p-values (int) + times: list of timings (seconds) + costs: list of costs (double) + Will calculate the range of the costs, default minimum range = 10.0 + """ + min_cost = min(costs) + cost_range = max(max(costs)-min_cost,min_cost_range) + fig = plt.figure() + ax1 = fig.add_subplot(111) + ax1.plot(p_values, times, label="time") + ax1.set_ylabel('Time used to optimize \ seconds') + ax1.set_xlabel('p_value') + ax2 = ax1.twinx() + ax2.plot(p_values, costs, 'r', label="cost") + ax2.set_ylabel('Cost at SO(3) form') + ax2.set_xlabel('p_value') + ax2.set_xticks(p_values) + ax2.set_ylim(min_cost, min_cost + cost_range) + plt.title(name, fontsize=12) + ax1.legend(loc="upper left") + ax2.legend(loc="upper right") + plt.interactive(False) + plt.show() + +def make_convergence_plot(name, p_values, times, costs, iter=10): + """ Make a bar that show the success rate for each p_value according to whether the SO(3) cost converges + Arguments: + name: string of the plot title + p_values: list of p-values (int) + times: list of timings (seconds) + costs: list of costs (double) + iter: int of iteration number for each p_value + """ + + max_cost = np.mean(np.array(heapq.nlargest(iter, costs))) + # calculate mean costs for each p value + p_values = list(dict(Counter(p_values)).keys()) + # make sure the iter number + iter = int(len(times)/len(p_values)) + p_mean_cost = [np.mean(np.array(costs[i*iter:(i+1)*iter])) for i in range(len(p_values))] + p_max = p_values[p_mean_cost.index(max(p_mean_cost))] + # print(p_mean_cost) + # print(p_max) + + #take mean and make the combined plot + mean_times = [] + mean_costs = [] + for p in p_values: + costs_tmp = costs[p_values.index(p)*iter:(p_values.index(p)+1)*iter] + mean_cost = sum(costs_tmp)/len(costs_tmp) + mean_costs.append(mean_cost) + times_tmp = times[p_values.index(p)*iter:(p_values.index(p)+1)*iter] + mean_time = sum(times_tmp)/len(times_tmp) + mean_times.append(mean_time) + make_combined_plot(name, p_values,mean_times, mean_costs) + + # calculate the convergence rate for each p_value + p_success_rates = [] + if p_mean_cost[0] >= 0.95*np.mean(np.array(costs)) and p_mean_cost[0] <= 1.05*np.mean(np.array(costs)): + p_success_rates = [ 1.0 for p in p_values] + else: + for p in p_values: + if p > p_max: + p_costs = costs[p_values.index(p)*iter:(p_values.index(p)+1)*iter] + # print(p_costs) + converged = [ int(p_cost < 0.3*max_cost) for p_cost in p_costs] + success_rate = sum(converged)/len(converged) + p_success_rates.append(success_rate) + else: + p_success_rates.append(0) + + plt.bar(p_values, p_success_rates, align='center', alpha=0.5) + plt.xticks(p_values) + plt.yticks(np.arange(0, 1.2, 0.2), ['0%', '20%', '40%', '60%', '80%', '100%']) + plt.xlabel("p_value") + plt.ylabel("success rate") + plt.title(name, fontsize=12) + plt.show() + +def make_eigen_and_bound_plot(name, p_values, times1, costPs, cost3s, times2, min_eigens, subounds): + """ Make a plot that combines time for optimizing, time for optimizing and compute min_eigen, + min_eigen, subound (subound = (f_R - f_SDP) / f_SDP). + Arguments: + name: string of the plot title + p_values: list of p-values (int) + times1: list of timings (seconds) + costPs: f_SDP + cost3s: f_R + times2: list of timings (seconds) + min_eigens: list of min_eigen (double) + subounds: list of subound (double) + """ + + if dict(Counter(p_values))[5] != 1: + p_values = list(dict(Counter(p_values)).keys()) + iter = int(len(times1)/len(p_values)) + p_mean_times1 = [np.mean(np.array(times1[i*iter:(i+1)*iter])) for i in range(len(p_values))] + p_mean_times2 = [np.mean(np.array(times2[i*iter:(i+1)*iter])) for i in range(len(p_values))] + print("p_values \n", p_values) + print("p_mean_times_opti \n", p_mean_times1) + print("p_mean_times_eig \n", p_mean_times2) + + p_mean_costPs = [np.mean(np.array(costPs[i*iter:(i+1)*iter])) for i in range(len(p_values))] + p_mean_cost3s = [np.mean(np.array(cost3s[i*iter:(i+1)*iter])) for i in range(len(p_values))] + p_mean_lambdas = [np.mean(np.array(min_eigens[i*iter:(i+1)*iter])) for i in range(len(p_values))] + + print("p_mean_costPs \n", p_mean_costPs) + print("p_mean_cost3s \n", p_mean_cost3s) + print("p_mean_lambdas \n", p_mean_lambdas) + print("*******************************************************************************************************************") + + + else: + plt.figure(1) + plt.ylabel('Time used (seconds)') + plt.xlabel('p_value') + plt.plot(p_values, times1, 'r', label="time for optimizing") + plt.plot(p_values, times2, 'blue', label="time for optimizing and check") + plt.title(name, fontsize=12) + plt.legend(loc="best") + plt.interactive(False) + plt.show() + + plt.figure(2) + plt.ylabel('Min eigen_value') + plt.xlabel('p_value') + plt.plot(p_values, min_eigens, 'r', label="min_eigen values") + plt.title(name, fontsize=12) + plt.legend(loc="best") + plt.interactive(False) + plt.show() + + plt.figure(3) + plt.ylabel('sub_bounds') + plt.xlabel('p_value') + plt.plot(p_values, subounds, 'blue', label="sub_bounds") + plt.title(name, fontsize=12) + plt.legend(loc="best") + plt.show() + +# Process arguments and call plot function +import argparse +import csv +import os + +parser = argparse.ArgumentParser() +parser.add_argument("path") +args = parser.parse_args() + + +file_path = [] +domain = os.path.abspath(args.path) +for info in os.listdir(args.path): + file_path.append(os.path.join(domain, info)) +file_path.sort() +print(file_path) + + +# name of all the plots +names = {} +names[0] = 'tinyGrid3D vertex = 9, edge = 11' +names[1] = 'smallGrid3D vertex = 125, edge = 297' +names[2] = 'parking-garage vertex = 1661, edge = 6275' +names[3] = 'sphere2500 vertex = 2500, edge = 4949' +# names[4] = 'sphere_bignoise vertex = 2200, edge = 8647' +names[5] = 'torus3D vertex = 5000, edge = 9048' +names[6] = 'cubicle vertex = 5750, edge = 16869' +names[7] = 'rim vertex = 10195, edge = 29743' + +# Parse CSV file +for key, name in names.items(): + print(key, name) + + # find according file to process + name_file = None + for path in file_path: + if name[0:3] in path: + name_file = path + if name_file == None: + print("The file %s is not in the path" % name) + continue + + p_values, times1, costPs, cost3s, times2, min_eigens, subounds = [],[],[],[],[],[],[] + with open(name_file) as csvfile: + reader = csv.reader(csvfile, delimiter='\t') + for row in reader: + print(row) + p_values.append(int(row[0])) + times1.append(float(row[1])) + costPs.append(float(row[2])) + cost3s.append(float(row[3])) + if len(row) > 4: + times2.append(float(row[4])) + min_eigens.append(float(row[5])) + subounds.append(float(row[6])) + + #plot + # make_combined_plot(name, p_values, times1, cost3s) + # make_convergence_plot(name, p_values, times1, cost3s) + make_eigen_and_bound_plot(name, p_values, times1, costPs, cost3s, times2, min_eigens, subounds) diff --git a/gtsam_unstable/timing/timeShonanAveraging.cpp b/gtsam_unstable/timing/timeShonanAveraging.cpp new file mode 100644 index 000000000..795961aef --- /dev/null +++ b/gtsam_unstable/timing/timeShonanAveraging.cpp @@ -0,0 +1,182 @@ +/* ---------------------------------------------------------------------------- + + * GTSAM Copyright 2010-2019, Georgia Tech Research Corporation, + * Atlanta, Georgia 30332-0415 + * All Rights Reserved + * Authors: Frank Dellaert, et al. (see THANKS for the full author list) + + * See LICENSE for the license information + + * -------------------------------------------------------------------------- */ + +/** + * @file testShonanAveraging.cpp + * @date September 2019 + * @author Jing Wu + * @author Frank Dellaert + * @brief Timing script for Shonan Averaging algorithm + */ + +#include "gtsam/base/Matrix.h" +#include "gtsam/base/Vector.h" +#include "gtsam/geometry/Point3.h" +#include "gtsam/geometry/Rot3.h" +#include +#include + +#include + +#include +#include +#include +#include + +using namespace std; +using namespace gtsam; + +// string g2oFile = findExampleDataFile("toyExample.g2o"); + +// save a single line of timing info to an output stream +void saveData(size_t p, double time1, double costP, double cost3, double time2, + double min_eigenvalue, double suBound, std::ostream* os) { + *os << (int)p << "\t" << time1 << "\t" << costP << "\t" << cost3 << "\t" + << time2 << "\t" << min_eigenvalue << "\t" << suBound << endl; +} + +void checkR(const Matrix& R) { + Matrix R2 = R.transpose(); + Matrix actual_R = R2 * R; + assert_equal(Rot3(),Rot3(actual_R)); +} + +void saveResult(string name, const Values& values) { + ofstream myfile; + myfile.open("shonan_result_of_" + name + ".dat"); + size_t nrSO3 = values.count(); + myfile << "#Type SO3 Number " << nrSO3 << "\n"; + for (int i = 0; i < nrSO3; ++i) { + Matrix R = values.at(i).matrix(); + // Check if the result of R.Transpose*R satisfy orthogonal constraint + checkR(R); + myfile << i; + for (int m = 0; m < 3; ++m) { + for (int n = 0; n < 3; ++n) { + myfile << " " << R(m, n); + } + } + myfile << "\n"; + } + myfile.close(); + cout << "Saved shonan_result.dat file" << endl; +} + +void saveG2oResult(string name, const Values& values, std::map poses) { + ofstream myfile; + myfile.open("shonan_result_of_" + name + ".g2o"); + size_t nrSO3 = values.count(); + for (int i = 0; i < nrSO3; ++i) { + Matrix R = values.at(i).matrix(); + // Check if the result of R.Transpose*R satisfy orthogonal constraint + checkR(R); + myfile << "VERTEX_SE3:QUAT" << " "; + myfile << i << " "; + myfile << poses[i].x() << " " << poses[i].y() << " " << poses[i].z() << " "; + Vector quaternion = Rot3(R).quaternion(); + myfile << quaternion(3) << " " << quaternion(2) << " " << quaternion(1) << " " << quaternion(0); + myfile << "\n"; + } + myfile.close(); + cout << "Saved shonan_result.g2o file" << endl; +} + +void saveResultQuat(const Values& values) { + ofstream myfile; + myfile.open("shonan_result.dat"); + size_t nrSOn = values.count(); + for (int i = 0; i < nrSOn; ++i) { + GTSAM_PRINT(values.at(i)); + Rot3 R = Rot3(values.at(i).matrix()); + float x = R.toQuaternion().x(); + float y = R.toQuaternion().y(); + float z = R.toQuaternion().z(); + float w = R.toQuaternion().w(); + myfile << "QuatSO3 " << i; + myfile << "QuatSO3 " << i << " " << w << " " << x << " " << y << " " << z << "\n"; + myfile.close(); + } +} + +int main(int argc, char* argv[]) { + // primitive argument parsing: + if (argc > 3) { + throw runtime_error("Usage: timeShonanAveraging [g2oFile]"); + } + + string g2oFile; + try { + if (argc > 1) + g2oFile = argv[argc - 1]; + else + g2oFile = string( + "/home/jingwu/git/SESync/data/sphere2500.g2o"); + + } catch (const exception& e) { + cerr << e.what() << '\n'; + exit(1); + } + + // Create a csv output file + size_t pos1 = g2oFile.find("data/"); + size_t pos2 = g2oFile.find(".g2o"); + string name = g2oFile.substr(pos1 + 5, pos2 - pos1 - 5); + cout << name << endl; + ofstream csvFile("shonan_timing_of_" + name + ".csv"); + + // Create Shonan averaging instance from the file. + // ShonanAveragingParameters parameters; + // double sigmaNoiseInRadians = 0 * M_PI / 180; + // parameters.setNoiseSigma(sigmaNoiseInRadians); + static const ShonanAveraging3 kShonan(g2oFile); + + // increase p value and try optimize using Shonan Algorithm. use chrono for + // timing + size_t pMin = 3; + Values Qstar; + Vector minEigenVector; + double CostP = 0, Cost3 = 0, lambdaMin = 0, suBound = 0; + cout << "(int)p" << "\t" << "time1" << "\t" << "costP" << "\t" << "cost3" << "\t" + << "time2" << "\t" << "MinEigenvalue" << "\t" << "SuBound" << endl; + + const Values randomRotations = kShonan.initializeRandomly(kRandomNumberGenerator); + + for (size_t p = pMin; p < 6; p++) { + // Randomly initialize at lowest level, initialize by line search after that + const Values initial = + (p > pMin) ? kShonan.initializeWithDescent(p, Qstar, minEigenVector, + lambdaMin) + : ShonanAveraging::LiftTo(pMin, randomRotations); + chrono::steady_clock::time_point t1 = chrono::steady_clock::now(); + // optimizing + const Values result = kShonan.tryOptimizingAt(p, initial); + chrono::steady_clock::time_point t2 = chrono::steady_clock::now(); + chrono::duration timeUsed1 = + chrono::duration_cast>(t2 - t1); + lambdaMin = kShonan.computeMinEigenValue(result, &minEigenVector); + chrono::steady_clock::time_point t3 = chrono::steady_clock::now(); + chrono::duration timeUsed2 = + chrono::duration_cast>(t3 - t1); + Qstar = result; + CostP = kShonan.costAt(p, result); + const Values SO3Values = kShonan.roundSolution(result); + Cost3 = kShonan.cost(SO3Values); + suBound = (Cost3 - CostP) / CostP; + + saveData(p, timeUsed1.count(), CostP, Cost3, timeUsed2.count(), + lambdaMin, suBound, &cout); + saveData(p, timeUsed1.count(), CostP, Cost3, timeUsed2.count(), + lambdaMin, suBound, &csvFile); + } + saveResult(name, kShonan.roundSolution(Qstar)); + // saveG2oResult(name, kShonan.roundSolution(Qstar), kShonan.Poses()); + return 0; +} diff --git a/timing/timeFrobeniusFactor.cpp b/timing/timeShonanFactor.cpp similarity index 92% rename from timing/timeFrobeniusFactor.cpp rename to timing/timeShonanFactor.cpp index 924213a33..207d54a4d 100644 --- a/timing/timeFrobeniusFactor.cpp +++ b/timing/timeShonanFactor.cpp @@ -10,8 +10,8 @@ * -------------------------------------------------------------------------- */ /** - * @file timeFrobeniusFactor.cpp - * @brief time FrobeniusFactor with BAL file + * @file timeShonanFactor.cpp + * @brief time ShonanFactor with BAL file * @author Frank Dellaert * @date 2019 */ @@ -27,7 +27,7 @@ #include #include #include -#include +#include #include #include @@ -42,7 +42,7 @@ static SharedNoiseModel gNoiseModel = noiseModel::Unit::Create(2); int main(int argc, char* argv[]) { // primitive argument parsing: if (argc > 3) { - throw runtime_error("Usage: timeFrobeniusFactor [g2oFile]"); + throw runtime_error("Usage: timeShonanFactor [g2oFile]"); } string g2oFile; @@ -70,7 +70,7 @@ int main(int argc, char* argv[]) { const auto &keys = m.keys(); const Rot3 &Rij = m.measured(); const auto &model = m.noiseModel(); - graph.emplace_shared( + graph.emplace_shared( keys[0], keys[1], Rij, 4, model, G); } From 5a85494f33118d7aff796ae1446d13f65a8d7340 Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Mon, 17 Aug 2020 13:12:40 -0400 Subject: [PATCH 387/869] replace atof/atoi with standardized stof/stoi --- examples/CombinedImuFactorsExample.cpp | 14 +++++++------- examples/ImuFactorsExample.cpp | 14 +++++++------- 2 files changed, 14 insertions(+), 14 deletions(-) diff --git a/examples/CombinedImuFactorsExample.cpp b/examples/CombinedImuFactorsExample.cpp index 2e5c46025..c9646e64d 100644 --- a/examples/CombinedImuFactorsExample.cpp +++ b/examples/CombinedImuFactorsExample.cpp @@ -85,10 +85,10 @@ Vector10 readInitialState(ifstream& file) { getline(file, value, ','); // i for (int i = 0; i < 9; i++) { getline(file, value, ','); - initial_state(i) = atof(value.c_str()); + initial_state(i) = stof(value.c_str()); } getline(file, value, '\n'); - initial_state(9) = atof(value.c_str()); + initial_state(9) = stof(value.c_str()); return initial_state; } @@ -204,16 +204,16 @@ int main(int argc, char* argv[]) { // Parse out first value string value; getline(file, value, ','); - int type = atoi(value.c_str()); + int type = stoi(value.c_str()); if (type == 0) { // IMU measurement Vector6 imu; for (int i = 0; i < 5; ++i) { getline(file, value, ','); - imu(i) = atof(value.c_str()); + imu(i) = stof(value.c_str()); } getline(file, value, '\n'); - imu(5) = atof(value.c_str()); + imu(5) = stof(value.c_str()); // Adding the IMU preintegration. preintegrated->integrateMeasurement(imu.head<3>(), imu.tail<3>(), dt); @@ -222,10 +222,10 @@ int main(int argc, char* argv[]) { Vector7 gps; for (int i = 0; i < 6; ++i) { getline(file, value, ','); - gps(i) = atof(value.c_str()); + gps(i) = stof(value.c_str()); } getline(file, value, '\n'); - gps(6) = atof(value.c_str()); + gps(6) = stof(value.c_str()); index++; diff --git a/examples/ImuFactorsExample.cpp b/examples/ImuFactorsExample.cpp index 20dc2c261..a8a9715e0 100644 --- a/examples/ImuFactorsExample.cpp +++ b/examples/ImuFactorsExample.cpp @@ -154,10 +154,10 @@ int main(int argc, char* argv[]) { getline(file, value, ','); // i for (int i = 0; i < 9; i++) { getline(file, value, ','); - initial_state(i) = atof(value.c_str()); + initial_state(i) = stof(value.c_str()); } getline(file, value, '\n'); - initial_state(9) = atof(value.c_str()); + initial_state(9) = stof(value.c_str()); cout << "initial state:\n" << initial_state.transpose() << "\n\n"; // Assemble initial quaternion through GTSAM constructor @@ -211,16 +211,16 @@ int main(int argc, char* argv[]) { while (file.good()) { // Parse out first value getline(file, value, ','); - int type = atoi(value.c_str()); + int type = stoi(value.c_str()); if (type == 0) { // IMU measurement Vector6 imu; for (int i = 0; i < 5; ++i) { getline(file, value, ','); - imu(i) = atof(value.c_str()); + imu(i) = stof(value.c_str()); } getline(file, value, '\n'); - imu(5) = atof(value.c_str()); + imu(5) = stof(value.c_str()); // Adding the IMU preintegration. preintegrated->integrateMeasurement(imu.head<3>(), imu.tail<3>(), dt); @@ -229,10 +229,10 @@ int main(int argc, char* argv[]) { Vector7 gps; for (int i = 0; i < 6; ++i) { getline(file, value, ','); - gps(i) = atof(value.c_str()); + gps(i) = stof(value.c_str()); } getline(file, value, '\n'); - gps(6) = atof(value.c_str()); + gps(6) = stof(value.c_str()); correction_count++; From 840831b62bda4248b41615fc74974f59e50e95cc Mon Sep 17 00:00:00 2001 From: Fan Jiang Date: Mon, 17 Aug 2020 14:37:12 -0400 Subject: [PATCH 388/869] Ported MATLAB Examples --- matlab/+gtsam/Point2.m | 12 +++++ matlab/+gtsam/Point3.m | 12 +++++ matlab/+gtsam/cylinderSampleProjection.m | 6 +-- .../+gtsam/cylinderSampleProjectionStereo.m | 20 ++++---- matlab/+gtsam/cylinderSampling.m | 6 +-- matlab/+gtsam/plotCamera.m | 2 +- matlab/+gtsam/plotFlyingResults.m | 16 +++---- matlab/+gtsam/plotPoint2.m | 6 +-- matlab/+gtsam/plotPoint3.m | 6 +-- matlab/+gtsam/plotPose3.m | 2 +- matlab/+gtsam/points2DTrackStereo.m | 2 +- matlab/gtsam_examples/CameraFlyingExample.m | 24 +++++----- matlab/gtsam_examples/MonocularVOExample.m | 4 +- matlab/gtsam_examples/PlanarSLAMExample.m | 9 ++-- .../PlanarSLAMExample_sampling.m | 11 +++-- matlab/gtsam_examples/Pose2SLAMwSPCG.m | 2 +- matlab/gtsam_examples/SBAExample.m | 4 +- matlab/gtsam_examples/SFMExample.m | 2 +- matlab/gtsam_examples/StereoVOExample.m | 8 ++-- matlab/gtsam_examples/VisualizeMEstimators.m | 2 +- matlab/gtsam_tests/testPlanarSLAMExample.m | 2 +- matlab/gtsam_tests/testSFMExample.m | 2 +- matlab/gtsam_tests/testStereoVOExample.m | 2 +- matlab/gtsam_tests/testValues.m | 8 ++-- matlab/gtsam_tests/testVisualISAMExample.m | 2 +- .../+imuSimulator/IMUComparison.m | 12 ++--- .../+imuSimulator/IMUComparison_with_cov.m | 4 +- .../+imuSimulator/calculateIMUMeas_coriolis.m | 2 +- .../+imuSimulator/calculateIMUMeasurement.m | 6 +-- .../+imuSimulator/coriolisExample.m | 30 ++++++------ .../+imuSimulator/covarianceAnalysisBetween.m | 10 ++-- .../covarianceAnalysisCreateFactorGraph.m | 8 ++-- .../covarianceAnalysisCreateTrajectory.m | 6 +-- .../+imuSimulator/integrateIMUTrajectory.m | 4 +- .../integrateIMUTrajectory_bodyFrame.m | 6 +-- .../integrateIMUTrajectory_navFrame.m | 4 +- .../+imuSimulator/integrateTrajectory.m | 8 ++-- .../+imuSimulator/test1onestep.m | 4 +- .../+imuSimulator/test2constglobal.m | 6 +-- .../+imuSimulator/test3constbody.m | 16 +++---- .../+imuSimulator/test4circle.m | 12 ++--- .../FlightCameraTransformIMU.m | 25 +++++----- ...ansformCalProjectionFactorIMUExampleISAM.m | 46 ++++++++++--------- .../plot_projected_landmarks.m | 6 +-- matlab/unstable_examples/project_landmarks.m | 4 +- 45 files changed, 213 insertions(+), 178 deletions(-) create mode 100644 matlab/+gtsam/Point2.m create mode 100644 matlab/+gtsam/Point3.m diff --git a/matlab/+gtsam/Point2.m b/matlab/+gtsam/Point2.m new file mode 100644 index 000000000..3ea65c33e --- /dev/null +++ b/matlab/+gtsam/Point2.m @@ -0,0 +1,12 @@ +function pt = Point2(varargin) + % Point2 shim + if nargin == 2 && isa(varargin{1}, 'double') + pt = [varargin{1} varargin{2}]'; + elseif nargin == 1 + pt = varargin{1}; + elseif nargin == 0 + pt = [0 0]'; + else + error('Arguments do not match any overload of Point2 shim'); + end +end \ No newline at end of file diff --git a/matlab/+gtsam/Point3.m b/matlab/+gtsam/Point3.m new file mode 100644 index 000000000..5f66b4517 --- /dev/null +++ b/matlab/+gtsam/Point3.m @@ -0,0 +1,12 @@ +function pt = Point3(varargin) + % Point3 shim + if nargin == 3 && isa(varargin{1}, 'double') + pt = [varargin{1} varargin{2} varargin{3}]'; + elseif nargin == 1 + pt = varargin{1}; + elseif nargin == 0 + pt = [0 0 0]'; + else + error('Arguments do not match any overload of Point3 shim'); + end +end \ No newline at end of file diff --git a/matlab/+gtsam/cylinderSampleProjection.m b/matlab/+gtsam/cylinderSampleProjection.m index 2b913b52d..697a57faa 100644 --- a/matlab/+gtsam/cylinderSampleProjection.m +++ b/matlab/+gtsam/cylinderSampleProjection.m @@ -50,9 +50,9 @@ for i = 1:cylinderNum visible = true; for k = 1:cylinderNum - rayCameraToPoint = pose.translation().between(sampledPoint3).vector(); - rayCameraToCylinder = pose.translation().between(cylinders{k}.centroid).vector(); - rayCylinderToPoint = cylinders{k}.centroid.between(sampledPoint3).vector(); + rayCameraToPoint = pose.translation().between(sampledPoint3); + rayCameraToCylinder = pose.translation().between(cylinders{k}.centroid); + rayCylinderToPoint = cylinders{k}.centroid.between(sampledPoint3); % Condition 1: all points in front of the cylinders' % surfaces are visible diff --git a/matlab/+gtsam/cylinderSampleProjectionStereo.m b/matlab/+gtsam/cylinderSampleProjectionStereo.m index 10409ac6d..58b4140fd 100644 --- a/matlab/+gtsam/cylinderSampleProjectionStereo.m +++ b/matlab/+gtsam/cylinderSampleProjectionStereo.m @@ -25,20 +25,20 @@ for i = 1:cylinderNum % For Cheirality Exception sampledPoint3 = cylinders{i}.Points{j}; sampledPoint3local = pose.transformTo(sampledPoint3); - if sampledPoint3local.z < 0 + if sampledPoint3local(3) < 0 continue; end % measurements - Z.du = K.fx() * K.baseline() / sampledPoint3local.z; - Z.uL = K.fx() * sampledPoint3local.x / sampledPoint3local.z + K.px(); + Z.du = K.fx() * K.baseline() / sampledPoint3local(3); + Z.uL = K.fx() * sampledPoint3local(1) / sampledPoint3local(3) + K.px(); Z.uR = Z.uL + Z.du; - Z.v = K.fy() / sampledPoint3local.z + K.py(); + Z.v = K.fy() / sampledPoint3local(3) + K.py(); % ignore points not visible in the scene - if Z.uL < 0 || Z.uL >= imageSize.x || ... - Z.uR < 0 || Z.uR >= imageSize.x || ... - Z.v < 0 || Z.v >= imageSize.y + if Z.uL < 0 || Z.uL >= imageSize(1) || ... + Z.uR < 0 || Z.uR >= imageSize(1) || ... + Z.v < 0 || Z.v >= imageSize(2) continue; end @@ -54,9 +54,9 @@ for i = 1:cylinderNum visible = true; for k = 1:cylinderNum - rayCameraToPoint = pose.translation().between(sampledPoint3).vector(); - rayCameraToCylinder = pose.translation().between(cylinders{k}.centroid).vector(); - rayCylinderToPoint = cylinders{k}.centroid.between(sampledPoint3).vector(); + rayCameraToPoint = sampledPoint3 - pose.translation(); + rayCameraToCylinder = cylinders{k}.centroid - pose.translation(); + rayCylinderToPoint = sampledPoint3 - cylinders{k}.centroid; % Condition 1: all points in front of the cylinders' % surfaces are visible diff --git a/matlab/+gtsam/cylinderSampling.m b/matlab/+gtsam/cylinderSampling.m index dcaa9c721..dc76295fa 100644 --- a/matlab/+gtsam/cylinderSampling.m +++ b/matlab/+gtsam/cylinderSampling.m @@ -12,8 +12,8 @@ function [cylinder] = cylinderSampling(baseCentroid, radius, height, density) % sample the points for i = 1:pointsNum theta = 2 * pi * rand; - x = radius * cos(theta) + baseCentroid.x; - y = radius * sin(theta) + baseCentroid.y; + x = radius * cos(theta) + baseCentroid(1); + y = radius * sin(theta) + baseCentroid(2); z = height * rand; points3{i,1} = Point3([x,y,z]'); end @@ -22,5 +22,5 @@ function [cylinder] = cylinderSampling(baseCentroid, radius, height, density) cylinder.radius = radius; cylinder.height = height; cylinder.Points = points3; - cylinder.centroid = Point3(baseCentroid.x, baseCentroid.y, height/2); + cylinder.centroid = Point3(baseCentroid(1), baseCentroid(2), height/2); end \ No newline at end of file diff --git a/matlab/+gtsam/plotCamera.m b/matlab/+gtsam/plotCamera.m index d0d1f45b7..986cd9a68 100644 --- a/matlab/+gtsam/plotCamera.m +++ b/matlab/+gtsam/plotCamera.m @@ -1,7 +1,7 @@ function plotCamera(pose, axisLength) hold on - C = pose.translation().vector(); + C = pose.translation(); R = pose.rotation().matrix(); xAxis = C+R(:,1)*axisLength; diff --git a/matlab/+gtsam/plotFlyingResults.m b/matlab/+gtsam/plotFlyingResults.m index 5d4a287c4..202f2409b 100644 --- a/matlab/+gtsam/plotFlyingResults.m +++ b/matlab/+gtsam/plotFlyingResults.m @@ -13,7 +13,7 @@ set(gcf, 'Position', [80,1,1800,1000]); %% plot all the cylinders and sampled points axis equal -axis([0, options.fieldSize.x, 0, options.fieldSize.y, 0, options.height + 30]); +axis([0, options.fieldSize(1), 0, options.fieldSize(2), 0, options.height + 30]); xlabel('X (m)'); ylabel('Y (m)'); zlabel('Height (m)'); @@ -50,8 +50,8 @@ for i = 1:cylinderNum [X,Y,Z] = cylinder(cylinders{i}.radius, sampleDensity * cylinders{i}.radius * cylinders{i}.height); - X = X + cylinders{i}.centroid.x; - Y = Y + cylinders{i}.centroid.y; + X = X + cylinders{i}.centroid(1); + Y = Y + cylinders{i}.centroid(2); Z = Z * cylinders{i}.height; h_cylinder{i} = surf(X,Y,Z); @@ -76,7 +76,7 @@ for i = 1:posesSize %plotCamera(poses{i}, 3); gRp = poses{i}.rotation().matrix(); % rotation from pose to global - C = poses{i}.translation().vector(); + C = poses{i}.translation(); axisLength = 3; xAxis = C+gRp(:,1)*axisLength; @@ -111,14 +111,14 @@ for i = 1:posesSize for j = 1:pointSize if ~isempty(pts3d{j}.cov{i}) hold on - h_point{j} = plot3(pts3d{j}.data.x, pts3d{j}.data.y, pts3d{j}.data.z); - h_point_cov{j} = gtsam.covarianceEllipse3D([pts3d{j}.data.x; pts3d{j}.data.y; pts3d{j}.data.z], ... + h_point{j} = plot3(pts3d{j}.data(1), pts3d{j}.data(2), pts3d{j}.data(3)); + h_point_cov{j} = gtsam.covarianceEllipse3D([pts3d{j}.data(1); pts3d{j}.data(2); pts3d{j}.data(3)], ... pts3d{j}.cov{i}, options.plot.covarianceScale); end end axis equal - axis([0, options.fieldSize.x, 0, options.fieldSize.y, 0, options.height + 30]); + axis([0, options.fieldSize(1), 0, options.fieldSize(2), 0, options.height + 30]); drawnow @@ -158,7 +158,7 @@ for i = 1 : posesSize hold on campos([poses{i}.x, poses{i}.y, poses{i}.z]); - camtarget([options.fieldSize.x/2, options.fieldSize.y/2, 0]); + camtarget([options.fieldSize(1)/2, options.fieldSize(2)/2, 0]); camlight(hlight, 'headlight'); if options.writeVideo diff --git a/matlab/+gtsam/plotPoint2.m b/matlab/+gtsam/plotPoint2.m index cd066951d..8d10ecab6 100644 --- a/matlab/+gtsam/plotPoint2.m +++ b/matlab/+gtsam/plotPoint2.m @@ -1,10 +1,10 @@ function plotPoint2(p,color,P) % plotPoint2 shows a Point2, possibly with covariance matrix if size(color,2)==1 - plot(p.x,p.y,[color '*']); + plot(p(1),p(2),[color '*']); else - plot(p.x,p.y,color); + plot(p(1),p(2),color); end if exist('P', 'var') && (~isempty(P)) - gtsam.covarianceEllipse([p.x;p.y],P,color(1)); + gtsam.covarianceEllipse([p(1);p(2)],P,color(1)); end \ No newline at end of file diff --git a/matlab/+gtsam/plotPoint3.m b/matlab/+gtsam/plotPoint3.m index 390b44939..85c84a210 100644 --- a/matlab/+gtsam/plotPoint3.m +++ b/matlab/+gtsam/plotPoint3.m @@ -1,12 +1,12 @@ function plotPoint3(p, color, P) %PLOTPOINT3 Plot a Point3 with an optional covariance matrix if size(color,2)==1 - plot3(p.x,p.y,p.z,[color '*']); + plot3(p(1),p(2),p(3),[color '*']); else - plot3(p.x,p.y,p.z,color); + plot3(p(1),p(2),p(3),color); end if exist('P', 'var') - gtsam.covarianceEllipse3D([p.x;p.y;p.z],P); + gtsam.covarianceEllipse3D([p(1);p(2);p(3)],P); end end diff --git a/matlab/+gtsam/plotPose3.m b/matlab/+gtsam/plotPose3.m index 8c3c7dd76..258e3f776 100644 --- a/matlab/+gtsam/plotPose3.m +++ b/matlab/+gtsam/plotPose3.m @@ -4,7 +4,7 @@ if nargin<3,axisLength=0.1;end % get rotation and translation (center) gRp = pose.rotation().matrix(); % rotation from pose to global -C = pose.translation().vector(); +C = pose.translation(); if ~isempty(axisLength) % draw the camera axes diff --git a/matlab/+gtsam/points2DTrackStereo.m b/matlab/+gtsam/points2DTrackStereo.m index 60c9f1295..04cddb7f7 100644 --- a/matlab/+gtsam/points2DTrackStereo.m +++ b/matlab/+gtsam/points2DTrackStereo.m @@ -38,7 +38,7 @@ graph.add(PriorFactorPose3(symbol('x', 1), cameraPoses{1}, posePriorNoise)); %% initialize graph and values initialEstimate = Values; for i = 1:pointsNum - point_j = points3d{i}.data.retract(0.05*randn(3,1)); + point_j = points3d{i}.data + (0.05*randn(3,1)); initialEstimate.insert(symbol('p', i), point_j); end diff --git a/matlab/gtsam_examples/CameraFlyingExample.m b/matlab/gtsam_examples/CameraFlyingExample.m index add2bc75a..a0dfef22a 100644 --- a/matlab/gtsam_examples/CameraFlyingExample.m +++ b/matlab/gtsam_examples/CameraFlyingExample.m @@ -46,7 +46,7 @@ options.camera.horizon = 60; % camera baseline options.camera.baseline = 0.05; % camera focal length -options.camera.f = round(options.camera.resolution.x * options.camera.horizon / ... +options.camera.f = round(options.camera.resolution(1) * options.camera.horizon / ... options.camera.fov); % camera focal baseline options.camera.fB = options.camera.f * options.camera.baseline; @@ -54,15 +54,15 @@ options.camera.fB = options.camera.f * options.camera.baseline; options.camera.disparity = options.camera.fB / options.camera.horizon; % Monocular Camera Calibration options.camera.monoK = Cal3_S2(options.camera.f, options.camera.f, 0, ... - options.camera.resolution.x/2, options.camera.resolution.y/2); + options.camera.resolution(1)/2, options.camera.resolution(2)/2); % Stereo Camera Calibration options.camera.stereoK = Cal3_S2Stereo(options.camera.f, options.camera.f, 0, ... - options.camera.resolution.x/2, options.camera.resolution.y/2, options.camera.disparity); + options.camera.resolution(1)/2, options.camera.resolution(2)/2, options.camera.disparity); % write video output options.writeVideo = true; % the testing field size (unit: meter) -options.fieldSize = Point2([100, 100]'); +options.fieldSize = Point2(100, 100); % camera flying speed (unit: meter / second) options.speed = 20; % camera flying height @@ -113,14 +113,14 @@ theta = 0; i = 1; while i <= cylinderNum theta = theta + 2*pi/10; - x = 40 * rand * cos(theta) + options.fieldSize.x/2; - y = 20 * rand * sin(theta) + options.fieldSize.y/2; - baseCentroid{i} = Point2([x, y]'); + x = 40 * rand * cos(theta) + options.fieldSize(1)/2; + y = 20 * rand * sin(theta) + options.fieldSize(2)/2; + baseCentroid{i} = Point2(x, y); % prevent two cylinders interact with each other regenerate = false; for j = 1:i-1 - if i > 1 && baseCentroid{i}.dist(baseCentroid{j}) < options.cylinder.radius * 2 + if i > 1 && norm(baseCentroid{i} - baseCentroid{j}) < options.cylinder.radius * 2 regenerate = true; break; end @@ -146,17 +146,17 @@ while 1 angle = 0.1*pi*(rand-0.5); inc_t = Point3(distance * cos(angle), ... distance * sin(angle), 0); - t = t.compose(inc_t); + t = t + inc_t; - if t.x > options.fieldSize.x - 10 || t.y > options.fieldSize.y - 10; + if t(1) > options.fieldSize(1) - 10 || t(2) > options.fieldSize(2) - 10; break; end %t = Point3([(i-1)*(options.fieldSize.x - 10)/options.poseNum + 10, ... % 15, 10]'); camera = PinholeCameraCal3_S2.Lookat(t, ... - Point3(options.fieldSize.x/2, options.fieldSize.y/2, 0), ... - Point3([0,0,1]'), options.camera.monoK); + Point3(options.fieldSize(1)/2, options.fieldSize(2)/2, 0), ... + Point3(0,0,1), options.camera.monoK); cameraPoses{end+1} = camera.pose; end diff --git a/matlab/gtsam_examples/MonocularVOExample.m b/matlab/gtsam_examples/MonocularVOExample.m index 11c4253de..0d09a1487 100644 --- a/matlab/gtsam_examples/MonocularVOExample.m +++ b/matlab/gtsam_examples/MonocularVOExample.m @@ -15,14 +15,14 @@ import gtsam.* %% Create two cameras and corresponding essential matrix E aRb = Rot3.Yaw(pi/2); -aTb = Point3 (0.1, 0, 0); +aTb = [.1, 0, 0]'; identity=Pose3; aPb = Pose3(aRb, aTb); cameraA = CalibratedCamera(identity); cameraB = CalibratedCamera(aPb); %% Create 5 points -P = { Point3(0, 0, 1), Point3(-0.1, 0, 1), Point3(0.1, 0, 1), Point3(0, 0.5, 0.5), Point3(0, -0.5, 0.5) }; +P = { [0, 0, 1]', [-0.1, 0, 1]', [0.1, 0, 1]', [0, 0.5, 0.5]', [0, -0.5, 0.5]' }; %% Project points in both cameras for i=1:5 diff --git a/matlab/gtsam_examples/PlanarSLAMExample.m b/matlab/gtsam_examples/PlanarSLAMExample.m index aec933d74..3febc23e6 100644 --- a/matlab/gtsam_examples/PlanarSLAMExample.m +++ b/matlab/gtsam_examples/PlanarSLAMExample.m @@ -71,9 +71,12 @@ marginals = Marginals(graph, result); plot2DTrajectory(result, [], marginals); plot2DPoints(result, 'b', marginals); -plot([result.atPose2(i1).x; result.atPoint2(j1).x],[result.atPose2(i1).y; result.atPoint2(j1).y], 'c-'); -plot([result.atPose2(i2).x; result.atPoint2(j1).x],[result.atPose2(i2).y; result.atPoint2(j1).y], 'c-'); -plot([result.atPose2(i3).x; result.atPoint2(j2).x],[result.atPose2(i3).y; result.atPoint2(j2).y], 'c-'); +p_j1 = result.atPoint2(j1); +p_j2 = result.atPoint2(j2); + +plot([result.atPose2(i1).x; p_j1(1)],[result.atPose2(i1).y; p_j1(2)], 'c-'); +plot([result.atPose2(i2).x; p_j1(1)],[result.atPose2(i2).y; p_j1(2)], 'c-'); +plot([result.atPose2(i3).x; p_j2(1)],[result.atPose2(i3).y; p_j2(2)], 'c-'); axis([-0.6 4.8 -1 1]) axis equal view(2) diff --git a/matlab/gtsam_examples/PlanarSLAMExample_sampling.m b/matlab/gtsam_examples/PlanarSLAMExample_sampling.m index 375ed645c..93979a68a 100644 --- a/matlab/gtsam_examples/PlanarSLAMExample_sampling.m +++ b/matlab/gtsam_examples/PlanarSLAMExample_sampling.m @@ -60,15 +60,18 @@ for j=1:2 S{j}=chol(Q{j}); % for sampling end -plot([sample.atPose2(i1).x; sample.atPoint2(j1).x],[sample.atPose2(i1).y; sample.atPoint2(j1).y], 'c-'); -plot([sample.atPose2(i2).x; sample.atPoint2(j1).x],[sample.atPose2(i2).y; sample.atPoint2(j1).y], 'c-'); -plot([sample.atPose2(i3).x; sample.atPoint2(j2).x],[sample.atPose2(i3).y; sample.atPoint2(j2).y], 'c-'); +p_j1 = sample.atPoint2(j1); +p_j2 = sample.atPoint2(j2); + +plot([sample.atPose2(i1).x; p_j1(1)],[sample.atPose2(i1).y; p_j1(2)], 'c-'); +plot([sample.atPose2(i2).x; p_j1(1)],[sample.atPose2(i2).y; p_j1(2)], 'c-'); +plot([sample.atPose2(i3).x; p_j2(1)],[sample.atPose2(i3).y; p_j2(2)], 'c-'); view(2); axis auto; axis equal %% Do Sampling on point 2 N=1000; for s=1:N delta = S{2}*randn(2,1); - proposedPoint = Point2(point{2}.x+delta(1),point{2}.y+delta(2)); + proposedPoint = Point2(point{2} + delta); plotPoint2(proposedPoint,'k.') end \ No newline at end of file diff --git a/matlab/gtsam_examples/Pose2SLAMwSPCG.m b/matlab/gtsam_examples/Pose2SLAMwSPCG.m index 67f22fe1d..2df7efe2f 100644 --- a/matlab/gtsam_examples/Pose2SLAMwSPCG.m +++ b/matlab/gtsam_examples/Pose2SLAMwSPCG.m @@ -54,7 +54,7 @@ initialEstimate.print(sprintf('\nInitial estimate:\n')); %% Optimize using Levenberg-Marquardt optimization with SubgraphSolver params = gtsam.LevenbergMarquardtParams; subgraphParams = gtsam.SubgraphSolverParameters; -params.setLinearSolverType('CONJUGATE_GRADIENT'); +params.setLinearSolverType('ITERATIVE'); params.setIterativeParams(subgraphParams); optimizer = gtsam.LevenbergMarquardtOptimizer(graph, initialEstimate); result = optimizer.optimize(); diff --git a/matlab/gtsam_examples/SBAExample.m b/matlab/gtsam_examples/SBAExample.m index 584ace09a..f94a2ee4e 100644 --- a/matlab/gtsam_examples/SBAExample.m +++ b/matlab/gtsam_examples/SBAExample.m @@ -47,7 +47,7 @@ end %% Add Gaussian priors for a pose and a landmark to constrain the system cameraPriorNoise = noiseModel.Diagonal.Sigmas(cameraNoiseSigmas); firstCamera = PinholeCameraCal3_S2(truth.cameras{1}.pose, truth.K); -graph.add(PriorFactorSimpleCamera(symbol('c',1), firstCamera, cameraPriorNoise)); +graph.add(PriorFactorPinholeCameraCal3_S2(symbol('c',1), firstCamera, cameraPriorNoise)); pointPriorNoise = noiseModel.Isotropic.Sigma(3,pointNoiseSigma); graph.add(PriorFactorPoint3(symbol('p',1), truth.points{1}, pointPriorNoise)); @@ -64,7 +64,7 @@ for i=1:size(truth.cameras,2) initialEstimate.insert(symbol('c',i), camera_i); end for j=1:size(truth.points,2) - point_j = Point3(truth.points{j}.vector() + 0.1*randn(3,1)); + point_j = Point3(truth.points{j} + 0.1*randn(3,1)); initialEstimate.insert(symbol('p',j), point_j); end initialEstimate.print(sprintf('\nInitial estimate:\n ')); diff --git a/matlab/gtsam_examples/SFMExample.m b/matlab/gtsam_examples/SFMExample.m index 6700e90d2..a57da929c 100644 --- a/matlab/gtsam_examples/SFMExample.m +++ b/matlab/gtsam_examples/SFMExample.m @@ -58,7 +58,7 @@ for i=1:size(truth.cameras,2) initialEstimate.insert(symbol('x',i), pose_i); end for j=1:size(truth.points,2) - point_j = Point3(truth.points{j}.vector() + 0.1*randn(3,1)); + point_j = Point3(truth.points{j} + 0.1*randn(3,1)); initialEstimate.insert(symbol('p',j), point_j); end initialEstimate.print(sprintf('\nInitial estimate:\n ')); diff --git a/matlab/gtsam_examples/StereoVOExample.m b/matlab/gtsam_examples/StereoVOExample.m index b437ca80c..e7345fcf2 100644 --- a/matlab/gtsam_examples/StereoVOExample.m +++ b/matlab/gtsam_examples/StereoVOExample.m @@ -51,10 +51,10 @@ graph.add(GenericStereoFactor3D(StereoPoint2(320, 270, 115), stereo_model, x2, l initialEstimate = Values; initialEstimate.insert(x1, first_pose); % noisy estimate for pose 2 -initialEstimate.insert(x2, Pose3(Rot3(), Point3(0.1,-.1,1.1))); -initialEstimate.insert(l1, Point3( 1, 1, 5)); -initialEstimate.insert(l2, Point3(-1, 1, 5)); -initialEstimate.insert(l3, Point3( 0,-.5, 5)); +initialEstimate.insert(x2, Pose3(Rot3(), [0.1, -.1, 1.1]')); +initialEstimate.insert(l1, [ 1, 1, 5]'); +initialEstimate.insert(l2, [-1, 1, 5]'); +initialEstimate.insert(l3, [ 0,-.5, 5]'); %% optimize fprintf(1,'Optimizing\n'); tic diff --git a/matlab/gtsam_examples/VisualizeMEstimators.m b/matlab/gtsam_examples/VisualizeMEstimators.m index 8a0485334..ce505df5d 100644 --- a/matlab/gtsam_examples/VisualizeMEstimators.m +++ b/matlab/gtsam_examples/VisualizeMEstimators.m @@ -48,7 +48,7 @@ function plot_m_estimator(x, model, plot_title, fig_id, filename) rho = zeros(size(x)); for i = 1:size(x, 2) w(i) = model.weight(x(i)); - rho(i) = model.residual(x(i)); + rho(i) = model.loss(x(i)); end psi = w .* x; diff --git a/matlab/gtsam_tests/testPlanarSLAMExample.m b/matlab/gtsam_tests/testPlanarSLAMExample.m index d3cab5d1f..e0b4dbfc8 100644 --- a/matlab/gtsam_tests/testPlanarSLAMExample.m +++ b/matlab/gtsam_tests/testPlanarSLAMExample.m @@ -66,4 +66,4 @@ CHECK('pose_1.equals(Pose2,1e-4)',pose_1.equals(Pose2,1e-4)); point_1 = result.atPoint2(symbol('l',1)); marginals.marginalCovariance(symbol('l',1)); -CHECK('point_1.equals(Point2(2,2),1e-4)',point_1.equals(Point2(2,2),1e-4)); +CHECK('point_1.equals(Point2(2,2),1e-4)',norm(point_1 - Point2(2,2)) < 1e-4); diff --git a/matlab/gtsam_tests/testSFMExample.m b/matlab/gtsam_tests/testSFMExample.m index 985cbdb2c..a1f63c3a7 100644 --- a/matlab/gtsam_tests/testSFMExample.m +++ b/matlab/gtsam_tests/testSFMExample.m @@ -69,5 +69,5 @@ end for j=1:size(truth.points,2) point_j = result.atPoint3(symbol('p',j)); - CHECK('point_j.equals(truth.points{j},1e-5)',point_j.equals(truth.points{j},1e-5)) + CHECK('point_j.equals(truth.points{j},1e-5)',norm(point_j - truth.points{j}) < 1e-5) end diff --git a/matlab/gtsam_tests/testStereoVOExample.m b/matlab/gtsam_tests/testStereoVOExample.m index 218d0ace1..c721244ba 100644 --- a/matlab/gtsam_tests/testStereoVOExample.m +++ b/matlab/gtsam_tests/testStereoVOExample.m @@ -65,4 +65,4 @@ pose_x1 = result.atPose3(x1); CHECK('pose_x1.equals(first_pose,1e-4)',pose_x1.equals(first_pose,1e-4)); point_l1 = result.atPoint3(l1); -CHECK('point_1.equals(expected_l1,1e-4)',point_l1.equals(expected_l1,1e-4)); \ No newline at end of file +CHECK('point_1.equals(expected_l1,1e-4)',norm(point_l1 - expected_l1) < 1e-4); \ No newline at end of file diff --git a/matlab/gtsam_tests/testValues.m b/matlab/gtsam_tests/testValues.m index fe2cd30fe..48bc83f2c 100644 --- a/matlab/gtsam_tests/testValues.m +++ b/matlab/gtsam_tests/testValues.m @@ -5,8 +5,8 @@ values = Values; E = EssentialMatrix(Rot3,Unit3); tol = 1e-9; -values.insert(0, Point2); -values.insert(1, Point3); +values.insert(0, Point2(0, 0)); +values.insert(1, Point3(0, 0, 0)); values.insert(2, Rot2); values.insert(3, Pose2); values.insert(4, Rot3); @@ -21,8 +21,8 @@ values.insert(10, imuBias.ConstantBias); values.insert(11, [1;2;3]); values.insert(12, [1 2;3 4]); -EXPECT('at',values.atPoint2(0).equals(Point2,tol)); -EXPECT('at',values.atPoint3(1).equals(Point3,tol)); +EXPECT('at',values.atPoint2(0) == Point2(0, 0)); +EXPECT('at',values.atPoint3(1) == Point3(0, 0, 0)); EXPECT('at',values.atRot2(2).equals(Rot2,tol)); EXPECT('at',values.atPose2(3).equals(Pose2,tol)); EXPECT('at',values.atRot3(4).equals(Rot3,tol)); diff --git a/matlab/gtsam_tests/testVisualISAMExample.m b/matlab/gtsam_tests/testVisualISAMExample.m index 223e823a6..f75942ea7 100644 --- a/matlab/gtsam_tests/testVisualISAMExample.m +++ b/matlab/gtsam_tests/testVisualISAMExample.m @@ -51,5 +51,5 @@ end for j=1:size(truth.points,2) point_j = result.atPoint3(symbol('l',j)); - CHECK('point_j.equals(truth.points{j},1e-5)',point_j.equals(truth.points{j},1e-5)) + CHECK('point_j.equals(truth.points{j},1e-5)',norm(point_j - truth.points{j}) < 1e-5) end diff --git a/matlab/unstable_examples/+imuSimulator/IMUComparison.m b/matlab/unstable_examples/+imuSimulator/IMUComparison.m index 68e20bb25..871f023ef 100644 --- a/matlab/unstable_examples/+imuSimulator/IMUComparison.m +++ b/matlab/unstable_examples/+imuSimulator/IMUComparison.m @@ -28,19 +28,19 @@ currentVelocityGlobalIMUbody = currentVelocityGlobal; %% Prepare data structures for actual trajectory and estimates % Actual trajectory positions = zeros(3, length(times)+1); -positions(:,1) = currentPoseGlobal.translation.vector; +positions(:,1) = currentPoseGlobal.translation; poses(1).p = positions(:,1); poses(1).R = currentPoseGlobal.rotation.matrix; % Trajectory estimate (integrated in the navigation frame) positionsIMUnav = zeros(3, length(times)+1); -positionsIMUnav(:,1) = currentPoseGlobalIMUbody.translation.vector; +positionsIMUnav(:,1) = currentPoseGlobalIMUbody.translation; posesIMUnav(1).p = positionsIMUnav(:,1); posesIMUnav(1).R = poses(1).R; % Trajectory estimate (integrated in the body frame) positionsIMUbody = zeros(3, length(times)+1); -positionsIMUbody(:,1) = currentPoseGlobalIMUbody.translation.vector; +positionsIMUbody(:,1) = currentPoseGlobalIMUbody.translation; posesIMUbody(1).p = positionsIMUbody(:,1); posesIMUbody(1).R = poses(1).R; @@ -120,9 +120,9 @@ for t = times currentPoseGlobalIMUnav, currentVelocityGlobalIMUnav, acc_omega, deltaT); %% Store data in some structure for statistics and plots - positions(:,i) = currentPoseGlobal.translation.vector; - positionsIMUbody(:,i) = currentPoseGlobalIMUbody.translation.vector; - positionsIMUnav(:,i) = currentPoseGlobalIMUnav.translation.vector; + positions(:,i) = currentPoseGlobal.translation; + positionsIMUbody(:,i) = currentPoseGlobalIMUbody.translation; + positionsIMUnav(:,i) = currentPoseGlobalIMUnav.translation; % - poses(i).p = positions(:,i); posesIMUbody(i).p = positionsIMUbody(:,i); diff --git a/matlab/unstable_examples/+imuSimulator/IMUComparison_with_cov.m b/matlab/unstable_examples/+imuSimulator/IMUComparison_with_cov.m index c589bea32..450697de0 100644 --- a/matlab/unstable_examples/+imuSimulator/IMUComparison_with_cov.m +++ b/matlab/unstable_examples/+imuSimulator/IMUComparison_with_cov.m @@ -28,7 +28,7 @@ currentVelocityGlobal = velocity; %% Prepare data structures for actual trajectory and estimates % Actual trajectory positions = zeros(3, length(times)+1); -positions(:,1) = currentPoseGlobal.translation.vector; +positions(:,1) = currentPoseGlobal.translation; poses(1).p = positions(:,1); poses(1).R = currentPoseGlobal.rotation.matrix; @@ -112,7 +112,7 @@ for t = times end %% Store data in some structure for statistics and plots - positions(:,i) = currentPoseGlobal.translation.vector; + positions(:,i) = currentPoseGlobal.translation; i = i + 1; end diff --git a/matlab/unstable_examples/+imuSimulator/calculateIMUMeas_coriolis.m b/matlab/unstable_examples/+imuSimulator/calculateIMUMeas_coriolis.m index c86e40a21..0d8abad2c 100644 --- a/matlab/unstable_examples/+imuSimulator/calculateIMUMeas_coriolis.m +++ b/matlab/unstable_examples/+imuSimulator/calculateIMUMeas_coriolis.m @@ -7,7 +7,7 @@ measuredOmega = omega1Body; % Acceleration measurement (in this simple toy example no other forces % act on the body and the only acceleration is the centripetal Coriolis acceleration) -measuredAcc = Point3(cross(omega1Body, velocity1Body)).vector; +measuredAcc = Point3(cross(omega1Body, velocity1Body)); acc_omega = [ measuredAcc; measuredOmega ]; end diff --git a/matlab/unstable_examples/+imuSimulator/calculateIMUMeasurement.m b/matlab/unstable_examples/+imuSimulator/calculateIMUMeasurement.m index 534b9365e..5ed1fc516 100644 --- a/matlab/unstable_examples/+imuSimulator/calculateIMUMeasurement.m +++ b/matlab/unstable_examples/+imuSimulator/calculateIMUMeasurement.m @@ -6,16 +6,16 @@ import gtsam.*; % Calculate gyro measured rotation rate by transforming body rotation rate % into the IMU frame. -measuredOmega = imuFrame.rotation.unrotate(Point3(omega1Body)).vector; +measuredOmega = imuFrame.rotation.unrotate(Point3(omega1Body)); % Transform both velocities into IMU frame, accounting for the velocity % induced by rigid body rotation on a lever arm (Coriolis effect). velocity1inertial = imuFrame.rotation.unrotate( ... - Point3(velocity1Body + cross(omega1Body, imuFrame.translation.vector))).vector; + Point3(velocity1Body + cross(omega1Body, imuFrame.translation))); imu2in1 = Rot3.Expmap(measuredOmega * deltaT); velocity2inertial = imu2in1.rotate(imuFrame.rotation.unrotate( ... - Point3(velocity2Body + cross(omega2Body, imuFrame.translation.vector)))).vector; + Point3(velocity2Body + cross(omega2Body, imuFrame.translation)))); % Acceleration in IMU frame measuredAcc = (velocity2inertial - velocity1inertial) / deltaT; diff --git a/matlab/unstable_examples/+imuSimulator/coriolisExample.m b/matlab/unstable_examples/+imuSimulator/coriolisExample.m index 35d27aa73..ee4deb433 100644 --- a/matlab/unstable_examples/+imuSimulator/coriolisExample.m +++ b/matlab/unstable_examples/+imuSimulator/coriolisExample.m @@ -190,13 +190,13 @@ for i = 1:length(times) newFactors.add(PriorFactorConstantBias(currentBiasKey, zeroBias, sigma_init_b)); % Store data - positionsInFixedGT(:,1) = currentPoseFixedGT.translation.vector; + positionsInFixedGT(:,1) = currentPoseFixedGT.translation; velocityInFixedGT(:,1) = currentVelocityFixedGT; - positionsInRotatingGT(:,1) = currentPoseRotatingGT.translation.vector; - %velocityInRotatingGT(:,1) = currentPoseRotatingGT.velocity.vector; - positionsEstimates(:,i) = currentPoseEstimate.translation.vector; - velocitiesEstimates(:,i) = currentVelocityEstimate.vector; - currentRotatingFrameForPlot(1).p = currentRotatingFrame.translation.vector; + positionsInRotatingGT(:,1) = currentPoseRotatingGT.translation; + %velocityInRotatingGT(:,1) = currentPoseRotatingGT.velocity; + positionsEstimates(:,i) = currentPoseEstimate.translation; + velocitiesEstimates(:,i) = currentVelocityEstimate; + currentRotatingFrameForPlot(1).p = currentRotatingFrame.translation; currentRotatingFrameForPlot(1).R = currentRotatingFrame.rotation.matrix; else @@ -204,18 +204,18 @@ for i = 1:length(times) % Update the position and velocity % x_t = x_0 + v_0*dt + 1/2*a_0*dt^2 % v_t = v_0 + a_0*dt - currentPositionFixedGT = Point3(currentPoseFixedGT.translation.vector ... + currentPositionFixedGT = Point3(currentPoseFixedGT.translation ... + currentVelocityFixedGT * deltaT + 0.5 * accelFixed * deltaT * deltaT); currentVelocityFixedGT = currentVelocityFixedGT + accelFixed * deltaT; currentPoseFixedGT = Pose3(Rot3, currentPositionFixedGT); % constant orientation % Rotate pose in fixed frame to get pose in rotating frame - previousPositionRotatingGT = currentPoseRotatingGT.translation.vector; + previousPositionRotatingGT = currentPoseRotatingGT.translation; currentRotatingFrame = currentRotatingFrame.compose(changePoseRotatingFrame); inverseCurrentRotatingFrame = (currentRotatingFrame.inverse); currentPoseRotatingGT = inverseCurrentRotatingFrame.compose(currentPoseFixedGT); - currentPositionRotatingGT = currentPoseRotatingGT.translation.vector; + currentPositionRotatingGT = currentPoseRotatingGT.translation; % Get velocity in rotating frame by treating it like a position and using compose % Maybe Luca knows a better way to do this within GTSAM. @@ -230,11 +230,11 @@ for i = 1:length(times) % - 0.5 * accelFixed * deltaT * deltaT) / deltaT + accelFixed * deltaT; % Store GT (ground truth) poses - positionsInFixedGT(:,i) = currentPoseFixedGT.translation.vector; + positionsInFixedGT(:,i) = currentPoseFixedGT.translation; velocityInFixedGT(:,i) = currentVelocityFixedGT; - positionsInRotatingGT(:,i) = currentPoseRotatingGT.translation.vector; + positionsInRotatingGT(:,i) = currentPoseRotatingGT.translation; velocityInRotatingGT(:,i) = currentVelocityRotatingGT; - currentRotatingFrameForPlot(i).p = currentRotatingFrame.translation.vector; + currentRotatingFrameForPlot(i).p = currentRotatingFrame.translation; currentRotatingFrameForPlot(i).R = currentRotatingFrame.rotation.matrix; %% Estimate trajectory in rotating frame using GTSAM (ground truth measurements) @@ -303,9 +303,9 @@ for i = 1:length(times) currentVelocityEstimate = isam.calculateEstimate(currentVelKey); currentBias = isam.calculateEstimate(currentBiasKey); - positionsEstimates(:,i) = currentPoseEstimate.translation.vector; - velocitiesEstimates(:,i) = currentVelocityEstimate.vector; - biasEstimates(:,i) = currentBias.vector; + positionsEstimates(:,i) = currentPoseEstimate.translation; + velocitiesEstimates(:,i) = currentVelocityEstimate; + biasEstimates(:,i) = currentBias; % In matrix form: R_error = R_gt'*R_estimate % Perform Logmap on the rotation matrix to get a vector diff --git a/matlab/unstable_examples/+imuSimulator/covarianceAnalysisBetween.m b/matlab/unstable_examples/+imuSimulator/covarianceAnalysisBetween.m index 2eddf75ee..64ba36d3b 100644 --- a/matlab/unstable_examples/+imuSimulator/covarianceAnalysisBetween.m +++ b/matlab/unstable_examples/+imuSimulator/covarianceAnalysisBetween.m @@ -151,14 +151,14 @@ hold on; if options.includeCameraFactors b = [-1000 2000 -2000 2000 -30 30]; for i = 1:size(metadata.camera.gtLandmarkPoints,2) - p = metadata.camera.gtLandmarkPoints(i).vector; + p = metadata.camera.gtLandmarkPoints(i); if(p(1) > b(1) && p(1) < b(2) && p(2) > b(3) && p(2) < b(4) && p(3) > b(5) && p(3) < b(6)) plot3(p(1), p(2), p(3), 'k+'); end end pointsToPlot = metadata.camera.gtLandmarkPoints(find(projectionFactorSeenBy > 0)); for i = 1:length(pointsToPlot) - p = pointsToPlot(i).vector; + p = pointsToPlot(i); plot3(p(1), p(2), p(3), 'gs', 'MarkerSize', 10); end end @@ -233,9 +233,9 @@ for k=1:numMonteCarloRuns for i=0:options.trajectoryLength % compute estimation errors currentPoseKey = symbol('x', i); - gtPosition = gtValues.at(currentPoseKey).translation.vector; - estPosition = estimate.at(currentPoseKey).translation.vector; - estR = estimate.at(currentPoseKey).rotation.matrix; + gtPosition = gtValues.atPose3(currentPoseKey).translation; + estPosition = estimate.atPose3(currentPoseKey).translation; + estR = estimate.atPose3(currentPoseKey).rotation.matrix; errPosition = estPosition - gtPosition; % compute covariances: diff --git a/matlab/unstable_examples/+imuSimulator/covarianceAnalysisCreateFactorGraph.m b/matlab/unstable_examples/+imuSimulator/covarianceAnalysisCreateFactorGraph.m index 00ae4b9c2..07f146dcb 100644 --- a/matlab/unstable_examples/+imuSimulator/covarianceAnalysisCreateFactorGraph.m +++ b/matlab/unstable_examples/+imuSimulator/covarianceAnalysisCreateFactorGraph.m @@ -14,7 +14,7 @@ graph = NonlinearFactorGraph; for i=0:length(measurements) % Get the current pose currentPoseKey = symbol('x', i); - currentPose = values.at(currentPoseKey); + currentPose = values.atPose3(currentPoseKey); if i==0 %% first time step, add priors @@ -26,11 +26,11 @@ for i=0:length(measurements) % IMU velocity and bias priors if options.includeIMUFactors == 1 currentVelKey = symbol('v', 0); - currentVel = values.at(currentVelKey).vector; + currentVel = values.atPoint3(currentVelKey); graph.add(PriorFactorLieVector(currentVelKey, LieVector(currentVel), noiseModels.noiseVel)); currentBiasKey = symbol('b', 0); - currentBias = values.at(currentBiasKey); + currentBias = values.atPoint3(currentBiasKey); graph.add(PriorFactorConstantBias(currentBiasKey, currentBias, noiseModels.noisePriorBias)); end @@ -155,7 +155,7 @@ for i=0:length(measurements) if options.includeCameraFactors == 1 for j = 1:length(measurements(i).landmarks) cameraMeasurmentNoise = measurementNoise.cameraNoiseVector .* randn(2,1); - cameraPixelMeasurement = measurements(i).landmarks(j).vector; + cameraPixelMeasurement = measurements(i).landmarks(j); % Only add the measurement if it is in the image frame (based on calibration) if(cameraPixelMeasurement(1) > 0 && cameraPixelMeasurement(2) > 0 ... && cameraPixelMeasurement(1) < 2*metadata.camera.calibration.px ... diff --git a/matlab/unstable_examples/+imuSimulator/covarianceAnalysisCreateTrajectory.m b/matlab/unstable_examples/+imuSimulator/covarianceAnalysisCreateTrajectory.m index 195b7ff69..3d8a9b5d2 100644 --- a/matlab/unstable_examples/+imuSimulator/covarianceAnalysisCreateTrajectory.m +++ b/matlab/unstable_examples/+imuSimulator/covarianceAnalysisCreateTrajectory.m @@ -40,7 +40,7 @@ if options.useRealData == 1 %% gt Between measurements if options.includeBetweenFactors == 1 && i > 0 - prevPose = values.at(currentPoseKey - 1); + prevPose = values.atPose3(currentPoseKey - 1); deltaPose = prevPose.between(currentPose); measurements(i).deltaVector = Pose3.Logmap(deltaPose); end @@ -65,7 +65,7 @@ if options.useRealData == 1 IMUdeltaPose = IMUPose1.between(IMUPose2); IMUdeltaPoseVector = Pose3.Logmap(IMUdeltaPose); IMUdeltaRotVector = IMUdeltaPoseVector(1:3); - IMUdeltaPositionVector = IMUPose2.translation.vector - IMUPose1.translation.vector; % translation in absolute frame + IMUdeltaPositionVector = IMUPose2.translation - IMUPose1.translation; % translation in absolute frame measurements(i).imu(j).deltaT = deltaT; @@ -88,7 +88,7 @@ if options.useRealData == 1 %% gt GPS measurements if options.includeGPSFactors == 1 && i > 0 - gpsPositionVector = imuSimulator.getPoseFromGtScenario(gtScenario,scenarioInd).translation.vector; + gpsPositionVector = imuSimulator.getPoseFromGtScenario(gtScenario,scenarioInd).translation; measurements(i).gpsPositionVector = gpsPositionVector; end diff --git a/matlab/unstable_examples/+imuSimulator/integrateIMUTrajectory.m b/matlab/unstable_examples/+imuSimulator/integrateIMUTrajectory.m index 3f72f1215..2de1e1103 100644 --- a/matlab/unstable_examples/+imuSimulator/integrateIMUTrajectory.m +++ b/matlab/unstable_examples/+imuSimulator/integrateIMUTrajectory.m @@ -5,9 +5,9 @@ function [ finalPose, finalVelocityGlobal ] = integrateIMUTrajectory( ... import gtsam.*; imu2in1 = Rot3.Expmap(acc_omegaIMU(4:6) * deltaT); -accelGlobal = initialPoseGlobal.rotation().rotate(Point3(acc_omegaIMU(1:3))).vector; +accelGlobal = initialPoseGlobal.rotation().rotate(Point3(acc_omegaIMU(1:3))); -finalPosition = Point3(initialPoseGlobal.translation.vector ... +finalPosition = Point3(initialPoseGlobal.translation ... + initialVelocityGlobal * deltaT + 0.5 * accelGlobal * deltaT * deltaT); finalVelocityGlobal = initialVelocityGlobal + accelGlobal * deltaT; finalRotation = initialPoseGlobal.rotation.compose(imu2in1); diff --git a/matlab/unstable_examples/+imuSimulator/integrateIMUTrajectory_bodyFrame.m b/matlab/unstable_examples/+imuSimulator/integrateIMUTrajectory_bodyFrame.m index 50b223060..bec2d760d 100644 --- a/matlab/unstable_examples/+imuSimulator/integrateIMUTrajectory_bodyFrame.m +++ b/matlab/unstable_examples/+imuSimulator/integrateIMUTrajectory_bodyFrame.m @@ -3,7 +3,7 @@ function [ finalPose, finalVelocityGlobal ] = integrateIMUTrajectory_bodyFrame( % Before integrating in the body frame we need to compensate for the Coriolis % effect -acc_body = acc_omegaIMU(1:3) - Point3(cross(acc_omegaIMU(4:6), velocity1Body)).vector; +acc_body = acc_omegaIMU(1:3) - Point3(cross(acc_omegaIMU(4:6), velocity1Body)); % after compensating for coriolis this will be essentially zero % since we are moving at constant body velocity @@ -16,8 +16,8 @@ finalPositionBody = velocity1Body * deltaT + 0.5 * acc_body * deltaT * deltaT; finalVelocityBody = velocity1Body + acc_body * deltaT; %% Express the integrated quantities in the global frame -finalVelocityGlobal = initialVelocityGlobal + (initialPoseGlobal.rotation().rotate(Point3(finalVelocityBody)).vector() ); -finalPosition = initialPoseGlobal.translation().vector() + initialPoseGlobal.rotation().rotate( Point3(finalPositionBody)).vector() ; +finalVelocityGlobal = initialVelocityGlobal + (initialPoseGlobal.rotation().rotate(Point3(finalVelocityBody)) ); +finalPosition = initialPoseGlobal.translation() + initialPoseGlobal.rotation().rotate( Point3(finalPositionBody)) ; finalRotation = initialPoseGlobal.rotation.compose(imu2in1); % Include position and rotation in a pose finalPose = Pose3(finalRotation, Point3(finalPosition) ); diff --git a/matlab/unstable_examples/+imuSimulator/integrateIMUTrajectory_navFrame.m b/matlab/unstable_examples/+imuSimulator/integrateIMUTrajectory_navFrame.m index b919520ac..ea851315f 100644 --- a/matlab/unstable_examples/+imuSimulator/integrateIMUTrajectory_navFrame.m +++ b/matlab/unstable_examples/+imuSimulator/integrateIMUTrajectory_navFrame.m @@ -9,8 +9,8 @@ finalRotation = initialPoseGlobal.rotation.compose(imu2in1); intermediateRotation = initialPoseGlobal.rotation.compose( Rot3.Expmap(acc_omegaIMU(4:6) * deltaT/2 )); % Integrate positions (equation (1) in Lupton) -accelGlobal = intermediateRotation.rotate(Point3(acc_omegaIMU(1:3))).vector; -finalPosition = Point3(initialPoseGlobal.translation.vector ... +accelGlobal = intermediateRotation.rotate(Point3(acc_omegaIMU(1:3))); +finalPosition = Point3(initialPoseGlobal.translation ... + initialVelocityGlobal * deltaT + 0.5 * accelGlobal * deltaT * deltaT); finalVelocityGlobal = initialVelocityGlobal + accelGlobal * deltaT; diff --git a/matlab/unstable_examples/+imuSimulator/integrateTrajectory.m b/matlab/unstable_examples/+imuSimulator/integrateTrajectory.m index e51b622b0..a704342ae 100644 --- a/matlab/unstable_examples/+imuSimulator/integrateTrajectory.m +++ b/matlab/unstable_examples/+imuSimulator/integrateTrajectory.m @@ -6,16 +6,16 @@ import gtsam.*; % Rotation: R^1_2 body2in1 = Rot3.Expmap(omega1Body * deltaT); % Velocity 2 in frame 1: v^1_2 = R^1_2 v^2_2 -velocity2inertial = body2in1.rotate(Point3(velocity2Body)).vector; +velocity2inertial = body2in1.rotate(Point3(velocity2Body)); % Acceleration: a^1 = (v^1_2 - v^1_1)/dt accelBody1 = (velocity2inertial - velocity1Body) / deltaT; % Velocity 1 in frame W: v^W_1 = R^W_1 v^1_1 -initialVelocityGlobal = initialPose.rotation().rotate(Point3(velocity1Body)).vector; +initialVelocityGlobal = initialPose.rotation().rotate(Point3(velocity1Body)); % Acceleration in frame W: a^W = R^W_1 a^1 -accelGlobal = initialPose.rotation().rotate(Point3(accelBody1)).vector; +accelGlobal = initialPose.rotation().rotate(Point3(accelBody1)); -finalPosition = Point3(initialPose.translation.vector + initialVelocityGlobal * deltaT + 0.5 * accelGlobal * deltaT * deltaT); +finalPosition = Point3(initialPose.translation + initialVelocityGlobal * deltaT + 0.5 * accelGlobal * deltaT * deltaT); finalVelocityGlobal = initialVelocityGlobal + accelGlobal * deltaT; finalRotation = initialPose.rotation.compose(body2in1); finalPose = Pose3(finalRotation, finalPosition); diff --git a/matlab/unstable_examples/+imuSimulator/test1onestep.m b/matlab/unstable_examples/+imuSimulator/test1onestep.m index 883569849..cb66d23d6 100644 --- a/matlab/unstable_examples/+imuSimulator/test1onestep.m +++ b/matlab/unstable_examples/+imuSimulator/test1onestep.m @@ -10,7 +10,7 @@ omega = [0;0;0.1]; velocity = [1;0;0]; R = Rot3.Expmap(omega * deltaT); -velocity2body = R.unrotate(Point3(velocity)).vector; +velocity2body = R.unrotate(Point3(velocity)); acc_omegaExpected = [-0.01; 0; 0; 0; 0; 0.1]; acc_omegaActual = imuSimulator.calculateIMUMeasurement(omega, omega, velocity, velocity2body, deltaT, Pose3(Rot3, Point3([1;0;0]))); disp('IMU measurement discrepancy:'); @@ -40,7 +40,7 @@ disp(acc_omegaActual - acc_omegaExpected); initialPose = Pose3; initialVelocity = velocity; finalPoseExpected = Pose3.Expmap([ omega; velocity ] * deltaT); -finalVelocityExpected = finalPoseExpected.rotation.rotate(Point3(velocity)).vector; +finalVelocityExpected = finalPoseExpected.rotation.rotate(Point3(velocity)); [ finalPoseActual, finalVelocityActual ] = imuSimulator.integrateTrajectory(initialPose, omega, velocity, velocity, deltaT); disp('Final pose discrepancy:'); disp(finalPoseExpected.between(finalPoseActual).matrix); diff --git a/matlab/unstable_examples/+imuSimulator/test2constglobal.m b/matlab/unstable_examples/+imuSimulator/test2constglobal.m index 19956d08a..6ab35d50b 100644 --- a/matlab/unstable_examples/+imuSimulator/test2constglobal.m +++ b/matlab/unstable_examples/+imuSimulator/test2constglobal.m @@ -21,12 +21,12 @@ positions = zeros(3, length(times)+1); i = 2; for t = times - velocity1body = currentPoseGlobal.rotation.unrotate(Point3(currentVelocityGlobal)).vector; + velocity1body = currentPoseGlobal.rotation.unrotate(Point3(currentVelocityGlobal)); R = Rot3.Expmap(omega * deltaT); - velocity2body = currentPoseGlobal.rotation.compose(R).unrotate(Point3(currentVelocityGlobal)).vector; + velocity2body = currentPoseGlobal.rotation.compose(R).unrotate(Point3(currentVelocityGlobal)); [ currentPoseGlobal, currentVelocityGlobal ] = imuSimulator.integrateTrajectory(currentPoseGlobal, omega, velocity1body, velocity2body, deltaT); - positions(:,i) = currentPoseGlobal.translation.vector; + positions(:,i) = currentPoseGlobal.translation; i = i + 1; end diff --git a/matlab/unstable_examples/+imuSimulator/test3constbody.m b/matlab/unstable_examples/+imuSimulator/test3constbody.m index b3ee2edfc..8ee14ab78 100644 --- a/matlab/unstable_examples/+imuSimulator/test3constbody.m +++ b/matlab/unstable_examples/+imuSimulator/test3constbody.m @@ -26,27 +26,27 @@ currentPoseGlobal = Pose3; currentVelocityGlobal = velocity; % Initial state (IMU) currentPoseGlobalIMU = Pose3; %currentPoseGlobal.compose(IMUinBody); -%currentVelocityGlobalIMU = IMUinBody.rotation.unrotate(Point3(velocity)).vector; % no Coriolis here? +%currentVelocityGlobalIMU = IMUinBody.rotation.unrotate(Point3(velocity)); % no Coriolis here? currentVelocityGlobalIMU = IMUinBody.rotation.unrotate( ... - Point3(velocity + cross(omega, IMUinBody.translation.vector))).vector; + Point3(velocity + cross(omega, IMUinBody.translation))); % Positions % body trajectory positions = zeros(3, length(times)+1); -positions(:,1) = currentPoseGlobal.translation.vector; +positions(:,1) = currentPoseGlobal.translation; poses(1).p = positions(:,1); poses(1).R = currentPoseGlobal.rotation.matrix; % Expected IMU trajectory (from body trajectory and lever arm) positionsIMUe = zeros(3, length(times)+1); -positionsIMUe(:,1) = IMUinBody.compose(currentPoseGlobalIMU).translation.vector; +positionsIMUe(:,1) = IMUinBody.compose(currentPoseGlobalIMU).translation; posesIMUe(1).p = positionsIMUe(:,1); posesIMUe(1).R = poses(1).R * IMUinBody.rotation.matrix; % Integrated IMU trajectory (from IMU measurements) positionsIMU = zeros(3, length(times)+1); -positionsIMU(:,1) = IMUinBody.compose(currentPoseGlobalIMU).translation.vector; +positionsIMU(:,1) = IMUinBody.compose(currentPoseGlobalIMU).translation; posesIMU(1).p = positionsIMU(:,1); posesIMU(1).R = IMUinBody.compose(currentPoseGlobalIMU).rotation.matrix; @@ -62,9 +62,9 @@ for t = times currentPoseGlobalIMU, currentVelocityGlobalIMU, acc_omega, deltaT); % Store data in some structure for statistics and plots - positions(:,i) = currentPoseGlobal.translation.vector; - positionsIMUe(:,i) = currentPoseGlobal.translation.vector + currentPoseGlobal.rotation.matrix * IMUinBody.translation.vector; - positionsIMU(:,i) = IMUinBody.compose(currentPoseGlobalIMU).translation.vector; + positions(:,i) = currentPoseGlobal.translation; + positionsIMUe(:,i) = currentPoseGlobal.translation + currentPoseGlobal.rotation.matrix * IMUinBody.translation; + positionsIMU(:,i) = IMUinBody.compose(currentPoseGlobalIMU).translation; poses(i).p = positions(:,i); posesIMUe(i).p = positionsIMUe(:,i); diff --git a/matlab/unstable_examples/+imuSimulator/test4circle.m b/matlab/unstable_examples/+imuSimulator/test4circle.m index 22ee175dd..ab2c546db 100644 --- a/matlab/unstable_examples/+imuSimulator/test4circle.m +++ b/matlab/unstable_examples/+imuSimulator/test4circle.m @@ -34,19 +34,19 @@ currentVelocityGlobalIMUbody = currentVelocityGlobal; %% Prepare data structures for actual trajectory and estimates % Actual trajectory positions = zeros(3, length(times)+1); -positions(:,1) = currentPoseGlobal.translation.vector; +positions(:,1) = currentPoseGlobal.translation; poses(1).p = positions(:,1); poses(1).R = currentPoseGlobal.rotation.matrix; % Trajectory estimate (integrated in the navigation frame) positionsIMUnav = zeros(3, length(times)+1); -positionsIMUnav(:,1) = currentPoseGlobalIMUbody.translation.vector; +positionsIMUnav(:,1) = currentPoseGlobalIMUbody.translation; posesIMUnav(1).p = positionsIMUnav(:,1); posesIMUnav(1).R = poses(1).R; % Trajectory estimate (integrated in the body frame) positionsIMUbody = zeros(3, length(times)+1); -positionsIMUbody(:,1) = currentPoseGlobalIMUbody.translation.vector; +positionsIMUbody(:,1) = currentPoseGlobalIMUbody.translation; posesIMUbody(1).p = positionsIMUbody(:,1); posesIMUbody(1).R = poses(1).R; @@ -72,9 +72,9 @@ for t = times currentPoseGlobalIMUnav, currentVelocityGlobalIMUnav, acc_omega, deltaT); %% Store data in some structure for statistics and plots - positions(:,i) = currentPoseGlobal.translation.vector; - positionsIMUbody(:,i) = currentPoseGlobalIMUbody.translation.vector; - positionsIMUnav(:,i) = currentPoseGlobalIMUnav.translation.vector; + positions(:,i) = currentPoseGlobal.translation; + positionsIMUbody(:,i) = currentPoseGlobalIMUbody.translation; + positionsIMUnav(:,i) = currentPoseGlobalIMUnav.translation; % - poses(i).p = positions(:,i); posesIMUbody(i).p = positionsIMUbody(:,i); diff --git a/matlab/unstable_examples/FlightCameraTransformIMU.m b/matlab/unstable_examples/FlightCameraTransformIMU.m index 9a8a27344..d2f2bc34d 100644 --- a/matlab/unstable_examples/FlightCameraTransformIMU.m +++ b/matlab/unstable_examples/FlightCameraTransformIMU.m @@ -120,7 +120,7 @@ for i=1:size(trajectory)-1 end % current ground-truth position indicator - h_cursor = plot3(a1, pose_t.x,pose_t.y,pose_t.z,'*'); + h_cursor = plot3(a1, pose_t(1),pose_t(2),pose_t(3),'*'); camera_pose = pose.compose(camera_transform); @@ -198,7 +198,7 @@ for i=1:size(trajectory)-1 if ~result.exists(lKey) p = landmarks.atPoint3(lKey); n = normrnd(0,landmark_noise,3,1); - noisy_landmark = Point3(p.x()+n(1),p.y()+n(2),p.z()+n(3)); + noisy_landmark = p + n; initial.insert(lKey, noisy_landmark); % and add a prior since its position is known @@ -245,32 +245,33 @@ for i=1:size(trajectory)-1 initial = Values; fg = NonlinearFactorGraph; - currentVelocityGlobal = result.at(currentVelKey); - currentBias = result.at(currentBiasKey); + currentVelocityGlobal = result.atPoint3(currentVelKey); + currentBias = result.atConstantBias(currentBiasKey); %% plot current pose result - isam_pose = result.at(xKey); + isam_pose = result.atPose3(xKey); pose_t = isam_pose.translation(); if exist('h_result','var') delete(h_result); end - h_result = plot3(a1, pose_t.x,pose_t.y,pose_t.z,'^b', 'MarkerSize', 10); + h_result = plot3(a1, pose_t(1),pose_t(2),pose_t(3),'^b', 'MarkerSize', 10); title(a1, sprintf('Step %d', i)); if exist('h_text1(1)', 'var') delete(h_text1(1)); % delete(h_text2(1)); end - ty = result.at(transformKey).translation().y(); - K_estimate = result.at(calibrationKey); + t = result.atPose3(transformKey).translation(); + ty = t(2); + K_estimate = result.atCal3_S2(calibrationKey); K_errors = K.localCoordinates(K_estimate); - camera_transform_estimate = result.at(transformKey); + camera_transform_estimate = result.atPose3(transformKey); - fx = result.at(calibrationKey).fx(); - fy = result.at(calibrationKey).fy(); + fx = result.atCal3_S2(calibrationKey).fx(); + fy = result.atCal3_S2(calibrationKey).fy(); % h_text1 = text(-600,0,0,sprintf('Y-Transform(0.0): %0.2f',ty)); text(0,1300,0,sprintf('Calibration and IMU-cam transform errors:')); @@ -304,7 +305,7 @@ for i=1:size(trajectory)-1 end %% print out final camera transform and write video -result.at(transformKey); +result.atPose3(transformKey); if(write_video) close(videoObj); end \ No newline at end of file diff --git a/matlab/unstable_examples/TransformCalProjectionFactorIMUExampleISAM.m b/matlab/unstable_examples/TransformCalProjectionFactorIMUExampleISAM.m index 4557d711f..9796a9737 100644 --- a/matlab/unstable_examples/TransformCalProjectionFactorIMUExampleISAM.m +++ b/matlab/unstable_examples/TransformCalProjectionFactorIMUExampleISAM.m @@ -53,7 +53,7 @@ y_shift = Point3(0,0.5,0); % insert shifted points for i=1:nrPoints - initial.insert(100+i,landmarks{i}.compose(y_shift)); + initial.insert(100+i,landmarks{i} + y_shift); end figure(1); @@ -134,7 +134,7 @@ for i=1:steps end if i == 2 fg.add(PriorFactorPose3(2, Pose3(Rot3(),Point3(1,0,0)),pose_cov)); - fg.add(PriorFactorLieVector(currentVelKey, currentVelocityGlobal, sigma_init_v)); + fg.add(PriorFactorVector(currentVelKey, currentVelocityGlobal, sigma_init_v)); fg.add(PriorFactorConstantBias(currentBiasKey, currentBias, sigma_init_b)); end if i > 1 @@ -144,7 +144,7 @@ for i=1:steps step = move_circle; end - initial.insert(i,result.at(i-1).compose(step)); + initial.insert(i,result.atPose3(i-1).compose(step)); fg.add(BetweenFactorPose3(i-1,i, step, covariance)); deltaT = 1; @@ -158,10 +158,13 @@ for i=1:steps [ currentIMUPoseGlobal, currentVelocityGlobal ] = imuSimulator.integrateTrajectory( ... currentIMUPoseGlobal, omega, velocity, velocity, deltaT); - - currentSummarizedMeasurement = gtsam.ImuFactorPreintegratedMeasurements( ... - currentBias, IMU_metadata.AccelerometerSigma.^2 * eye(3), ... - IMU_metadata.GyroscopeSigma.^2 * eye(3), IMU_metadata.IntegrationSigma.^2 * eye(3)); + + params = gtsam.PreintegrationParams.MakeSharedD(9.81); + params.setAccelerometerCovariance(IMU_metadata.AccelerometerSigma.^2 * eye(3)); + params.setGyroscopeCovariance(IMU_metadata.GyroscopeSigma.^2 * eye(3)); + params.setIntegrationCovariance(IMU_metadata.IntegrationSigma.^2 * eye(3)); + currentSummarizedMeasurement = gtsam.PreintegratedImuMeasurements( ... + params, currentBias); accMeas = acc_omega(1:3)-g; omegaMeas = acc_omega(4:6); @@ -171,7 +174,7 @@ for i=1:steps fg.add(ImuFactor( ... i-1, currentVelKey-1, ... i, currentVelKey, ... - currentBiasKey, currentSummarizedMeasurement, g, w_coriolis)); + currentBiasKey, currentSummarizedMeasurement)); % Bias evolution as given in the IMU metadata fg.add(BetweenFactorConstantBias(currentBiasKey-1, currentBiasKey, imuBias.ConstantBias(zeros(3,1), zeros(3,1)), ... @@ -204,8 +207,8 @@ for i=1:steps initial = Values; fg = NonlinearFactorGraph; - currentVelocityGlobal = isam.calculateEstimate(currentVelKey); - currentBias = isam.calculateEstimate(currentBiasKey); + currentVelocityGlobal = isam.calculateEstimate().atVector(currentVelKey); + currentBias = isam.calculateEstimate().atConstantBias(currentBiasKey); %% Compute some marginals marginal = isam.marginalCovariance(calibrationKey); @@ -249,10 +252,10 @@ for i=1:steps gtsam.plotPose3(currentIMUPoseGlobal, [], 2); %% plot results - result_camera_transform = result.at(transformKey); + result_camera_transform = result.atPose3(transformKey); for j=1:i - gtsam.plotPose3(result.at(j),[],0.5); - gtsam.plotPose3(result.at(j).compose(result_camera_transform),[],0.5); + gtsam.plotPose3(result.atPose3(j),[],0.5); + gtsam.plotPose3(result.atPose3(j).compose(result_camera_transform),[],0.5); end xlabel('x (m)'); @@ -265,14 +268,15 @@ for i=1:steps % axis equal for l=101:100+nrPoints - plotPoint3(result.at(l),'g'); + plotPoint3(result.atPoint3(l),'g'); end - ty = result.at(transformKey).translation().y(); - fx = result.at(calibrationKey).fx(); - fy = result.at(calibrationKey).fy(); - px = result.at(calibrationKey).px(); - py = result.at(calibrationKey).py(); + t = result.atPose3(transformKey).translation(); + ty = t(2); + fx = result.atCal3_S2(calibrationKey).fx(); + fy = result.atCal3_S2(calibrationKey).fy(); + px = result.atCal3_S2(calibrationKey).px(); + py = result.atCal3_S2(calibrationKey).py(); text(1,5,5,sprintf('Y-Transform(0.0): %0.2f',ty)); text(1,5,3,sprintf('fx(900): %.0f',fx)); text(1,5,1,sprintf('fy(900): %.0f',fy)); @@ -342,10 +346,10 @@ end fprintf('Cheirality Exception count: %d\n', cheirality_exception_count); disp('Transform after optimization'); -result.at(transformKey) +result.atPose3(transformKey) disp('Calibration after optimization'); -result.at(calibrationKey) +result.atCal3_S2(calibrationKey) disp('Bias after optimization'); currentBias diff --git a/matlab/unstable_examples/plot_projected_landmarks.m b/matlab/unstable_examples/plot_projected_landmarks.m index 6b8101844..30e222016 100644 --- a/matlab/unstable_examples/plot_projected_landmarks.m +++ b/matlab/unstable_examples/plot_projected_landmarks.m @@ -25,9 +25,9 @@ for i = 0:measurement_keys.size-1 key_index = gtsam.symbolIndex(key); p = landmarks.atPoint3(gtsam.symbol('l',key_index)); - x(i+1) = p.x; - y(i+1) = p.y; - z(i+1) = p.z; + x(i+1) = p(1); + y(i+1) = p(2); + z(i+1) = p(3); end diff --git a/matlab/unstable_examples/project_landmarks.m b/matlab/unstable_examples/project_landmarks.m index aaccc9248..3bccef94b 100644 --- a/matlab/unstable_examples/project_landmarks.m +++ b/matlab/unstable_examples/project_landmarks.m @@ -11,9 +11,9 @@ function [ measurements ] = project_landmarks( pose, landmarks, K ) z = camera.project(landmarks.atPoint3(symbol('l',i))); % check bounding box - if z.x < 0 || z.x > 1280 + if z(1) < 0 || z(1) > 1280 continue - elseif z.y < 0 || z.y > 960 + elseif z(2) < 0 || z(2) > 960 continue end From b0d100b8fb735f09c994305c64961850725d86f6 Mon Sep 17 00:00:00 2001 From: Fan Jiang Date: Mon, 17 Aug 2020 14:38:00 -0400 Subject: [PATCH 389/869] Python supplementary files --- python/CMakeLists.txt | 104 +++++++++++++++++++++++ python/README.md | 87 +++++++++++++++++++ python/gtsam/gtsam.tpl | 30 +++++++ python/gtsam/preamble.h | 4 + python/gtsam/specializations.h | 4 + python/gtsam_unstable/gtsam_unstable.tpl | 32 +++++++ python/gtsam_unstable/preamble.h | 0 python/gtsam_unstable/specializations.h | 0 python/requirements.txt | 2 + python/setup.py.in | 49 +++++++++++ 10 files changed, 312 insertions(+) create mode 100644 python/CMakeLists.txt create mode 100644 python/README.md create mode 100644 python/gtsam/gtsam.tpl create mode 100644 python/gtsam/preamble.h create mode 100644 python/gtsam/specializations.h create mode 100644 python/gtsam_unstable/gtsam_unstable.tpl create mode 100644 python/gtsam_unstable/preamble.h create mode 100644 python/gtsam_unstable/specializations.h create mode 100644 python/requirements.txt create mode 100644 python/setup.py.in diff --git a/python/CMakeLists.txt b/python/CMakeLists.txt new file mode 100644 index 000000000..81a6c6c4d --- /dev/null +++ b/python/CMakeLists.txt @@ -0,0 +1,104 @@ +set(GTSAM_PYTHON_BUILD_DIRECTORY ${PROJECT_BINARY_DIR}/python) + +if(GTSAM_BUILD_PYTHON) + # Generate setup.py. + file(READ "${PROJECT_SOURCE_DIR}/README.md" README_CONTENTS) + configure_file(${PROJECT_SOURCE_DIR}/python/setup.py.in + ${GTSAM_PYTHON_BUILD_DIRECTORY}/setup.py) + + set(WRAP_USE_CUSTOM_PYTHON_LIBRARY ${GTSAM_USE_CUSTOM_PYTHON_LIBRARY}) + set(WRAP_PYTHON_VERSION ${GTSAM_PYTHON_VERSION}) + + include(PybindWrap) + + add_custom_target(gtsam_header DEPENDS "${PROJECT_SOURCE_DIR}/gtsam/gtsam.i") + add_custom_target(gtsam_unstable_header DEPENDS "${PROJECT_SOURCE_DIR}/gtsam_unstable/gtsam_unstable.i") + + # ignoring the non-concrete types (type aliases) + set(ignore + gtsam::Point2 + gtsam::Point3 + gtsam::LieVector + gtsam::LieMatrix + gtsam::ISAM2ThresholdMapValue + gtsam::FactorIndices + gtsam::FactorIndexSet + gtsam::BetweenFactorPose3s + gtsam::Point2Vector + gtsam::Pose3Vector + gtsam::KeyVector) + + pybind_wrap(gtsam_py # target + ${PROJECT_SOURCE_DIR}/gtsam/gtsam.i # interface_header + "gtsam.cpp" # generated_cpp + "gtsam" # module_name + "gtsam" # top_namespace + "${ignore}" # ignore_classes + ${PROJECT_SOURCE_DIR}/python/gtsam/gtsam.tpl + gtsam # libs + "gtsam;gtsam_header" # dependencies + ON # use_boost + ) + + set_target_properties(gtsam_py PROPERTIES + INSTALL_RPATH "${CMAKE_INSTALL_PREFIX}/lib" + INSTALL_RPATH_USE_LINK_PATH TRUE + OUTPUT_NAME "gtsam" + LIBRARY_OUTPUT_DIRECTORY "${GTSAM_PYTHON_BUILD_DIRECTORY}/gtsam" + DEBUG_POSTFIX "" # Otherwise you will have a wrong name + RELWITHDEBINFO_POSTFIX "" # Otherwise you will have a wrong name + ) + + set(GTSAM_MODULE_PATH ${GTSAM_PYTHON_BUILD_DIRECTORY}/gtsam) + + # Symlink all tests .py files to build folder. + create_symlinks("${CMAKE_CURRENT_SOURCE_DIR}/gtsam" + "${GTSAM_MODULE_PATH}") + + if(GTSAM_UNSTABLE_BUILD_PYTHON) + set(ignore + gtsam::Point2 + gtsam::Point3 + gtsam::LieVector + gtsam::LieMatrix + gtsam::ISAM2ThresholdMapValue + gtsam::FactorIndices + gtsam::FactorIndexSet + gtsam::BetweenFactorPose3s + gtsam::Point2Vector + gtsam::Pose3Vector + gtsam::KeyVector + gtsam::FixedLagSmootherKeyTimestampMapValue) + pybind_wrap(gtsam_unstable_py # target + ${PROJECT_SOURCE_DIR}/gtsam_unstable/gtsam_unstable.i # interface_header + "gtsam_unstable.cpp" # generated_cpp + "gtsam_unstable" # module_name + "gtsam" # top_namespace + "${ignore}" # ignore_classes + ${PROJECT_SOURCE_DIR}/python/gtsam_unstable/gtsam_unstable.tpl + gtsam_unstable # libs + "gtsam_unstable;gtsam_unstable_header" # dependencies + ON # use_boost + ) + + set_target_properties(gtsam_unstable_py PROPERTIES + INSTALL_RPATH "${CMAKE_INSTALL_PREFIX}/lib" + INSTALL_RPATH_USE_LINK_PATH TRUE + OUTPUT_NAME "gtsam_unstable" + LIBRARY_OUTPUT_DIRECTORY "${GTSAM_PYTHON_BUILD_DIRECTORY}/gtsam_unstable" + DEBUG_POSTFIX "" # Otherwise you will have a wrong name + RELWITHDEBINFO_POSTFIX "" # Otherwise you will have a wrong name + ) + + set(GTSAM_UNSTABLE_MODULE_PATH ${GTSAM_PYTHON_BUILD_DIRECTORY}/gtsam_unstable) + + # Symlink all tests .py files to build folder. + create_symlinks("${CMAKE_CURRENT_SOURCE_DIR}/gtsam_unstable" + "${GTSAM_UNSTABLE_MODULE_PATH}") + endif() + + set(GTSAM_PYTHON_INSTALL_TARGET python-install) + add_custom_target(${GTSAM_PYTHON_INSTALL_TARGET} + COMMAND ${PYTHON_EXECUTABLE} ${GTSAM_PYTHON_BUILD_DIRECTORY}/setup.py install + WORKING_DIRECTORY ${GTSAM_PYTHON_BUILD_DIRECTORY}) +endif() diff --git a/python/README.md b/python/README.md new file mode 100644 index 000000000..e418cbede --- /dev/null +++ b/python/README.md @@ -0,0 +1,87 @@ +# README + +# Python Wrapper + +This is the Python wrapper around the GTSAM C++ library. We use Cython to generate the bindings to the underlying C++ code. + +## Requirements + +- If you want to build the GTSAM python library for a specific python version (eg 3.6), + use the `-DGTSAM_PYTHON_VERSION=3.6` option when running `cmake` otherwise the default interpreter will be used. +- If the interpreter is inside an environment (such as an anaconda environment or virtualenv environment), + then the environment should be active while building GTSAM. +- This wrapper needs `Cython(>=0.25.2)`, `backports_abc(>=0.5)`, and `numpy(>=1.11.0)`. These can be installed as follows: + + ```bash + pip install -r /cython/requirements.txt + ``` + +- For compatibility with GTSAM's Eigen version, it contains its own cloned version of [Eigency](https://github.com/wouterboomsma/eigency.git), + named `gtsam_eigency`, to interface between C++'s Eigen and Python's numpy. + +## Install + +- Run cmake with the `GTSAM_INSTALL_CYTHON_TOOLBOX` cmake flag enabled to configure building the wrapper. The wrapped module will be built and copied to the directory defined by `GTSAM_CYTHON_INSTALL_PATH`, which is by default `/cython` in Release mode and `/cython` for other modes. + +- Build GTSAM and the wrapper with `make`. + +- To install, simply run `make python-install`. + - The same command can be used to install into a virtual environment if it is active. + - **NOTE**: if you don't want GTSAM to install to a system directory such as `/usr/local`, pass `-DCMAKE_INSTALL_PREFIX="./install"` to cmake to install GTSAM to a subdirectory of the build directory. + +- You can also directly run `make python-install` without running `make`, and it will compile all the dependencies accordingly. + +## Unit Tests + +The Cython toolbox also has a small set of unit tests located in the +test directory. To run them: + + ```bash + cd + python -m unittest discover + ``` + +## Utils + +TODO + +## Examples + +TODO + +## Writing Your Own Scripts + +See the tests for examples. + +### Some Important Notes: + +- Vector/Matrix: + + - GTSAM expects double-precision floating point vectors and matrices. + Hence, you should pass numpy matrices with `dtype=float`, or `float64`. + - Also, GTSAM expects _column-major_ matrices, unlike the default storage + scheme in numpy. Hence, you should pass column-major matrices to GTSAM using + the flag order='F'. And you always get column-major matrices back. + For more details, see [this link](https://github.com/wouterboomsma/eigency#storage-layout---why-arrays-are-sometimes-transposed). + - Passing row-major matrices of different dtype, e.g. `int`, will also work + as the wrapper converts them to column-major and dtype float for you, + using numpy.array.astype(float, order='F', copy=False). + However, this will result a copy if your matrix is not in the expected type + and storage order. + +- Inner namespace: Classes in inner namespace will be prefixed by \_ in Python. + + Examples: `noiseModel_Gaussian`, `noiseModel_mEstimator_Tukey` + +- Casting from a base class to a derive class must be done explicitly. + + Examples: + + ```python + noiseBase = factor.noiseModel() + noiseGaussian = dynamic_cast_noiseModel_Gaussian_noiseModel_Base(noiseBase) + ``` + +## Wrapping Custom GTSAM-based Project + +Please refer to the template project and the corresponding tutorial available [here](https://github.com/borglab/GTSAM-project-python). diff --git a/python/gtsam/gtsam.tpl b/python/gtsam/gtsam.tpl new file mode 100644 index 000000000..de3efbee0 --- /dev/null +++ b/python/gtsam/gtsam.tpl @@ -0,0 +1,30 @@ +{include_boost} + +#include +#include +#include +#include "gtsam/base/serialization.h" +#include "gtsam/nonlinear/utilities.h" // for RedirectCout. + +{includes} +#include + +{boost_class_export} + +{hoder_type} + +#include "python/gtsam/preamble.h" + +using namespace std; + +namespace py = pybind11; + +PYBIND11_MODULE({module_name}, m_) {{ + m_.doc() = "pybind11 wrapper of {module_name}"; + +{wrapped_namespace} + +#include "python/gtsam/specializations.h" + +}} + diff --git a/python/gtsam/preamble.h b/python/gtsam/preamble.h new file mode 100644 index 000000000..f8e5804d0 --- /dev/null +++ b/python/gtsam/preamble.h @@ -0,0 +1,4 @@ +PYBIND11_MAKE_OPAQUE(std::vector); +PYBIND11_MAKE_OPAQUE(std::vector >); +PYBIND11_MAKE_OPAQUE(std::vector); +PYBIND11_MAKE_OPAQUE(std::vector>); diff --git a/python/gtsam/specializations.h b/python/gtsam/specializations.h new file mode 100644 index 000000000..c1114059b --- /dev/null +++ b/python/gtsam/specializations.h @@ -0,0 +1,4 @@ +py::bind_vector >(m_, "KeyVector"); +py::bind_vector > >(m_, "Point2Vector"); +py::bind_vector >(m_, "Pose3Vector"); +py::bind_vector > > >(m_, "BetweenFactorPose3s"); \ No newline at end of file diff --git a/python/gtsam_unstable/gtsam_unstable.tpl b/python/gtsam_unstable/gtsam_unstable.tpl new file mode 100644 index 000000000..f8d2f231e --- /dev/null +++ b/python/gtsam_unstable/gtsam_unstable.tpl @@ -0,0 +1,32 @@ +{include_boost} + +#include +#include +#include +#include "gtsam/base/serialization.h" +#include "gtsam/nonlinear/utilities.h" // for RedirectCout. + +{includes} +#include + +{boost_class_export} + +{hoder_type} + +#include "python/gtsam_unstable/preamble.h" + +using namespace std; + +namespace py = pybind11; + +PYBIND11_MODULE({module_name}, m_) {{ + m_.doc() = "pybind11 wrapper of {module_name}"; + + py::module::import("gtsam"); + +{wrapped_namespace} + +#include "python/gtsam_unstable/specializations.h" + +}} + diff --git a/python/gtsam_unstable/preamble.h b/python/gtsam_unstable/preamble.h new file mode 100644 index 000000000..e69de29bb diff --git a/python/gtsam_unstable/specializations.h b/python/gtsam_unstable/specializations.h new file mode 100644 index 000000000..e69de29bb diff --git a/python/requirements.txt b/python/requirements.txt new file mode 100644 index 000000000..481d27d8e --- /dev/null +++ b/python/requirements.txt @@ -0,0 +1,2 @@ +numpy>=1.11.0 +pyparsing>=2.4.2 diff --git a/python/setup.py.in b/python/setup.py.in new file mode 100644 index 000000000..55431a9ad --- /dev/null +++ b/python/setup.py.in @@ -0,0 +1,49 @@ +import os +import sys + +try: + from setuptools import setup, find_packages +except ImportError: + from distutils.core import setup, find_packages + +packages = find_packages(where=".") +print("PACKAGES: ", packages) +package_data = { + '': [ + './*.so', + './*.dll', + ] +} + +# Cleaner to read in the contents rather than copy them over. +readme_contents = open("${PROJECT_SOURCE_DIR}/README.md").read() + +setup( + name='gtsam', + description='Georgia Tech Smoothing And Mapping library', + url='https://gtsam.org/', + version='${GTSAM_VERSION_STRING}', # https://www.python.org/dev/peps/pep-0440/ + author='Frank Dellaert et. al.', + author_email='frank.dellaert@gtsam.org', + license='Simplified BSD license', + keywords='slam sam robotics localization mapping optimization', + long_description=readme_contents, + # https://pypi.org/pypi?%3Aaction=list_classifiers + classifiers=[ + 'Development Status :: 5 - Production/Stable', + 'Intended Audience :: Education', + 'Intended Audience :: Developers', + 'Intended Audience :: Science/Research', + 'Operating System :: MacOS', + 'Operating System :: Microsoft :: Windows', + 'Operating System :: POSIX', + 'License :: OSI Approved :: BSD License', + 'Programming Language :: Python :: 2', + 'Programming Language :: Python :: 3', + ], + packages=packages, + package_data=package_data, + test_suite="gtsam.tests", + install_requires=["numpy"], + zip_safe=False, +) From c7eb02969abc42696db93efc37988519d5a7f7a0 Mon Sep 17 00:00:00 2001 From: Fan Jiang Date: Mon, 17 Aug 2020 14:44:14 -0400 Subject: [PATCH 390/869] Remove old wrap --- wrap/Argument.cpp | 316 --- wrap/Argument.h | 242 -- wrap/CMakeLists.txt | 45 - wrap/Class.cpp | 897 ------- wrap/Class.h | 315 --- wrap/Constructor.cpp | 160 -- wrap/Constructor.h | 99 - wrap/Deconstructor.cpp | 73 - wrap/Deconstructor.h | 61 - wrap/FileWriter.cpp | 52 - wrap/FileWriter.h | 35 - wrap/ForwardDeclaration.h | 36 - wrap/FullyOverloadedFunction.cpp | 34 - wrap/FullyOverloadedFunction.h | 147 -- wrap/Function.cpp | 78 - wrap/Function.h | 73 - wrap/GlobalFunction.cpp | 227 -- wrap/GlobalFunction.h | 148 -- wrap/Method.cpp | 205 -- wrap/Method.h | 74 - wrap/MethodBase.cpp | 135 - wrap/MethodBase.h | 70 - wrap/Module.cpp | 649 ----- wrap/Module.h | 95 - wrap/OverloadedFunction.h | 140 -- wrap/Qualified.cpp | 5 - wrap/Qualified.h | 370 --- wrap/README.md | 27 - wrap/ReturnType.cpp | 101 - wrap/ReturnType.h | 89 - wrap/ReturnValue.cpp | 102 - wrap/ReturnValue.h | 126 - wrap/StaticMethod.cpp | 151 -- wrap/StaticMethod.h | 51 - wrap/Template.h | 146 -- wrap/TemplateInstantiationTypedef.cpp | 69 - wrap/TemplateInstantiationTypedef.h | 36 - wrap/TemplateMethod.cpp | 53 - wrap/TemplateMethod.h | 42 - wrap/TemplateSubstitution.h | 76 - wrap/TypeAttributesTable.cpp | 93 - wrap/TypeAttributesTable.h | 71 - wrap/TypedefPair.h | 28 - wrap/matlab.h | 443 ---- wrap/python/pybind11/.appveyor.yml | 70 - wrap/python/pybind11/.gitignore | 38 - wrap/python/pybind11/.gitmodules | 3 - wrap/python/pybind11/.readthedocs.yml | 3 - wrap/python/pybind11/.travis.yml | 280 --- wrap/python/pybind11/CMakeLists.txt | 157 -- wrap/python/pybind11/CONTRIBUTING.md | 49 - wrap/python/pybind11/ISSUE_TEMPLATE.md | 17 - wrap/python/pybind11/LICENSE | 29 - wrap/python/pybind11/MANIFEST.in | 2 - wrap/python/pybind11/README.md | 129 - wrap/python/pybind11/docs/Doxyfile | 20 - .../pybind11/docs/_static/theme_overrides.css | 11 - .../pybind11/docs/advanced/cast/chrono.rst | 81 - .../pybind11/docs/advanced/cast/custom.rst | 91 - .../pybind11/docs/advanced/cast/eigen.rst | 310 --- .../docs/advanced/cast/functional.rst | 109 - .../pybind11/docs/advanced/cast/index.rst | 42 - .../pybind11/docs/advanced/cast/overview.rst | 165 -- .../pybind11/docs/advanced/cast/stl.rst | 240 -- .../pybind11/docs/advanced/cast/strings.rst | 305 --- .../python/pybind11/docs/advanced/classes.rst | 1125 --------- .../pybind11/docs/advanced/embedding.rst | 261 -- .../pybind11/docs/advanced/exceptions.rst | 142 -- .../pybind11/docs/advanced/functions.rst | 507 ---- wrap/python/pybind11/docs/advanced/misc.rst | 306 --- .../pybind11/docs/advanced/pycpp/index.rst | 13 - .../pybind11/docs/advanced/pycpp/numpy.rst | 386 --- .../pybind11/docs/advanced/pycpp/object.rst | 170 -- .../docs/advanced/pycpp/utilities.rst | 144 -- .../pybind11/docs/advanced/smart_ptrs.rst | 173 -- wrap/python/pybind11/docs/basics.rst | 293 --- wrap/python/pybind11/docs/benchmark.py | 88 - wrap/python/pybind11/docs/benchmark.rst | 97 - wrap/python/pybind11/docs/changelog.rst | 1158 --------- wrap/python/pybind11/docs/classes.rst | 521 ---- wrap/python/pybind11/docs/compiling.rst | 289 --- wrap/python/pybind11/docs/conf.py | 332 --- wrap/python/pybind11/docs/faq.rst | 297 --- wrap/python/pybind11/docs/index.rst | 47 - wrap/python/pybind11/docs/intro.rst | 93 - wrap/python/pybind11/docs/limitations.rst | 20 - wrap/python/pybind11/docs/pybind11-logo.png | Bin 58510 -> 0 bytes .../docs/pybind11_vs_boost_python1.png | Bin 44653 -> 0 bytes .../docs/pybind11_vs_boost_python1.svg | 427 ---- .../docs/pybind11_vs_boost_python2.png | Bin 41121 -> 0 bytes .../docs/pybind11_vs_boost_python2.svg | 427 ---- wrap/python/pybind11/docs/reference.rst | 117 - wrap/python/pybind11/docs/release.rst | 25 - wrap/python/pybind11/docs/requirements.txt | 1 - wrap/python/pybind11/docs/upgrade.rst | 404 --- wrap/python/pybind11/include/pybind11/attr.h | 493 ---- .../pybind11/include/pybind11/buffer_info.h | 108 - wrap/python/pybind11/include/pybind11/cast.h | 2128 ---------------- .../python/pybind11/include/pybind11/chrono.h | 162 -- .../python/pybind11/include/pybind11/common.h | 2 - .../pybind11/include/pybind11/complex.h | 65 - .../pybind11/include/pybind11/detail/class.h | 623 ----- .../pybind11/include/pybind11/detail/common.h | 807 ------ .../pybind11/include/pybind11/detail/descr.h | 100 - .../pybind11/include/pybind11/detail/init.h | 335 --- .../include/pybind11/detail/internals.h | 291 --- .../pybind11/include/pybind11/detail/typeid.h | 55 - wrap/python/pybind11/include/pybind11/eigen.h | 607 ----- wrap/python/pybind11/include/pybind11/embed.h | 200 -- wrap/python/pybind11/include/pybind11/eval.h | 117 - .../pybind11/include/pybind11/functional.h | 94 - .../pybind11/include/pybind11/iostream.h | 207 -- wrap/python/pybind11/include/pybind11/numpy.h | 1610 ------------ .../pybind11/include/pybind11/operators.h | 168 -- .../pybind11/include/pybind11/options.h | 65 - .../pybind11/include/pybind11/pybind11.h | 2162 ----------------- .../pybind11/include/pybind11/pytypes.h | 1471 ----------- wrap/python/pybind11/include/pybind11/stl.h | 386 --- .../pybind11/include/pybind11/stl_bind.h | 630 ----- wrap/python/pybind11/pybind11/__init__.py | 28 - wrap/python/pybind11/pybind11/__main__.py | 37 - wrap/python/pybind11/pybind11/_version.py | 2 - wrap/python/pybind11/setup.cfg | 12 - wrap/python/pybind11/setup.py | 108 - wrap/python/pybind11/tests/CMakeLists.txt | 239 -- wrap/python/pybind11/tests/conftest.py | 239 -- .../python/pybind11/tests/constructor_stats.h | 276 --- wrap/python/pybind11/tests/local_bindings.h | 64 - wrap/python/pybind11/tests/object.h | 175 -- .../tests/pybind11_cross_module_tests.cpp | 123 - wrap/python/pybind11/tests/pybind11_tests.cpp | 93 - wrap/python/pybind11/tests/pybind11_tests.h | 65 - wrap/python/pybind11/tests/pytest.ini | 16 - wrap/python/pybind11/tests/test_buffers.cpp | 169 -- wrap/python/pybind11/tests/test_buffers.py | 87 - .../pybind11/tests/test_builtin_casters.cpp | 170 -- .../pybind11/tests/test_builtin_casters.py | 342 --- .../pybind11/tests/test_call_policies.cpp | 100 - .../pybind11/tests/test_call_policies.py | 187 -- wrap/python/pybind11/tests/test_callbacks.cpp | 168 -- wrap/python/pybind11/tests/test_callbacks.py | 136 -- wrap/python/pybind11/tests/test_chrono.cpp | 55 - wrap/python/pybind11/tests/test_chrono.py | 107 - wrap/python/pybind11/tests/test_class.cpp | 422 ---- wrap/python/pybind11/tests/test_class.py | 281 --- .../tests/test_cmake_build/CMakeLists.txt | 58 - .../pybind11/tests/test_cmake_build/embed.cpp | 21 - .../installed_embed/CMakeLists.txt | 15 - .../installed_function/CMakeLists.txt | 12 - .../installed_target/CMakeLists.txt | 22 - .../pybind11/tests/test_cmake_build/main.cpp | 6 - .../subdirectory_embed/CMakeLists.txt | 25 - .../subdirectory_function/CMakeLists.txt | 8 - .../subdirectory_target/CMakeLists.txt | 15 - .../pybind11/tests/test_cmake_build/test.py | 5 - .../tests/test_constants_and_functions.cpp | 127 - .../tests/test_constants_and_functions.py | 39 - wrap/python/pybind11/tests/test_copy_move.cpp | 213 -- wrap/python/pybind11/tests/test_copy_move.py | 112 - .../pybind11/tests/test_docstring_options.cpp | 61 - .../pybind11/tests/test_docstring_options.py | 38 - wrap/python/pybind11/tests/test_eigen.cpp | 329 --- wrap/python/pybind11/tests/test_eigen.py | 694 ------ .../pybind11/tests/test_embed/CMakeLists.txt | 41 - .../pybind11/tests/test_embed/catch.cpp | 22 - .../tests/test_embed/external_module.cpp | 23 - .../tests/test_embed/test_interpreter.cpp | 284 --- .../tests/test_embed/test_interpreter.py | 9 - wrap/python/pybind11/tests/test_enum.cpp | 85 - wrap/python/pybind11/tests/test_enum.py | 167 -- wrap/python/pybind11/tests/test_eval.cpp | 91 - wrap/python/pybind11/tests/test_eval.py | 17 - wrap/python/pybind11/tests/test_eval_call.py | 4 - .../python/pybind11/tests/test_exceptions.cpp | 196 -- wrap/python/pybind11/tests/test_exceptions.py | 146 -- .../tests/test_factory_constructors.cpp | 338 --- .../tests/test_factory_constructors.py | 459 ---- .../python/pybind11/tests/test_gil_scoped.cpp | 44 - wrap/python/pybind11/tests/test_gil_scoped.py | 80 - wrap/python/pybind11/tests/test_iostream.cpp | 73 - wrap/python/pybind11/tests/test_iostream.py | 214 -- .../tests/test_kwargs_and_defaults.cpp | 102 - .../tests/test_kwargs_and_defaults.py | 147 -- .../pybind11/tests/test_local_bindings.cpp | 101 - .../pybind11/tests/test_local_bindings.py | 226 -- .../tests/test_methods_and_attributes.cpp | 454 ---- .../tests/test_methods_and_attributes.py | 512 ---- wrap/python/pybind11/tests/test_modules.cpp | 98 - wrap/python/pybind11/tests/test_modules.py | 72 - .../tests/test_multiple_inheritance.cpp | 220 -- .../tests/test_multiple_inheritance.py | 349 --- .../pybind11/tests/test_numpy_array.cpp | 309 --- .../python/pybind11/tests/test_numpy_array.py | 421 ---- .../pybind11/tests/test_numpy_dtypes.cpp | 466 ---- .../pybind11/tests/test_numpy_dtypes.py | 310 --- .../pybind11/tests/test_numpy_vectorize.cpp | 89 - .../pybind11/tests/test_numpy_vectorize.py | 196 -- .../pybind11/tests/test_opaque_types.cpp | 67 - .../pybind11/tests/test_opaque_types.py | 46 - .../tests/test_operator_overloading.cpp | 169 -- .../tests/test_operator_overloading.py | 106 - wrap/python/pybind11/tests/test_pickling.cpp | 130 - wrap/python/pybind11/tests/test_pickling.py | 42 - wrap/python/pybind11/tests/test_pytypes.cpp | 296 --- wrap/python/pybind11/tests/test_pytypes.py | 253 -- .../tests/test_sequences_and_iterators.cpp | 353 --- .../tests/test_sequences_and_iterators.py | 171 -- wrap/python/pybind11/tests/test_smart_ptr.cpp | 366 --- wrap/python/pybind11/tests/test_smart_ptr.py | 285 --- wrap/python/pybind11/tests/test_stl.cpp | 284 --- wrap/python/pybind11/tests/test_stl.py | 241 -- .../pybind11/tests/test_stl_binders.cpp | 107 - .../python/pybind11/tests/test_stl_binders.py | 225 -- .../tests/test_tagbased_polymorphic.cpp | 136 -- .../tests/test_tagbased_polymorphic.py | 20 - wrap/python/pybind11/tests/test_union.cpp | 22 - wrap/python/pybind11/tests/test_union.py | 8 - .../pybind11/tests/test_virtual_functions.cpp | 479 ---- .../pybind11/tests/test_virtual_functions.py | 377 --- wrap/python/pybind11/tools/FindCatch.cmake | 57 - wrap/python/pybind11/tools/FindEigen3.cmake | 81 - .../pybind11/tools/FindPythonLibsNew.cmake | 202 -- wrap/python/pybind11/tools/check-style.sh | 70 - wrap/python/pybind11/tools/libsize.py | 38 - wrap/python/pybind11/tools/mkdoc.py | 379 --- .../pybind11/tools/pybind11Config.cmake.in | 104 - .../python/pybind11/tools/pybind11Tools.cmake | 227 -- wrap/spirit.h | 172 -- wrap/tests/CMakeLists.txt | 1 - wrap/tests/expected-cython/geometry.pxd | 153 -- wrap/tests/expected-cython/geometry.pyx | 483 ---- .../tests/expected-python/geometry_python.cpp | 96 - wrap/tests/expected/+gtsam/Point2.m | 101 - wrap/tests/expected/+gtsam/Point3.m | 93 - wrap/tests/expected/.gitignore | 1 - wrap/tests/expected/MyBase.m | 35 - wrap/tests/expected/MyFactorPosePoint2.m | 36 - wrap/tests/expected/MyTemplateMatrix.m | 156 -- wrap/tests/expected/MyTemplatePoint2.m | 156 -- wrap/tests/expected/MyVector12.m | 36 - wrap/tests/expected/MyVector3.m | 36 - wrap/tests/expected/Point2.m | 90 - wrap/tests/expected/Point3.m | 107 - wrap/tests/expected/Test.m | 218 -- wrap/tests/expected/aGlobalFunction.m | 6 - wrap/tests/expected/geometry_wrapper.cpp | 1264 ---------- .../tests/expected/overloadedGlobalFunction.m | 8 - wrap/tests/expected2/+gtsam/Point2.m | 101 - wrap/tests/expected2/+gtsam/Point3.m | 61 - wrap/tests/expected2/MyBase.m | 35 - wrap/tests/expected2/MyFactorPosePoint2.m | 36 - wrap/tests/expected2/MyTemplateMatrix.m | 156 -- wrap/tests/expected2/MyTemplatePoint2.m | 156 -- wrap/tests/expected2/MyVector12.m | 36 - wrap/tests/expected2/MyVector3.m | 36 - wrap/tests/expected2/Test.m | 218 -- wrap/tests/expected2/aGlobalFunction.m | 6 - wrap/tests/expected2/geometry_wrapper.cpp | 1230 ---------- .../expected2/overloadedGlobalFunction.m | 8 - wrap/tests/expected_namespaces/+ns1/ClassA.m | 36 - wrap/tests/expected_namespaces/+ns1/ClassB.m | 36 - .../+ns1/aGlobalFunction.m | 6 - .../expected_namespaces/+ns2/+ns3/ClassB.m | 36 - wrap/tests/expected_namespaces/+ns2/ClassA.m | 72 - wrap/tests/expected_namespaces/+ns2/ClassC.m | 36 - .../+ns2/aGlobalFunction.m | 6 - .../+ns2/overloadedGlobalFunction.m | 8 - wrap/tests/expected_namespaces/ClassD.m | 36 - .../testNamespaces_wrapper.cpp | 448 ---- wrap/tests/geometry.h | 140 -- wrap/tests/testArgument.cpp | 131 - wrap/tests/testClass.cpp | 285 --- wrap/tests/testDependencies.h | 8 - wrap/tests/testGlobalFunction.cpp | 55 - wrap/tests/testMemory.m | 7 - wrap/tests/testMethod.cpp | 63 - wrap/tests/testNamespaces.h | 60 - wrap/tests/testReturnValue.cpp | 119 - wrap/tests/testSpirit.cpp | 151 -- wrap/tests/testTemplate.cpp | 78 - wrap/tests/testType.cpp | 137 -- wrap/tests/testWrap.cpp | 505 ---- wrap/utilities.cpp | 148 -- wrap/utilities.h | 136 -- wrap/wrap.cpp | 89 - 285 files changed, 54751 deletions(-) delete mode 100644 wrap/Argument.cpp delete mode 100644 wrap/Argument.h delete mode 100644 wrap/CMakeLists.txt delete mode 100644 wrap/Class.cpp delete mode 100644 wrap/Class.h delete mode 100644 wrap/Constructor.cpp delete mode 100644 wrap/Constructor.h delete mode 100644 wrap/Deconstructor.cpp delete mode 100644 wrap/Deconstructor.h delete mode 100644 wrap/FileWriter.cpp delete mode 100644 wrap/FileWriter.h delete mode 100644 wrap/ForwardDeclaration.h delete mode 100644 wrap/FullyOverloadedFunction.cpp delete mode 100644 wrap/FullyOverloadedFunction.h delete mode 100644 wrap/Function.cpp delete mode 100644 wrap/Function.h delete mode 100644 wrap/GlobalFunction.cpp delete mode 100644 wrap/GlobalFunction.h delete mode 100644 wrap/Method.cpp delete mode 100644 wrap/Method.h delete mode 100644 wrap/MethodBase.cpp delete mode 100644 wrap/MethodBase.h delete mode 100644 wrap/Module.cpp delete mode 100644 wrap/Module.h delete mode 100644 wrap/OverloadedFunction.h delete mode 100644 wrap/Qualified.cpp delete mode 100644 wrap/Qualified.h delete mode 100644 wrap/README.md delete mode 100644 wrap/ReturnType.cpp delete mode 100644 wrap/ReturnType.h delete mode 100644 wrap/ReturnValue.cpp delete mode 100644 wrap/ReturnValue.h delete mode 100644 wrap/StaticMethod.cpp delete mode 100644 wrap/StaticMethod.h delete mode 100644 wrap/Template.h delete mode 100644 wrap/TemplateInstantiationTypedef.cpp delete mode 100644 wrap/TemplateInstantiationTypedef.h delete mode 100644 wrap/TemplateMethod.cpp delete mode 100644 wrap/TemplateMethod.h delete mode 100644 wrap/TemplateSubstitution.h delete mode 100644 wrap/TypeAttributesTable.cpp delete mode 100644 wrap/TypeAttributesTable.h delete mode 100644 wrap/TypedefPair.h delete mode 100644 wrap/matlab.h delete mode 100644 wrap/python/pybind11/.appveyor.yml delete mode 100644 wrap/python/pybind11/.gitignore delete mode 100644 wrap/python/pybind11/.gitmodules delete mode 100644 wrap/python/pybind11/.readthedocs.yml delete mode 100644 wrap/python/pybind11/.travis.yml delete mode 100644 wrap/python/pybind11/CMakeLists.txt delete mode 100644 wrap/python/pybind11/CONTRIBUTING.md delete mode 100644 wrap/python/pybind11/ISSUE_TEMPLATE.md delete mode 100644 wrap/python/pybind11/LICENSE delete mode 100644 wrap/python/pybind11/MANIFEST.in delete mode 100644 wrap/python/pybind11/README.md delete mode 100644 wrap/python/pybind11/docs/Doxyfile delete mode 100644 wrap/python/pybind11/docs/_static/theme_overrides.css delete mode 100644 wrap/python/pybind11/docs/advanced/cast/chrono.rst delete mode 100644 wrap/python/pybind11/docs/advanced/cast/custom.rst delete mode 100644 wrap/python/pybind11/docs/advanced/cast/eigen.rst delete mode 100644 wrap/python/pybind11/docs/advanced/cast/functional.rst delete mode 100644 wrap/python/pybind11/docs/advanced/cast/index.rst delete mode 100644 wrap/python/pybind11/docs/advanced/cast/overview.rst delete mode 100644 wrap/python/pybind11/docs/advanced/cast/stl.rst delete mode 100644 wrap/python/pybind11/docs/advanced/cast/strings.rst delete mode 100644 wrap/python/pybind11/docs/advanced/classes.rst delete mode 100644 wrap/python/pybind11/docs/advanced/embedding.rst delete mode 100644 wrap/python/pybind11/docs/advanced/exceptions.rst delete mode 100644 wrap/python/pybind11/docs/advanced/functions.rst delete mode 100644 wrap/python/pybind11/docs/advanced/misc.rst delete mode 100644 wrap/python/pybind11/docs/advanced/pycpp/index.rst delete mode 100644 wrap/python/pybind11/docs/advanced/pycpp/numpy.rst delete mode 100644 wrap/python/pybind11/docs/advanced/pycpp/object.rst delete mode 100644 wrap/python/pybind11/docs/advanced/pycpp/utilities.rst delete mode 100644 wrap/python/pybind11/docs/advanced/smart_ptrs.rst delete mode 100644 wrap/python/pybind11/docs/basics.rst delete mode 100644 wrap/python/pybind11/docs/benchmark.py delete mode 100644 wrap/python/pybind11/docs/benchmark.rst delete mode 100644 wrap/python/pybind11/docs/changelog.rst delete mode 100644 wrap/python/pybind11/docs/classes.rst delete mode 100644 wrap/python/pybind11/docs/compiling.rst delete mode 100644 wrap/python/pybind11/docs/conf.py delete mode 100644 wrap/python/pybind11/docs/faq.rst delete mode 100644 wrap/python/pybind11/docs/index.rst delete mode 100644 wrap/python/pybind11/docs/intro.rst delete mode 100644 wrap/python/pybind11/docs/limitations.rst delete mode 100644 wrap/python/pybind11/docs/pybind11-logo.png delete mode 100644 wrap/python/pybind11/docs/pybind11_vs_boost_python1.png delete mode 100644 wrap/python/pybind11/docs/pybind11_vs_boost_python1.svg delete mode 100644 wrap/python/pybind11/docs/pybind11_vs_boost_python2.png delete mode 100644 wrap/python/pybind11/docs/pybind11_vs_boost_python2.svg delete mode 100644 wrap/python/pybind11/docs/reference.rst delete mode 100644 wrap/python/pybind11/docs/release.rst delete mode 100644 wrap/python/pybind11/docs/requirements.txt delete mode 100644 wrap/python/pybind11/docs/upgrade.rst delete mode 100644 wrap/python/pybind11/include/pybind11/attr.h delete mode 100644 wrap/python/pybind11/include/pybind11/buffer_info.h delete mode 100644 wrap/python/pybind11/include/pybind11/cast.h delete mode 100644 wrap/python/pybind11/include/pybind11/chrono.h delete mode 100644 wrap/python/pybind11/include/pybind11/common.h delete mode 100644 wrap/python/pybind11/include/pybind11/complex.h delete mode 100644 wrap/python/pybind11/include/pybind11/detail/class.h delete mode 100644 wrap/python/pybind11/include/pybind11/detail/common.h delete mode 100644 wrap/python/pybind11/include/pybind11/detail/descr.h delete mode 100644 wrap/python/pybind11/include/pybind11/detail/init.h delete mode 100644 wrap/python/pybind11/include/pybind11/detail/internals.h delete mode 100644 wrap/python/pybind11/include/pybind11/detail/typeid.h delete mode 100644 wrap/python/pybind11/include/pybind11/eigen.h delete mode 100644 wrap/python/pybind11/include/pybind11/embed.h delete mode 100644 wrap/python/pybind11/include/pybind11/eval.h delete mode 100644 wrap/python/pybind11/include/pybind11/functional.h delete mode 100644 wrap/python/pybind11/include/pybind11/iostream.h delete mode 100644 wrap/python/pybind11/include/pybind11/numpy.h delete mode 100644 wrap/python/pybind11/include/pybind11/operators.h delete mode 100644 wrap/python/pybind11/include/pybind11/options.h delete mode 100644 wrap/python/pybind11/include/pybind11/pybind11.h delete mode 100644 wrap/python/pybind11/include/pybind11/pytypes.h delete mode 100644 wrap/python/pybind11/include/pybind11/stl.h delete mode 100644 wrap/python/pybind11/include/pybind11/stl_bind.h delete mode 100644 wrap/python/pybind11/pybind11/__init__.py delete mode 100644 wrap/python/pybind11/pybind11/__main__.py delete mode 100644 wrap/python/pybind11/pybind11/_version.py delete mode 100644 wrap/python/pybind11/setup.cfg delete mode 100644 wrap/python/pybind11/setup.py delete mode 100644 wrap/python/pybind11/tests/CMakeLists.txt delete mode 100644 wrap/python/pybind11/tests/conftest.py delete mode 100644 wrap/python/pybind11/tests/constructor_stats.h delete mode 100644 wrap/python/pybind11/tests/local_bindings.h delete mode 100644 wrap/python/pybind11/tests/object.h delete mode 100644 wrap/python/pybind11/tests/pybind11_cross_module_tests.cpp delete mode 100644 wrap/python/pybind11/tests/pybind11_tests.cpp delete mode 100644 wrap/python/pybind11/tests/pybind11_tests.h delete mode 100644 wrap/python/pybind11/tests/pytest.ini delete mode 100644 wrap/python/pybind11/tests/test_buffers.cpp delete mode 100644 wrap/python/pybind11/tests/test_buffers.py delete mode 100644 wrap/python/pybind11/tests/test_builtin_casters.cpp delete mode 100644 wrap/python/pybind11/tests/test_builtin_casters.py delete mode 100644 wrap/python/pybind11/tests/test_call_policies.cpp delete mode 100644 wrap/python/pybind11/tests/test_call_policies.py delete mode 100644 wrap/python/pybind11/tests/test_callbacks.cpp delete mode 100644 wrap/python/pybind11/tests/test_callbacks.py delete mode 100644 wrap/python/pybind11/tests/test_chrono.cpp delete mode 100644 wrap/python/pybind11/tests/test_chrono.py delete mode 100644 wrap/python/pybind11/tests/test_class.cpp delete mode 100644 wrap/python/pybind11/tests/test_class.py delete mode 100644 wrap/python/pybind11/tests/test_cmake_build/CMakeLists.txt delete mode 100644 wrap/python/pybind11/tests/test_cmake_build/embed.cpp delete mode 100644 wrap/python/pybind11/tests/test_cmake_build/installed_embed/CMakeLists.txt delete mode 100644 wrap/python/pybind11/tests/test_cmake_build/installed_function/CMakeLists.txt delete mode 100644 wrap/python/pybind11/tests/test_cmake_build/installed_target/CMakeLists.txt delete mode 100644 wrap/python/pybind11/tests/test_cmake_build/main.cpp delete mode 100644 wrap/python/pybind11/tests/test_cmake_build/subdirectory_embed/CMakeLists.txt delete mode 100644 wrap/python/pybind11/tests/test_cmake_build/subdirectory_function/CMakeLists.txt delete mode 100644 wrap/python/pybind11/tests/test_cmake_build/subdirectory_target/CMakeLists.txt delete mode 100644 wrap/python/pybind11/tests/test_cmake_build/test.py delete mode 100644 wrap/python/pybind11/tests/test_constants_and_functions.cpp delete mode 100644 wrap/python/pybind11/tests/test_constants_and_functions.py delete mode 100644 wrap/python/pybind11/tests/test_copy_move.cpp delete mode 100644 wrap/python/pybind11/tests/test_copy_move.py delete mode 100644 wrap/python/pybind11/tests/test_docstring_options.cpp delete mode 100644 wrap/python/pybind11/tests/test_docstring_options.py delete mode 100644 wrap/python/pybind11/tests/test_eigen.cpp delete mode 100644 wrap/python/pybind11/tests/test_eigen.py delete mode 100644 wrap/python/pybind11/tests/test_embed/CMakeLists.txt delete mode 100644 wrap/python/pybind11/tests/test_embed/catch.cpp delete mode 100644 wrap/python/pybind11/tests/test_embed/external_module.cpp delete mode 100644 wrap/python/pybind11/tests/test_embed/test_interpreter.cpp delete mode 100644 wrap/python/pybind11/tests/test_embed/test_interpreter.py delete mode 100644 wrap/python/pybind11/tests/test_enum.cpp delete mode 100644 wrap/python/pybind11/tests/test_enum.py delete mode 100644 wrap/python/pybind11/tests/test_eval.cpp delete mode 100644 wrap/python/pybind11/tests/test_eval.py delete mode 100644 wrap/python/pybind11/tests/test_eval_call.py delete mode 100644 wrap/python/pybind11/tests/test_exceptions.cpp delete mode 100644 wrap/python/pybind11/tests/test_exceptions.py delete mode 100644 wrap/python/pybind11/tests/test_factory_constructors.cpp delete mode 100644 wrap/python/pybind11/tests/test_factory_constructors.py delete mode 100644 wrap/python/pybind11/tests/test_gil_scoped.cpp delete mode 100644 wrap/python/pybind11/tests/test_gil_scoped.py delete mode 100644 wrap/python/pybind11/tests/test_iostream.cpp delete mode 100644 wrap/python/pybind11/tests/test_iostream.py delete mode 100644 wrap/python/pybind11/tests/test_kwargs_and_defaults.cpp delete mode 100644 wrap/python/pybind11/tests/test_kwargs_and_defaults.py delete mode 100644 wrap/python/pybind11/tests/test_local_bindings.cpp delete mode 100644 wrap/python/pybind11/tests/test_local_bindings.py delete mode 100644 wrap/python/pybind11/tests/test_methods_and_attributes.cpp delete mode 100644 wrap/python/pybind11/tests/test_methods_and_attributes.py delete mode 100644 wrap/python/pybind11/tests/test_modules.cpp delete mode 100644 wrap/python/pybind11/tests/test_modules.py delete mode 100644 wrap/python/pybind11/tests/test_multiple_inheritance.cpp delete mode 100644 wrap/python/pybind11/tests/test_multiple_inheritance.py delete mode 100644 wrap/python/pybind11/tests/test_numpy_array.cpp delete mode 100644 wrap/python/pybind11/tests/test_numpy_array.py delete mode 100644 wrap/python/pybind11/tests/test_numpy_dtypes.cpp delete mode 100644 wrap/python/pybind11/tests/test_numpy_dtypes.py delete mode 100644 wrap/python/pybind11/tests/test_numpy_vectorize.cpp delete mode 100644 wrap/python/pybind11/tests/test_numpy_vectorize.py delete mode 100644 wrap/python/pybind11/tests/test_opaque_types.cpp delete mode 100644 wrap/python/pybind11/tests/test_opaque_types.py delete mode 100644 wrap/python/pybind11/tests/test_operator_overloading.cpp delete mode 100644 wrap/python/pybind11/tests/test_operator_overloading.py delete mode 100644 wrap/python/pybind11/tests/test_pickling.cpp delete mode 100644 wrap/python/pybind11/tests/test_pickling.py delete mode 100644 wrap/python/pybind11/tests/test_pytypes.cpp delete mode 100644 wrap/python/pybind11/tests/test_pytypes.py delete mode 100644 wrap/python/pybind11/tests/test_sequences_and_iterators.cpp delete mode 100644 wrap/python/pybind11/tests/test_sequences_and_iterators.py delete mode 100644 wrap/python/pybind11/tests/test_smart_ptr.cpp delete mode 100644 wrap/python/pybind11/tests/test_smart_ptr.py delete mode 100644 wrap/python/pybind11/tests/test_stl.cpp delete mode 100644 wrap/python/pybind11/tests/test_stl.py delete mode 100644 wrap/python/pybind11/tests/test_stl_binders.cpp delete mode 100644 wrap/python/pybind11/tests/test_stl_binders.py delete mode 100644 wrap/python/pybind11/tests/test_tagbased_polymorphic.cpp delete mode 100644 wrap/python/pybind11/tests/test_tagbased_polymorphic.py delete mode 100644 wrap/python/pybind11/tests/test_union.cpp delete mode 100644 wrap/python/pybind11/tests/test_union.py delete mode 100644 wrap/python/pybind11/tests/test_virtual_functions.cpp delete mode 100644 wrap/python/pybind11/tests/test_virtual_functions.py delete mode 100644 wrap/python/pybind11/tools/FindCatch.cmake delete mode 100644 wrap/python/pybind11/tools/FindEigen3.cmake delete mode 100644 wrap/python/pybind11/tools/FindPythonLibsNew.cmake delete mode 100755 wrap/python/pybind11/tools/check-style.sh delete mode 100644 wrap/python/pybind11/tools/libsize.py delete mode 100755 wrap/python/pybind11/tools/mkdoc.py delete mode 100644 wrap/python/pybind11/tools/pybind11Config.cmake.in delete mode 100644 wrap/python/pybind11/tools/pybind11Tools.cmake delete mode 100644 wrap/spirit.h delete mode 100644 wrap/tests/CMakeLists.txt delete mode 100644 wrap/tests/expected-cython/geometry.pxd delete mode 100644 wrap/tests/expected-cython/geometry.pyx delete mode 100644 wrap/tests/expected-python/geometry_python.cpp delete mode 100644 wrap/tests/expected/+gtsam/Point2.m delete mode 100644 wrap/tests/expected/+gtsam/Point3.m delete mode 100644 wrap/tests/expected/.gitignore delete mode 100644 wrap/tests/expected/MyBase.m delete mode 100644 wrap/tests/expected/MyFactorPosePoint2.m delete mode 100644 wrap/tests/expected/MyTemplateMatrix.m delete mode 100644 wrap/tests/expected/MyTemplatePoint2.m delete mode 100644 wrap/tests/expected/MyVector12.m delete mode 100644 wrap/tests/expected/MyVector3.m delete mode 100644 wrap/tests/expected/Point2.m delete mode 100644 wrap/tests/expected/Point3.m delete mode 100644 wrap/tests/expected/Test.m delete mode 100644 wrap/tests/expected/aGlobalFunction.m delete mode 100644 wrap/tests/expected/geometry_wrapper.cpp delete mode 100644 wrap/tests/expected/overloadedGlobalFunction.m delete mode 100644 wrap/tests/expected2/+gtsam/Point2.m delete mode 100644 wrap/tests/expected2/+gtsam/Point3.m delete mode 100644 wrap/tests/expected2/MyBase.m delete mode 100644 wrap/tests/expected2/MyFactorPosePoint2.m delete mode 100644 wrap/tests/expected2/MyTemplateMatrix.m delete mode 100644 wrap/tests/expected2/MyTemplatePoint2.m delete mode 100644 wrap/tests/expected2/MyVector12.m delete mode 100644 wrap/tests/expected2/MyVector3.m delete mode 100644 wrap/tests/expected2/Test.m delete mode 100644 wrap/tests/expected2/aGlobalFunction.m delete mode 100644 wrap/tests/expected2/geometry_wrapper.cpp delete mode 100644 wrap/tests/expected2/overloadedGlobalFunction.m delete mode 100644 wrap/tests/expected_namespaces/+ns1/ClassA.m delete mode 100644 wrap/tests/expected_namespaces/+ns1/ClassB.m delete mode 100644 wrap/tests/expected_namespaces/+ns1/aGlobalFunction.m delete mode 100644 wrap/tests/expected_namespaces/+ns2/+ns3/ClassB.m delete mode 100644 wrap/tests/expected_namespaces/+ns2/ClassA.m delete mode 100644 wrap/tests/expected_namespaces/+ns2/ClassC.m delete mode 100644 wrap/tests/expected_namespaces/+ns2/aGlobalFunction.m delete mode 100644 wrap/tests/expected_namespaces/+ns2/overloadedGlobalFunction.m delete mode 100644 wrap/tests/expected_namespaces/ClassD.m delete mode 100644 wrap/tests/expected_namespaces/testNamespaces_wrapper.cpp delete mode 100644 wrap/tests/geometry.h delete mode 100644 wrap/tests/testArgument.cpp delete mode 100644 wrap/tests/testClass.cpp delete mode 100644 wrap/tests/testDependencies.h delete mode 100644 wrap/tests/testGlobalFunction.cpp delete mode 100644 wrap/tests/testMemory.m delete mode 100644 wrap/tests/testMethod.cpp delete mode 100644 wrap/tests/testNamespaces.h delete mode 100644 wrap/tests/testReturnValue.cpp delete mode 100644 wrap/tests/testSpirit.cpp delete mode 100644 wrap/tests/testTemplate.cpp delete mode 100644 wrap/tests/testType.cpp delete mode 100644 wrap/tests/testWrap.cpp delete mode 100644 wrap/utilities.cpp delete mode 100644 wrap/utilities.h delete mode 100644 wrap/wrap.cpp diff --git a/wrap/Argument.cpp b/wrap/Argument.cpp deleted file mode 100644 index f85aed72e..000000000 --- a/wrap/Argument.cpp +++ /dev/null @@ -1,316 +0,0 @@ -/* ---------------------------------------------------------------------------- - - * GTSAM Copyright 2010, Georgia Tech Research Corporation, - * Atlanta, Georgia 30332-0415 - * All Rights Reserved - * Authors: Frank Dellaert, et al. (see THANKS for the full author list) - - * See LICENSE for the license information - - * -------------------------------------------------------------------------- */ - -/** - * @file Argument.ccp - * @author Frank Dellaert - * @author Andrew Melim - * @author Richard Roberts - **/ - -#include "Argument.h" -#include "Class.h" - -#include - -#include -#include -#include - -using namespace std; -using namespace wrap; - -/* ************************************************************************* */ -Argument Argument::expandTemplate(const TemplateSubstitution& ts) const { - Argument instArg = *this; - instArg.type = ts.tryToSubstitite(type); - return instArg; -} - -/* ************************************************************************* */ -ArgumentList ArgumentList::expandTemplate( - const TemplateSubstitution& ts) const { - ArgumentList instArgList; - for(const Argument& arg: *this) { - Argument instArg = arg.expandTemplate(ts); - instArgList.push_back(instArg); - } - return instArgList; -} - -/* ************************************************************************* */ -string Argument::matlabClass(const string& delim) const { - string result; - for(const string& ns: type.namespaces()) - result += ns + delim; - if (type.name() == "string" || type.name() == "unsigned char" - || type.name() == "char") - return result + "char"; - if (type.name() == "Vector" || type.name() == "Matrix") - return result + "double"; - if (type.name() == "int" || type.name() == "size_t") - return result + "numeric"; - if (type.name() == "bool") - return result + "logical"; - return result + type.name(); -} - -/* ************************************************************************* */ -void Argument::matlab_unwrap(FileWriter& file, const string& matlabName) const { - file.oss << " "; - - string cppType = type.qualifiedName("::"); - string matlabUniqueType = type.qualifiedName(); - bool isNotScalar = !type.isScalar(); - - // We cannot handle scalar non const references - if (!isNotScalar && is_ref && !is_const) { - throw std::runtime_error("Cannot unwrap a scalar non-const reference"); - } - - if (is_ptr && type.category != Qualified::EIGEN) - // A pointer: emit an "unwrap_shared_ptr" call which returns a pointer - file.oss << "boost::shared_ptr<" << cppType << "> " << name - << " = unwrap_shared_ptr< "; - else if (is_ref && isNotScalar && type.category != Qualified::EIGEN) - // A reference: emit an "unwrap_shared_ptr" call and de-reference the pointer - file.oss << cppType << "& " << name << " = *unwrap_shared_ptr< "; - else - // Not a pointer, or a reference to a scalar type. Therefore, emit an "unwrap" call - // unwrap is specified in matlab.h as a series of template specializations - // that know how to unpack the expected MATLAB object - // example: double tol = unwrap< double >(in[2]); - // example: Vector v = unwrap< Vector >(in[1]); - file.oss << cppType << " " << name << " = unwrap< "; - - file.oss << cppType << " >(" << matlabName; - if( (is_ptr || is_ref) && isNotScalar && type.category != Qualified::EIGEN) - file.oss << ", \"ptr_" << matlabUniqueType << "\""; - file.oss << ");" << endl; -} - -/* ************************************************************************* */ -void Argument::proxy_check(FileWriter& proxyFile, const string& s) const { - proxyFile.oss << "isa(" << s << ",'" << matlabClass(".") << "')"; - if (type.name() == "Vector") - proxyFile.oss << " && size(" << s << ",2)==1"; -} - -/* ************************************************************************* */ -void Argument::emit_cython_pxd( - FileWriter& file, const std::string& className, - const std::vector& templateArgs) const { - string cythonType = type.pxdClassName(); - if (cythonType == "This") cythonType = className; - else if (type.isEigen()) - cythonType = "const " + cythonType + "&"; - else if (type.match(templateArgs)) - cythonType = type.name(); - - // add modifier - if (!type.isEigen()) { - if (is_ptr) cythonType = "shared_ptr[" + cythonType + "]&"; - if (is_ref) cythonType = cythonType + "&"; - if (is_const) cythonType = "const " + cythonType; - } - - file.oss << cythonType << " " << name; -} - -/* ************************************************************************* */ -void Argument::emit_cython_pyx(FileWriter& file) const { - file.oss << type.pyxArgumentType() << " " << name; -} - -/* ************************************************************************* */ -std::string Argument::pyx_convertEigenTypeAndStorageOrder() const { - if (!type.isEigen()) - return ""; - return name + " = " + name + ".astype(float, order=\'F\', copy=False)"; -} - -/* ************************************************************************* */ -std::string Argument::pyx_asParam() const { - string cythonType = type.pxdClassName(); - string cythonVar; - if (type.isNonBasicType()) { - cythonVar = name + "." + type.shared_pxd_obj_in_pyx(); - if (!is_ptr) cythonVar = "deref(" + cythonVar + ")"; - } else if (type.isEigen()) { - cythonVar = "<" + cythonType + ">" + "(Map[" + cythonType + "](" + name + "))"; - } else { - cythonVar = name; - } - return cythonVar; -} - -/* ************************************************************************* */ -string ArgumentList::types() const { - string str; - bool first = true; - for(Argument arg: *this) { - if (!first) - str += ","; - str += arg.type.name(); - first = false; - } - return str; -} - -/* ************************************************************************* */ -string ArgumentList::signature() const { - string sig; - bool cap = false; - - for(Argument arg: *this) { - for(char ch: arg.type.name()) - if (isupper(ch)) { - sig += ch; - //If there is a capital letter, we don't want to read it below - cap = true; - } - if (!cap) - sig += arg.type.name()[0]; - //Reset to default - cap = false; - } - - return sig; -} - -/* ************************************************************************* */ -string ArgumentList::names() const { - string str; - bool first = true; - for(Argument arg: *this) { - if (!first) - str += ","; - str += arg.name; - first = false; - } - return str; -} - -/* ************************************************************************* */ -bool ArgumentList::allScalar() const { - for(Argument arg: *this) - if (!arg.type.isScalar()) - return false; - return true; -} - -/* ************************************************************************* */ -void ArgumentList::matlab_unwrap(FileWriter& file, int start) const { - int index = start; - for(Argument arg: *this) { - stringstream buf; - buf << "in[" << index << "]"; - arg.matlab_unwrap(file, buf.str()); - index++; - } -} - -/* ************************************************************************* */ -void ArgumentList::emit_prototype(FileWriter& file, const string& name) const { - file.oss << name << "("; - bool first = true; - for(Argument arg: *this) { - if (!first) - file.oss << ", "; - file.oss << arg.type.name() << " " << arg.name; - first = false; - } - file.oss << ")"; -} - -/* ************************************************************************* */ -void ArgumentList::emit_cython_pxd( - FileWriter& file, const std::string& className, - const std::vector& templateArgs) const { - for (size_t j = 0; j(__params[" + std::to_string(j) + "])\n"; - return s; -} - -/* ************************************************************************* */ -void ArgumentList::proxy_check(FileWriter& proxyFile) const { - // Check nr of arguments - proxyFile.oss << "if length(varargin) == " << size(); - if (size() > 0) - proxyFile.oss << " && "; - // ...and their type.names - bool first = true; - for (size_t i = 0; i < size(); i++) { - if (!first) - proxyFile.oss << " && "; - string s = "varargin{" + boost::lexical_cast(i + 1) + "}"; - (*this)[i].proxy_check(proxyFile, s); - first = false; - } - proxyFile.oss << "\n"; -} - -/* ************************************************************************* */ - diff --git a/wrap/Argument.h b/wrap/Argument.h deleted file mode 100644 index c08eb0be9..000000000 --- a/wrap/Argument.h +++ /dev/null @@ -1,242 +0,0 @@ -/* ---------------------------------------------------------------------------- - - * GTSAM Copyright 2010, Georgia Tech Research Corporation, - * Atlanta, Georgia 30332-0415 - * All Rights Reserved - * Authors: Frank Dellaert, et al. (see THANKS for the full author list) - - * See LICENSE for the license information - - * -------------------------------------------------------------------------- */ - -/** - * @file Argument.h - * @brief arguments to constructors and methods - * @author Frank Dellaert - * @author Andrew Melim - * @author Richard Roberts - **/ - -#pragma once - -#include "TemplateSubstitution.h" -#include "FileWriter.h" -#include "ReturnValue.h" - -namespace wrap { - -/// Argument class -struct Argument { - Qualified type; - std::string name; - bool is_const, is_ref, is_ptr; - - Argument() : - is_const(false), is_ref(false), is_ptr(false) { - } - - Argument(const Qualified& t, const std::string& n) : - type(t), name(n), is_const(false), is_ref(false), is_ptr(false) { - } - - bool isSameSignature(const Argument& other) const { - return type == other.type - && is_const == other.is_const && is_ref == other.is_ref - && is_ptr == other.is_ptr; - } - - bool operator==(const Argument& other) const { - return type == other.type && name == other.name - && is_const == other.is_const && is_ref == other.is_ref - && is_ptr == other.is_ptr; - } - - Argument expandTemplate(const TemplateSubstitution& ts) const; - - /// return MATLAB class for use in isa(x,class) - std::string matlabClass(const std::string& delim = "") const; - - /// MATLAB code generation, MATLAB to C++ - void matlab_unwrap(FileWriter& file, const std::string& matlabName) const; - - /** - * emit checking argument to MATLAB proxy - * @param proxyFile output stream - */ - void proxy_check(FileWriter& proxyFile, const std::string& s) const; - - /** - * emit arguments for cython pxd - * @param file output stream - */ - void emit_cython_pxd(FileWriter& file, const std::string& className, - const std::vector& templateArgs) const; - void emit_cython_pyx(FileWriter& file) const; - std::string pyx_asParam() const; - std::string pyx_convertEigenTypeAndStorageOrder() const; - - friend std::ostream& operator<<(std::ostream& os, const Argument& arg) { - os << (arg.is_const ? "const " : "") << arg.type << (arg.is_ptr ? "*" : "") - << (arg.is_ref ? "&" : ""); - return os; - } - -}; - -/// Argument list is just a container with Arguments -struct ArgumentList: public std::vector { - - /// create a comma-separated string listing all argument types (not used) - std::string types() const; - - /// create a short "signature" string - std::string signature() const; - - /// create a comma-separated string listing all argument names, used in m-files - std::string names() const; - - /// Check if all arguments scalar - bool allScalar() const; - - ArgumentList expandTemplate(const TemplateSubstitution& ts) const; - - bool isSameSignature(const ArgumentList& other) const { - for(size_t i = 0; i& templateArgs) const; - void emit_cython_pyx(FileWriter& file) const; - std::string pyx_asParams() const; - std::string pyx_paramsList() const; - std::string pyx_castParamsToPythonType(const std::string& indent) const; - std::string pyx_convertEigenTypeAndStorageOrder(const std::string& indent) const; - - /** - * emit checking arguments to MATLAB proxy - * @param proxyFile output stream - */ - void proxy_check(FileWriter& proxyFile) const; - - /// Output stream operator - friend std::ostream& operator<<(std::ostream& os, - const ArgumentList& argList) { - os << "("; - if (argList.size() > 0) - os << argList.front(); - if (argList.size() > 1) - for (size_t i = 1; i < argList.size(); i++) - os << ", " << argList[i]; - os << ")"; - return os; - } - -}; - -/* ************************************************************************* */ -// http://boost-spirit.com/distrib/spirit_1_8_2/libs/spirit/doc/grammar.html -struct ArgumentGrammar: public classic::grammar { - - wrap::Argument& result_; ///< successful parse will be placed in here - TypeGrammar argument_type_g; ///< Type parser for Argument::type - - /// Construct type grammar and specify where result is placed - ArgumentGrammar(wrap::Argument& result) : - result_(result), argument_type_g(result.type) { - } - - /// Definition of type grammar - template - struct definition: BasicRules { - - typedef classic::rule Rule; - - Rule argument_p; - - definition(ArgumentGrammar const& self) { - using namespace classic; - - // NOTE: allows for pointers to all types - // Slightly more permissive than before on basis/eigen type qualification - // Also, currently parses Point2*&, can't make it work otherwise :-( - argument_p = !str_p("const")[assign_a(self.result_.is_const, T)] // - >> self.argument_type_g // - >> !ch_p('*')[assign_a(self.result_.is_ptr, T)] - >> !ch_p('&')[assign_a(self.result_.is_ref, T)] - >> BasicRules::name_p[assign_a(self.result_.name)]; - } - - Rule const& start() const { - return argument_p; - } - - }; -}; -// ArgumentGrammar - -/* ************************************************************************* */ -// http://boost-spirit.com/distrib/spirit_1_8_2/libs/spirit/doc/grammar.html -struct ArgumentListGrammar: public classic::grammar { - - wrap::ArgumentList& result_; ///< successful parse will be placed in here - - /// Construct type grammar and specify where result is placed - ArgumentListGrammar(wrap::ArgumentList& result) : - result_(result) { - } - - /// Definition of type grammar - template - struct definition { - - const Argument arg0; ///< used to reset arg - Argument arg; ///< temporary argument for use during parsing - ArgumentGrammar argument_g; ///< single Argument parser - - classic::rule argument_p, argumentList_p; - - definition(ArgumentListGrammar const& self) : - argument_g(arg) { - using namespace classic; - - argument_p = argument_g // - [classic::push_back_a(self.result_, arg)] // - [assign_a(arg, arg0)]; - - argumentList_p = '(' >> !argument_p >> *(',' >> argument_p) >> ')'; - } - - classic::rule const& start() const { - return argumentList_p; - } - - }; -}; -// ArgumentListGrammar - -/* ************************************************************************* */ - -}// \namespace wrap - diff --git a/wrap/CMakeLists.txt b/wrap/CMakeLists.txt deleted file mode 100644 index c04a44edb..000000000 --- a/wrap/CMakeLists.txt +++ /dev/null @@ -1,45 +0,0 @@ -# Build/install Wrap - -set(WRAP_BOOST_LIBRARIES - Boost::system - Boost::filesystem - Boost::thread -) - -# Allow for disabling serialization to handle errors related to Clang's linker -option(GTSAM_WRAP_SERIALIZATION "If enabled, allows for wrapped objects to be saved via boost.serialization" ON) - -# Build the executable itself -file(GLOB wrap_srcs "*.cpp") -file(GLOB wrap_headers "*.h") -list(REMOVE_ITEM wrap_srcs ${CMAKE_CURRENT_SOURCE_DIR}/wrap.cpp) -add_library(wrap_lib STATIC ${wrap_srcs} ${wrap_headers}) -target_include_directories(wrap_lib PUBLIC - $ -) -if (NOT GTSAM_WRAP_SERIALIZATION) - target_compile_definitions(wrap_lib PUBLIC -DWRAP_DISABLE_SERIALIZE) -endif() - -# Apply build flags: -gtsam_apply_build_flags(wrap_lib) - -target_link_libraries(wrap_lib ${WRAP_BOOST_LIBRARIES}) -gtsam_assign_source_folders(${wrap_srcs} ${wrap_headers}) -add_executable(wrap wrap.cpp) -target_link_libraries(wrap PRIVATE wrap_lib) - -# Set folder in Visual Studio -file(RELATIVE_PATH relative_path "${PROJECT_SOURCE_DIR}" "${CMAKE_CURRENT_SOURCE_DIR}") -set_target_properties(wrap_lib wrap PROPERTIES FOLDER "${relative_path}") - -# Install wrap binary and export target -install(TARGETS wrap EXPORT GTSAM-exports DESTINATION ${CMAKE_INSTALL_BINDIR}) -list(APPEND GTSAM_EXPORTED_TARGETS wrap) -set(GTSAM_EXPORTED_TARGETS "${GTSAM_EXPORTED_TARGETS}" PARENT_SCOPE) - -# Install matlab header -install(FILES matlab.h DESTINATION ${CMAKE_INSTALL_INCLUDEDIR}/wrap) - -# Build tests -add_subdirectory(tests) diff --git a/wrap/Class.cpp b/wrap/Class.cpp deleted file mode 100644 index 65ce9eab7..000000000 --- a/wrap/Class.cpp +++ /dev/null @@ -1,897 +0,0 @@ -/* ---------------------------------------------------------------------------- - - * GTSAM Copyright 2010, Georgia Tech Research Corporation, - * Atlanta, Georgia 30332-0415 - * All Rights Reserved - * Authors: Frank Dellaert, et al. (see THANKS for the full author list) - - * See LICENSE for the license information - - * -------------------------------------------------------------------------- */ - -/** - * @file Class.cpp - * @author Frank Dellaert - * @author Andrew Melim - * @author Richard Roberts - **/ - -#include "Class.h" -#include "utilities.h" -#include "Argument.h" -#include - -#include -#include -#include -#include -#include -#include -#include - -#include -#include -#include -#include -#include // std::ostream_iterator -//#include // on Linux GCC: fails with error regarding needing C++0x std flags -//#include // same failure as above -#include // works on Linux GCC -using namespace std; -using namespace wrap; - -/* ************************************************************************* */ -void Class::assignParent(const Qualified& parent) { - parentClass.reset(parent); -} - -/* ************************************************************************* */ -boost::optional Class::qualifiedParent() const { - boost::optional result = boost::none; - if (parentClass) - result = parentClass->qualifiedName("::"); - return result; -} - -/* ************************************************************************* */ -static void handleException(const out_of_range& oor, - const Class::Methods& methods) { - cerr << "Class::method: key not found: " << oor.what() << ", methods are:\n"; - using boost::adaptors::map_keys; - ostream_iterator out_it(cerr, "\n"); - boost::copy(methods | map_keys, out_it); -} - -/* ************************************************************************* */ -// Method& Class::mutableMethod(Str key) { -// try { -// return methods_.at(key); -// } catch (const out_of_range& oor) { -// handleException(oor, methods_); -// throw runtime_error("Internal error in wrap"); -// } -// } - -/* ************************************************************************* */ -const Method& Class::method(Str key) const { - try { - return methods_.at(key); - } catch (const out_of_range& oor) { - handleException(oor, methods_); - throw runtime_error("Internal error in wrap"); - } -} - -/* ************************************************************************* */ -void Class::matlab_proxy(Str toolboxPath, Str wrapperName, - const TypeAttributesTable& typeAttributes, FileWriter& wrapperFile, - vector& functionNames) const { - - // Create namespace folders - createNamespaceStructure(namespaces(), toolboxPath); - - // open destination classFile - string classFile = matlabName(toolboxPath); - FileWriter proxyFile(classFile, verbose_, "%"); - - // get the name of actual matlab object - const string matlabQualName = qualifiedName("."); - const string matlabUniqueName = qualifiedName(); - const string cppName = qualifiedName("::"); - - // emit class proxy code - // we want our class to inherit the handle class for memory purposes - const string parent = - parentClass ? parentClass->qualifiedName(".") : "handle"; - comment_fragment(proxyFile); - proxyFile.oss << "classdef " << name() << " < " << parent << endl; - proxyFile.oss << " properties\n"; - proxyFile.oss << " ptr_" << matlabUniqueName << " = 0\n"; - proxyFile.oss << " end\n"; - proxyFile.oss << " methods\n"; - - // Constructor - proxyFile.oss << " function obj = " << name() << "(varargin)\n"; - // Special pointer constructors - one in MATLAB to create an object and - // assign a pointer returned from a C++ function. In turn this MATLAB - // constructor calls a special C++ function that just adds the object to - // its collector. This allows wrapped functions to return objects in - // other wrap modules - to add these to their collectors the pointer is - // passed from one C++ module into matlab then back into the other C++ - // module. - pointer_constructor_fragments(proxyFile, wrapperFile, wrapperName, - functionNames); - wrapperFile.oss << "\n"; - - // Regular constructors - boost::optional cppBaseName = qualifiedParent(); - for (size_t i = 0; i < constructor.nrOverloads(); i++) { - ArgumentList args = constructor.argumentList(i); - const int id = (int) functionNames.size(); - constructor.proxy_fragment(proxyFile, wrapperName, (bool) parentClass, id, - args); - const string wrapFunctionName = constructor.wrapper_fragment(wrapperFile, - cppName, matlabUniqueName, cppBaseName, id, args); - wrapperFile.oss << "\n"; - functionNames.push_back(wrapFunctionName); - } - proxyFile.oss << " else\n"; - proxyFile.oss << " error('Arguments do not match any overload of " - << matlabQualName << " constructor');\n"; - proxyFile.oss << " end\n"; - if (parentClass) - proxyFile.oss << " obj = obj@" << parentClass->qualifiedName(".") - << "(uint64(" << ptr_constructor_key << "), base_ptr);\n"; - proxyFile.oss << " obj.ptr_" << matlabUniqueName << " = my_ptr;\n"; - proxyFile.oss << " end\n\n"; - - // Deconstructor - { - const int id = (int) functionNames.size(); - deconstructor.proxy_fragment(proxyFile, wrapperName, matlabUniqueName, id); - proxyFile.oss << "\n"; - const string functionName = deconstructor.wrapper_fragment(wrapperFile, - cppName, matlabUniqueName, id); - wrapperFile.oss << "\n"; - functionNames.push_back(functionName); - } - proxyFile.oss - << " function display(obj), obj.print(''); end\n %DISPLAY Calls print on the object\n"; - proxyFile.oss - << " function disp(obj), obj.display; end\n %DISP Calls print on the object\n"; - - // Methods - for(const Methods::value_type& name_m: methods_) { - const Method& m = name_m.second; - m.proxy_wrapper_fragments(proxyFile, wrapperFile, cppName, matlabQualName, - matlabUniqueName, wrapperName, typeAttributes, functionNames); - proxyFile.oss << "\n"; - wrapperFile.oss << "\n"; - } - if (hasSerialization) - serialization_fragments(proxyFile, wrapperFile, wrapperName, functionNames); - - proxyFile.oss << " end\n"; - proxyFile.oss << "\n"; - proxyFile.oss << " methods(Static = true)\n"; - - // Static methods - for(const StaticMethods::value_type& name_m: static_methods) { - const StaticMethod& m = name_m.second; - m.proxy_wrapper_fragments(proxyFile, wrapperFile, cppName, matlabQualName, - matlabUniqueName, wrapperName, typeAttributes, functionNames); - proxyFile.oss << "\n"; - wrapperFile.oss << "\n"; - } - if (hasSerialization) - deserialization_fragments(proxyFile, wrapperFile, wrapperName, - functionNames); - - proxyFile.oss << " end\n"; - proxyFile.oss << "end\n"; - - // Close file - proxyFile.emit(true); -} - -/* ************************************************************************* */ -void Class::pointer_constructor_fragments(FileWriter& proxyFile, - FileWriter& wrapperFile, Str wrapperName, - vector& functionNames) const { - - const string matlabUniqueName = qualifiedName(); - const string cppName = qualifiedName("::"); - - const int collectorInsertId = (int) functionNames.size(); - const string collectorInsertFunctionName = matlabUniqueName - + "_collectorInsertAndMakeBase_" - + boost::lexical_cast(collectorInsertId); - functionNames.push_back(collectorInsertFunctionName); - - int upcastFromVoidId; - string upcastFromVoidFunctionName; - if (isVirtual) { - upcastFromVoidId = (int) functionNames.size(); - upcastFromVoidFunctionName = matlabUniqueName + "_upcastFromVoid_" - + boost::lexical_cast(upcastFromVoidId); - functionNames.push_back(upcastFromVoidFunctionName); - } - - // MATLAB constructor that assigns pointer to matlab object then calls c++ - // function to add the object to the collector. - if (isVirtual) { - proxyFile.oss - << " if (nargin == 2 || (nargin == 3 && strcmp(varargin{3}, 'void')))"; - } else { - proxyFile.oss << " if nargin == 2"; - } - proxyFile.oss << " && isa(varargin{1}, 'uint64') && varargin{1} == uint64(" - << ptr_constructor_key << ")\n"; - if (isVirtual) { - proxyFile.oss << " if nargin == 2\n"; - proxyFile.oss << " my_ptr = varargin{2};\n"; - proxyFile.oss << " else\n"; - proxyFile.oss << " my_ptr = " << wrapperName << "(" - << upcastFromVoidId << ", varargin{2});\n"; - proxyFile.oss << " end\n"; - } else { - proxyFile.oss << " my_ptr = varargin{2};\n"; - } - if (!parentClass) // If this class has a base class, we'll get a base class pointer back - proxyFile.oss << " "; - else - proxyFile.oss << " base_ptr = "; - proxyFile.oss << wrapperName << "(" << collectorInsertId << ", my_ptr);\n"; // Call collector insert and get base class ptr - - // C++ function to add pointer from MATLAB to collector. The pointer always - // comes from a C++ return value; this mechanism allows the object to be added - // to a collector in a different wrap module. If this class has a base class, - // a new pointer to the base class is allocated and returned. - wrapperFile.oss << "void " << collectorInsertFunctionName - << "(int nargout, mxArray *out[], int nargin, const mxArray *in[])\n"; - wrapperFile.oss << "{\n"; - wrapperFile.oss << " mexAtExit(&_deleteAllObjects);\n"; - // Typedef boost::shared_ptr - wrapperFile.oss << " typedef boost::shared_ptr<" << cppName << "> Shared;\n"; - wrapperFile.oss << "\n"; - // Get self pointer passed in - wrapperFile.oss - << " Shared *self = *reinterpret_cast (mxGetData(in[0]));\n"; - // Add to collector - wrapperFile.oss << " collector_" << matlabUniqueName << ".insert(self);\n"; - // If we have a base class, return the base class pointer (MATLAB will call the base class collectorInsertAndMakeBase to add this to the collector and recurse the heirarchy) - boost::optional cppBaseName = qualifiedParent(); - if (cppBaseName) { - wrapperFile.oss << "\n"; - wrapperFile.oss << " typedef boost::shared_ptr<" << *cppBaseName - << "> SharedBase;\n"; - wrapperFile.oss - << " out[0] = mxCreateNumericMatrix(1, 1, mxUINT32OR64_CLASS, mxREAL);\n"; - wrapperFile.oss - << " *reinterpret_cast(mxGetData(out[0])) = new SharedBase(*self);\n"; - } - wrapperFile.oss << "}\n"; - - // If this is a virtual function, C++ function to dynamic upcast it from a - // shared_ptr. This mechanism allows automatic dynamic creation of the - // real underlying derived-most class when a C++ method returns a virtual - // base class. - if (isVirtual) - wrapperFile.oss << "\n" - "void " << upcastFromVoidFunctionName - << "(int nargout, mxArray *out[], int nargin, const mxArray *in[]) {\n" - " mexAtExit(&_deleteAllObjects);\n" - " typedef boost::shared_ptr<" << cppName - << "> Shared;\n" - " boost::shared_ptr *asVoid = *reinterpret_cast**> (mxGetData(in[0]));\n" - " out[0] = mxCreateNumericMatrix(1, 1, mxUINT32OR64_CLASS, mxREAL);\n" - " Shared *self = new Shared(boost::static_pointer_cast<" << cppName - << ">(*asVoid));\n" - " *reinterpret_cast(mxGetData(out[0])) = self;\n" - "}\n"; -} - -/* ************************************************************************* */ -Class Class::expandTemplate(const TemplateSubstitution& ts) const { - Class inst = *this; - inst.methods_ = expandMethodTemplate(methods_, ts); - inst.static_methods = expandMethodTemplate(static_methods, ts); - inst.constructor = constructor.expandTemplate(ts); - inst.deconstructor.name = inst.name(); - return inst; -} - -/* ************************************************************************* */ -vector Class::expandTemplate(Str templateArg, - const vector& instantiations) const { - vector result; - for(const Qualified& instName: instantiations) { - Qualified expandedClass = (Qualified) (*this); - expandedClass.expand(instName.name()); - const TemplateSubstitution ts(templateArg, instName, expandedClass); - Class inst = expandTemplate(ts); - inst.name_ = expandedClass.name(); - inst.templateArgs.clear(); - inst.typedefName = qualifiedName("::") + "<" + instName.qualifiedName("::") - + ">"; - inst.templateInstTypeList.push_back(instName); - inst.templateClass = *this; - result.push_back(inst); - } - return result; -} - -/* ************************************************************************* */ -vector Class::expandTemplate(Str templateArg, - const vector& integers) const { - vector result; - for(int i: integers) { - Qualified expandedClass = (Qualified) (*this); - stringstream ss; ss << i; - string instName = ss.str(); - expandedClass.expand(instName); - const TemplateSubstitution ts(templateArg, instName, expandedClass); - Class inst = expandTemplate(ts); - inst.name_ = expandedClass.name(); - inst.templateArgs.clear(); - inst.typedefName = qualifiedName("::") + "<" + instName + ">"; - result.push_back(inst); - } - return result; -} - -/* ************************************************************************* */ -void Class::addMethod(bool verbose, bool is_const, Str methodName, - const ArgumentList& argumentList, - const ReturnValue& returnValue, const Template& tmplate) { - // Check if templated - if (tmplate.valid()) { - try { - templateMethods_[methodName].addOverload(methodName, argumentList, - returnValue, is_const, - tmplate.argName(), verbose); - } catch (const std::runtime_error& e) { - throw std::runtime_error("Class::addMethod: error adding " + name_ + - "::" + methodName + "\n" + e.what()); - } - // Create method to expand - // For all values of the template argument, create a new method - for (const Qualified& instName : tmplate.argValues()) { - const TemplateSubstitution ts(tmplate.argName(), instName, *this); - // substitute template in arguments - ArgumentList expandedArgs = argumentList.expandTemplate(ts); - // do the same for return type - ReturnValue expandedRetVal = returnValue.expandTemplate(ts); - // Now stick in new overload stack with expandedMethodName key - // but note we use the same, unexpanded methodName in overload - string expandedMethodName = methodName + instName.name(); - try { - methods_[expandedMethodName].addOverload(methodName, expandedArgs, - expandedRetVal, is_const, - instName, verbose); - } catch (const std::runtime_error& e) { - throw std::runtime_error("Class::addMethod: error adding " + name_ + - "::" + expandedMethodName + "\n" + e.what()); - } - } - } else { - try { - // just add overload - methods_[methodName].addOverload(methodName, argumentList, returnValue, - is_const, boost::none, verbose); - nontemplateMethods_[methodName].addOverload(methodName, argumentList, - returnValue, is_const, - boost::none, verbose); - } catch (const std::runtime_error& e) { - throw std::runtime_error("Class::addMethod: error adding " + name_ + - "::" + methodName + "\n" + e.what()); - } - } -} - -/* ************************************************************************* */ -void Class::erase_serialization(Methods& methods) { - Methods::iterator it = methods.find("serializable"); - if (it != methods.end()) { -#ifndef WRAP_DISABLE_SERIALIZE - isSerializable = true; -#else - // cout << "Ignoring serializable() flag in class " << name << endl; -#endif - methods.erase(it); - } - - it = methods.find("serialize"); - if (it != methods.end()) { -#ifndef WRAP_DISABLE_SERIALIZE - isSerializable = true; - hasSerialization = true; -#else - // cout << "Ignoring serialize() flag in class " << name << endl; -#endif - methods.erase(it); - } -} - -void Class::erase_serialization() { - erase_serialization(methods_); - erase_serialization(nontemplateMethods_); -} - -/* ************************************************************************* */ -void Class::verifyAll(vector& validTypes, bool& hasSerialiable) const { - - hasSerialiable |= isSerializable; - - // verify all of the function arguments - //TODO:verifyArguments(validTypes, constructor.args_list); - verifyArguments(validTypes, static_methods); - verifyArguments(validTypes, methods_); - - // verify function return types - verifyReturnTypes(validTypes, static_methods); - verifyReturnTypes(validTypes, methods_); - - // verify parents - boost::optional parent = qualifiedParent(); - if (parent - && find(validTypes.begin(), validTypes.end(), *parent) - == validTypes.end()) - throw DependencyMissing(*parent, qualifiedName("::")); -} - -/* ************************************************************************* */ -void Class::appendInheritedMethods(const Class& cls, - const vector& classes) { - - if (cls.parentClass) { - - // Find parent - for(const Class& parent: classes) { - // We found a parent class for our parent, TODO improve ! - if (parent.name() == cls.parentClass->name()) { - methods_.insert(parent.methods_.begin(), parent.methods_.end()); - appendInheritedMethods(parent, classes); - } - } - } -} - -/* ************************************************************************* */ -void Class::removeInheritedNontemplateMethods(vector& classes) { - if (!parentClass) return; - // Find parent - auto parentIt = std::find_if(classes.begin(), classes.end(), - [&](const Class& cls) { return cls.name() == parentClass->name(); }); - if (parentIt == classes.end()) return; // ignore if parent not found - Class& parent = *parentIt; - - // Only check nontemplateMethods_ - for(const string& methodName: nontemplateMethods_ | boost::adaptors::map_keys) { - // check if the method exists in its parent - // Check against parent's methods_ because all the methods of grand - // parent and grand-grand-parent, etc. are already included there - // This is to avoid looking into higher level grand parents... - auto it = parent.methods_.find(methodName); - if (it == parent.methods_.end()) continue; // if not: ignore! - - Method& parentMethod = it->second; - Method& method = nontemplateMethods_[methodName]; - // check if they have the same modifiers (const/static/templateArgs) - if (!method.isSameModifiers(parentMethod)) continue; // if not: ignore - - // check and remove duplicate overloads - auto methodOverloads = boost::combine(method.returnVals_, method.argLists_); - auto parentMethodOverloads = boost::combine(parentMethod.returnVals_, parentMethod.argLists_); - auto result = boost::remove_if( - methodOverloads, - [&](boost::tuple const& overload) { - bool found = std::find_if( - parentMethodOverloads.begin(), - parentMethodOverloads.end(), - [&](boost::tuple const& - parentOverload) { - return overload.get<0>() == parentOverload.get<0>() && - overload.get<1>().isSameSignature(parentOverload.get<1>()); - }) != parentMethodOverloads.end(); - return found; - }); - // remove all duplicate overloads - method.returnVals_.erase(boost::get<0>(result.get_iterator_tuple()), - method.returnVals_.end()); - method.argLists_.erase(boost::get<1>(result.get_iterator_tuple()), - method.argLists_.end()); - } - // [Optional] remove the entire method if it has no overload - for (auto it = nontemplateMethods_.begin(), ite = nontemplateMethods_.end(); it != ite;) - if (it->second.nrOverloads() == 0) it = nontemplateMethods_.erase(it); else ++it; -} - -/* ************************************************************************* */ -string Class::getTypedef() const { - string result; - for(Str namesp: namespaces()) { - result += ("namespace " + namesp + " { "); - } - result += ("typedef " + typedefName + " " + name() + ";"); - for (size_t i = 0; i < namespaces().size(); ++i) { - result += " }"; - } - return result; -} - -/* ************************************************************************* */ -void Class::comment_fragment(FileWriter& proxyFile) const { - proxyFile.oss << "%class " << name() << ", see Doxygen page for details\n"; - proxyFile.oss - << "%at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html\n"; - - constructor.comment_fragment(proxyFile); - - if (!methods_.empty()) - proxyFile.oss << "%\n%-------Methods-------\n"; - for(const Methods::value_type& name_m: methods_) - name_m.second.comment_fragment(proxyFile); - - if (!static_methods.empty()) - proxyFile.oss << "%\n%-------Static Methods-------\n"; - for(const StaticMethods::value_type& name_m: static_methods) - name_m.second.comment_fragment(proxyFile); - - if (hasSerialization) { - proxyFile.oss << "%\n%-------Serialization Interface-------\n"; - proxyFile.oss << "%string_serialize() : returns string\n"; - proxyFile.oss << "%string_deserialize(string serialized) : returns " - << name() << "\n"; - } - - proxyFile.oss << "%\n"; -} - -/* ************************************************************************* */ -void Class::serialization_fragments(FileWriter& proxyFile, - FileWriter& wrapperFile, Str wrapperName, - vector& functionNames) const { - -//void Point3_string_serialize_17(int nargout, mxArray *out[], int nargin, const mxArray *in[]) -//{ -// typedef boost::shared_ptr Shared; -// checkArguments("string_serialize",nargout,nargin-1,0); -// Shared obj = unwrap_shared_ptr(in[0], "ptr_Point3"); -// ostringstream out_archive_stream; -// boost::archive::text_oarchive out_archive(out_archive_stream); -// out_archive << *obj; -// out[0] = wrap< string >(out_archive_stream.str()); -//} - - int serialize_id = functionNames.size(); - const string matlabQualName = qualifiedName("."); - const string matlabUniqueName = qualifiedName(); - const string cppClassName = qualifiedName("::"); - const string wrapFunctionNameSerialize = matlabUniqueName - + "_string_serialize_" + boost::lexical_cast(serialize_id); - functionNames.push_back(wrapFunctionNameSerialize); - - // call - //void Point3_string_serialize_17(int nargout, mxArray *out[], int nargin, const mxArray *in[]) - wrapperFile.oss << "void " << wrapFunctionNameSerialize - << "(int nargout, mxArray *out[], int nargin, const mxArray *in[])\n"; - wrapperFile.oss << "{\n"; - wrapperFile.oss << " typedef boost::shared_ptr<" << cppClassName - << "> Shared;" << endl; - - // check arguments - for serialize, no arguments - // example: checkArguments("string_serialize",nargout,nargin-1,0); - wrapperFile.oss - << " checkArguments(\"string_serialize\",nargout,nargin-1,0);\n"; - - // get class pointer - // example: Shared obj = unwrap_shared_ptr(in[0], "ptr_Point3"); - wrapperFile.oss << " Shared obj = unwrap_shared_ptr<" << cppClassName - << ">(in[0], \"ptr_" << matlabUniqueName << "\");" << endl; - - // Serialization boilerplate - wrapperFile.oss << " ostringstream out_archive_stream;\n"; - wrapperFile.oss - << " boost::archive::text_oarchive out_archive(out_archive_stream);\n"; - wrapperFile.oss << " out_archive << *obj;\n"; - wrapperFile.oss << " out[0] = wrap< string >(out_archive_stream.str());\n"; - - // finish - wrapperFile.oss << "}\n"; - - // Generate code for matlab function -// function varargout string_serialize(this, varargin) -// % STRING_SERIALIZE usage: string_serialize() : returns string -// % Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html -// if length(varargin) == 0 -// varargout{1} = geometry_wrapper(15, this, varargin{:}); -// else -// error('Arguments do not match any overload of function Point3.string_serialize'); -// end -// end - - proxyFile.oss - << " function varargout = string_serialize(this, varargin)\n"; - proxyFile.oss - << " % STRING_SERIALIZE usage: string_serialize() : returns string\n"; - proxyFile.oss - << " % Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html\n"; - proxyFile.oss << " if length(varargin) == 0\n"; - proxyFile.oss << " varargout{1} = " << wrapperName << "(" - << boost::lexical_cast(serialize_id) << ", this, varargin{:});\n"; - proxyFile.oss << " else\n"; - proxyFile.oss - << " error('Arguments do not match any overload of function " - << matlabQualName << ".string_serialize');\n"; - proxyFile.oss << " end\n"; - proxyFile.oss << " end\n\n"; - - // Generate code for matlab save function -// function sobj = saveobj(obj) -// % SAVEOBJ Saves the object to a matlab-readable format -// sobj = obj.string_serialize(); -// end - - proxyFile.oss << " function sobj = saveobj(obj)\n"; - proxyFile.oss - << " % SAVEOBJ Saves the object to a matlab-readable format\n"; - proxyFile.oss << " sobj = obj.string_serialize();\n"; - proxyFile.oss << " end\n"; -} - -/* ************************************************************************* */ -void Class::deserialization_fragments(FileWriter& proxyFile, - FileWriter& wrapperFile, Str wrapperName, - vector& functionNames) const { - //void Point3_string_deserialize_18(int nargout, mxArray *out[], int nargin, const mxArray *in[]) - //{ - // typedef boost::shared_ptr Shared; - // checkArguments("Point3.string_deserialize",nargout,nargin,1); - // string serialized = unwrap< string >(in[0]); - // istringstream in_archive_stream(serialized); - // boost::archive::text_iarchive in_archive(in_archive_stream); - // Shared output(new Point3(0,0,0)); - // in_archive >> *output; - // out[0] = wrap_shared_ptr(output,"Point3", false); - //} - int deserialize_id = functionNames.size(); - const string matlabQualName = qualifiedName("."); - const string matlabUniqueName = qualifiedName(); - const string cppClassName = qualifiedName("::"); - const string wrapFunctionNameDeserialize = matlabUniqueName - + "_string_deserialize_" + boost::lexical_cast(deserialize_id); - functionNames.push_back(wrapFunctionNameDeserialize); - - // call - wrapperFile.oss << "void " << wrapFunctionNameDeserialize - << "(int nargout, mxArray *out[], int nargin, const mxArray *in[])\n"; - wrapperFile.oss << "{\n"; - wrapperFile.oss << " typedef boost::shared_ptr<" << cppClassName - << "> Shared;" << endl; - - // check arguments - for deserialize, 1 string argument - wrapperFile.oss << " checkArguments(\"" << matlabUniqueName - << ".string_deserialize\",nargout,nargin,1);\n"; - - // string argument with deserialization boilerplate - wrapperFile.oss << " string serialized = unwrap< string >(in[0]);\n"; - wrapperFile.oss << " istringstream in_archive_stream(serialized);\n"; - wrapperFile.oss - << " boost::archive::text_iarchive in_archive(in_archive_stream);\n"; - wrapperFile.oss << " Shared output(new " << cppClassName << "());\n"; - wrapperFile.oss << " in_archive >> *output;\n"; - wrapperFile.oss << " out[0] = wrap_shared_ptr(output,\"" << matlabQualName - << "\", false);\n"; - wrapperFile.oss << "}\n"; - - // Generate matlab function -// function varargout = string_deserialize(varargin) -// % STRING_DESERIALIZE usage: string_deserialize() : returns Point3 -// % Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html -// if length(varargin) == 1 -// varargout{1} = geometry_wrapper(18, varargin{:}); -// else -// error('Arguments do not match any overload of function Point3.string_deserialize'); -// end -// end - - proxyFile.oss << " function varargout = string_deserialize(varargin)\n"; - proxyFile.oss - << " % STRING_DESERIALIZE usage: string_deserialize() : returns " - << matlabQualName << "\n"; - proxyFile.oss - << " % Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html\n"; - proxyFile.oss << " if length(varargin) == 1\n"; - proxyFile.oss << " varargout{1} = " << wrapperName << "(" - << boost::lexical_cast(deserialize_id) << ", varargin{:});\n"; - proxyFile.oss << " else\n"; - proxyFile.oss - << " error('Arguments do not match any overload of function " - << matlabQualName << ".string_deserialize');\n"; - proxyFile.oss << " end\n"; - proxyFile.oss << " end\n\n"; - - // Generate matlab load function -// function obj = loadobj(sobj) -// % LOADOBJ Saves the object to a matlab-readable format -// obj = Point3.string_deserialize(sobj); -// end - - proxyFile.oss << " function obj = loadobj(sobj)\n"; - proxyFile.oss - << " % LOADOBJ Saves the object to a matlab-readable format\n"; - proxyFile.oss << " obj = " << matlabQualName - << ".string_deserialize(sobj);\n"; - proxyFile.oss << " end" << endl; -} - -/* ************************************************************************* */ -string Class::getSerializationExport() const { - //BOOST_CLASS_EXPORT_GUID(gtsam::SharedDiagonal, "gtsamSharedDiagonal"); - return "BOOST_CLASS_EXPORT_GUID(" + qualifiedName("::") + ", \"" - + qualifiedName() + "\");"; -} - -/* ************************************************************************* */ -void Class::python_wrapper(FileWriter& wrapperFile) const { - wrapperFile.oss << "class_<" << name() << ">(\"" << name() << "\")\n"; - constructor.python_wrapper(wrapperFile, name()); - for(const StaticMethod& m: static_methods | boost::adaptors::map_values) - m.python_wrapper(wrapperFile, name()); - for(const Method& m: methods_ | boost::adaptors::map_values) - m.python_wrapper(wrapperFile, name()); - wrapperFile.oss << ";\n\n"; -} - -/* ************************************************************************* */ -void Class::emit_cython_pxd(FileWriter& pxdFile) const { - pxdFile.oss << "cdef extern from \"" << includeFile << "\""; - string ns = qualifiedNamespaces("::"); - if (!ns.empty()) - pxdFile.oss << " namespace \"" << ns << "\""; - pxdFile.oss << ":" << endl; - pxdFile.oss << " cdef cppclass " << pxdClassName() << " \"" << qualifiedName("::") << "\""; - if (templateArgs.size()>0) { - pxdFile.oss << "["; - for(size_t i = 0; ipxdClassName() << ")"; - pxdFile.oss << ":\n"; - - constructor.emit_cython_pxd(pxdFile, *this); - if (constructor.nrOverloads()>0) pxdFile.oss << "\n"; - - for(const StaticMethod& m: static_methods | boost::adaptors::map_values) - m.emit_cython_pxd(pxdFile, *this); - if (static_methods.size()>0) pxdFile.oss << "\n"; - - for(const Method& m: nontemplateMethods_ | boost::adaptors::map_values) - m.emit_cython_pxd(pxdFile, *this); - - for(const TemplateMethod& m: templateMethods_ | boost::adaptors::map_values) - m.emit_cython_pxd(pxdFile, *this); - size_t numMethods = constructor.nrOverloads() + static_methods.size() + - methods_.size() + templateMethods_.size(); - if (numMethods == 0) - pxdFile.oss << " pass\n"; -} -/* ************************************************************************* */ -void Class::emit_cython_wrapper_pxd(FileWriter& pxdFile) const { - pxdFile.oss << "\ncdef class " << pyxClassName(); - if (getParent()) - pxdFile.oss << "(" << getParent()->pyxClassName() << ")"; - pxdFile.oss << ":\n"; - pxdFile.oss << " cdef " << shared_pxd_class_in_pyx() << " " - << shared_pxd_obj_in_pyx() << "\n"; - // cyCreateFromShared - pxdFile.oss << " @staticmethod\n"; - pxdFile.oss << " cdef " << pyxClassName() << " cyCreateFromShared(const " - << shared_pxd_class_in_pyx() << "& other)\n"; - for(const StaticMethod& m: static_methods | boost::adaptors::map_values) - m.emit_cython_wrapper_pxd(pxdFile, *this); - if (static_methods.size()>0) pxdFile.oss << "\n"; -} - -/* ************************************************************************* */ -void Class::pyxInitParentObj(FileWriter& pyxFile, const std::string& pyObj, - const std::string& cySharedObj, - const std::vector& allClasses) const { - if (parentClass) { - pyxFile.oss << pyObj << "." << parentClass->shared_pxd_obj_in_pyx() << " = " - << "<" << parentClass->shared_pxd_class_in_pyx() << ">(" - << cySharedObj << ")\n"; - // Find the parent class with name "parentClass" and point its cython obj - // to the same pointer - auto parent_it = find_if(allClasses.begin(), allClasses.end(), - [this](const Class& cls) { - return cls.pxdClassName() == - this->parentClass->pxdClassName(); - }); - if (parent_it == allClasses.end()) { - cerr << "Can't find parent class: " << parentClass->pxdClassName(); - throw std::runtime_error("Parent class not found!"); - } - parent_it->pyxInitParentObj(pyxFile, pyObj, cySharedObj, allClasses); - } -} - -/* ************************************************************************* */ -void Class::pyxDynamicCast(FileWriter& pyxFile, const Class& curLevel, - const std::vector& allClasses) const { - std::string me = this->pyxClassName(), sharedMe = this->shared_pxd_class_in_pyx(); - if (curLevel.parentClass) { - std::string parent = curLevel.parentClass->pyxClassName(), - parentObj = curLevel.parentClass->shared_pxd_obj_in_pyx(), - parentCythonClass = curLevel.parentClass->pxd_class_in_pyx(); - pyxFile.oss << "def dynamic_cast_" << me << "_" << parent << "(" << parent - << " parent):\n"; - pyxFile.oss << " try:\n"; - pyxFile.oss << " return " << me << ".cyCreateFromShared(<" << sharedMe - << ">dynamic_pointer_cast[" << pxd_class_in_pyx() << "," - << parentCythonClass << "](parent." << parentObj - << "))\n"; - pyxFile.oss << " except:\n"; - pyxFile.oss << " raise TypeError('dynamic cast failed!')\n"; - // Move up higher to one level: Find the parent class with name "parentClass" - auto parent_it = find_if(allClasses.begin(), allClasses.end(), - [&curLevel](const Class& cls) { - return cls.pxdClassName() == - curLevel.parentClass->pxdClassName(); - }); - if (parent_it == allClasses.end()) { - cerr << "Can't find parent class: " << parentClass->pxdClassName(); - throw std::runtime_error("Parent class not found!"); - } - pyxDynamicCast(pyxFile, *parent_it, allClasses); - } -} - -/* ************************************************************************* */ -void Class::emit_cython_pyx(FileWriter& pyxFile, const std::vector& allClasses) const { - pyxFile.oss << "cdef class " << pyxClassName(); - if (parentClass) pyxFile.oss << "(" << parentClass->pyxClassName() << ")"; - pyxFile.oss << ":\n"; - - // __init___ - pyxFile.oss << " def __init__(self, *args, **kwargs):\n"; - pyxFile.oss << " cdef list __params\n"; - pyxFile.oss << " self." << shared_pxd_obj_in_pyx() << " = " << shared_pxd_class_in_pyx() << "()\n"; - pyxFile.oss << " if len(args)==0 and len(kwargs)==1 and kwargs.has_key('cyCreateFromShared'):\n return\n"; - - // Constructors - constructor.emit_cython_pyx(pyxFile, *this); - pyxFile.oss << " if (self." << shared_pxd_obj_in_pyx() << ".use_count()==0):\n"; - pyxFile.oss << " raise TypeError('" << pyxClassName() - << " construction failed!')\n"; - pyxInitParentObj(pyxFile, " self", "self." + shared_pxd_obj_in_pyx(), allClasses); - pyxFile.oss << "\n"; - - // cyCreateFromShared - pyxFile.oss << " @staticmethod\n"; - pyxFile.oss << " cdef " << pyxClassName() << " cyCreateFromShared(const " - << shared_pxd_class_in_pyx() << "& other):\n" - << " if other.get() == NULL:\n" - << " raise RuntimeError('Cannot create object from a nullptr!')\n" - << " cdef " << pyxClassName() << " return_value = " << pyxClassName() << "(cyCreateFromShared=True)\n" - << " return_value." << shared_pxd_obj_in_pyx() << " = other\n"; - pyxInitParentObj(pyxFile, " return_value", "other", allClasses); - pyxFile.oss << " return return_value" << "\n\n"; - - for(const StaticMethod& m: static_methods | boost::adaptors::map_values) - m.emit_cython_pyx(pyxFile, *this); - if (static_methods.size()>0) pyxFile.oss << "\n"; - - for(const Method& m: methods_ | boost::adaptors::map_values) - m.emit_cython_pyx(pyxFile, *this); - - pyxDynamicCast(pyxFile, *this, allClasses); - - pyxFile.oss << "\n\n"; -} - -/* ************************************************************************* */ diff --git a/wrap/Class.h b/wrap/Class.h deleted file mode 100644 index 3df37fe67..000000000 --- a/wrap/Class.h +++ /dev/null @@ -1,315 +0,0 @@ -/* ---------------------------------------------------------------------------- - - * GTSAM Copyright 2010, Georgia Tech Research Corporation, - * Atlanta, Georgia 30332-0415 - * All Rights Reserved - * Authors: Frank Dellaert, et al. (see THANKS for the full author list) - - * See LICENSE for the license information - - * -------------------------------------------------------------------------- */ - -/** - * @file Class.h - * @brief describe the C++ class that is being wrapped - * @author Frank Dellaert - * @author Andrew Melim - * @author Richard Roberts - **/ - -#pragma once - -#include "spirit.h" -#include "Template.h" -#include "Constructor.h" -#include "Deconstructor.h" -#include "Method.h" -#include "StaticMethod.h" -#include "TemplateMethod.h" -#include "TypeAttributesTable.h" - -#ifdef __GNUC__ -#pragma GCC diagnostic push -#pragma GCC diagnostic ignored "-Wunused-variable" -#endif -#include -#include -#ifdef __GNUC__ -#pragma GCC diagnostic pop -#endif - -namespace bl = boost::lambda; - -#include -#include - -#include -#include - -namespace wrap { - -/// Class has name, constructors, methods -class Class: public Qualified { - -public: - typedef const std::string& Str; - typedef std::map Methods; - typedef std::map StaticMethods; - typedef std::map TemplateMethods; - -private: - - boost::optional parentClass; ///< The *single* parent - Methods methods_; ///< Class methods, including all expanded/instantiated template methods -- to be serialized to matlab and Python classes in Cython pyx - Methods nontemplateMethods_; ///< only nontemplate methods -- to be serialized into Cython pxd - TemplateMethods templateMethods_; ///< only template methods -- to be serialized into Cython pxd - // Method& mutableMethod(Str key); - -public: - - StaticMethods static_methods; ///< Static methods - - // Then the instance variables are set directly by the Module constructor - std::vector templateArgs; ///< Template arguments - std::string typedefName; ///< The name to typedef *from*, if this class is actually a typedef, i.e. typedef [typedefName] [name] - std::vector templateInstTypeList; ///< the original typelist used to instantiate this class from a template. - ///< Empty if it's not an instantiation. Needed for template classes in Cython pxd. - boost::optional templateClass = boost::none; ///< qualified name of the original template class from which this class was instantiated. - ///< boost::none if not an instantiation. Needed for template classes in Cython pxd. - bool isVirtual; ///< Whether the class is part of a virtual inheritance chain - bool isSerializable; ///< Whether we can use boost.serialization to serialize the class - creates exports - bool hasSerialization; ///< Whether we should create the serialization functions - Constructor constructor; ///< Class constructors - Deconstructor deconstructor; ///< Deconstructor to deallocate C++ object - bool verbose_; ///< verbose flag - std::string includeFile; - - /// Constructor creates an empty class - Class(bool verbose = true) : - parentClass(boost::none), isVirtual(false), isSerializable(false), hasSerialization( - false), deconstructor(verbose), verbose_(verbose) { - } - - Class(const std::string& name, bool verbose = true) - : Qualified(name, Qualified::Category::CLASS), - parentClass(boost::none), - isVirtual(false), - isSerializable(false), - hasSerialization(false), - deconstructor(verbose), - verbose_(verbose) {} - - void assignParent(const Qualified& parent); - - boost::optional qualifiedParent() const; - boost::optional getParent() const { return parentClass; } - - size_t nrMethods() const { - return methods_.size(); - } - - const Method& method(Str key) const; - - bool exists(Str name) const { - return methods_.find(name) != methods_.end(); - } - - // And finally MATLAB code is emitted, methods below called by Module::matlab_code - void matlab_proxy(Str toolboxPath, Str wrapperName, - const TypeAttributesTable& typeAttributes, FileWriter& wrapperFile, - std::vector& functionNames) const; ///< emit proxy class - - Class expandTemplate(const TemplateSubstitution& ts) const; - - std::vector expandTemplate(Str templateArg, - const std::vector& instantiations) const; - - // Create new classes with integer template arguments - std::vector expandTemplate(Str templateArg, - const std::vector& integers) const; - - /// Add potentially overloaded, potentially templated method - void addMethod(bool verbose, bool is_const, Str methodName, - const ArgumentList& argumentList, const ReturnValue& returnValue, - const Template& tmplate); - - /// Post-process classes for serialization markers - void erase_serialization(); // non-const ! - void erase_serialization(Methods& methods); // non-const ! - - /// verify all of the function arguments - void verifyAll(std::vector& functionNames, - bool& hasSerialiable) const; - - void appendInheritedMethods(const Class& cls, - const std::vector& classes); - - void removeInheritedNontemplateMethods(std::vector& classes); - - /// The typedef line for this class, if this class is a typedef, otherwise returns an empty string. - std::string getTypedef() const; - - /// Returns the string for an export flag - std::string getSerializationExport() const; - - /// Creates a member function that performs serialization - void serialization_fragments(FileWriter& proxyFile, FileWriter& wrapperFile, - Str wrapperName, std::vector& functionNames) const; - - /// Creates a static member function that performs deserialization - void deserialization_fragments(FileWriter& proxyFile, FileWriter& wrapperFile, - Str wrapperName, std::vector& functionNames) const; - - // emit python wrapper - void python_wrapper(FileWriter& wrapperFile) const; - - // emit cython wrapper - void emit_cython_pxd(FileWriter& pxdFile) const; - void emit_cython_wrapper_pxd(FileWriter& pxdFile) const; - void emit_cython_pyx(FileWriter& pyxFile, - const std::vector& allClasses) const; - void pyxInitParentObj(FileWriter& pyxFile, const std::string& pyObj, - const std::string& cySharedObj, - const std::vector& allClasses) const; - void pyxDynamicCast(FileWriter& pyxFile, const Class& curLevel, - const std::vector& allClasses) const; - - friend std::ostream& operator<<(std::ostream& os, const Class& cls) { - os << "class " << cls.name() << "{\n"; - os << cls.constructor << ";\n"; - for(const StaticMethod& m: cls.static_methods | boost::adaptors::map_values) - os << m << ";\n"; - for(const Method& m: cls.methods_ | boost::adaptors::map_values) - os << m << ";\n"; - os << "};" << std::endl; - return os; - } - -private: - - void pointer_constructor_fragments(FileWriter& proxyFile, - FileWriter& wrapperFile, Str wrapperName, - std::vector& functionNames) const; - - void comment_fragment(FileWriter& proxyFile) const; -}; - -/* ************************************************************************* */ -// http://boost-spirit.com/distrib/spirit_1_8_2/libs/spirit/doc/grammar.html -struct ClassGrammar: public classic::grammar { - - Class& cls_; ///< successful parse will be placed in here - Template& template_; ///< result needs to be visible outside - - /// Construct type grammar and specify where result is placed - ClassGrammar(Class& cls, Template& t) : - cls_(cls), template_(t) { - } - - /// Definition of type grammar - template - struct definition: BasicRules { - - using BasicRules::name_p; - using BasicRules::className_p; - using BasicRules::comments_p; - - // NOTE: allows for pointers to all types - ArgumentList args; - ArgumentListGrammar argumentList_g; - - Constructor constructor0, constructor; - - ReturnValue retVal0, retVal; - ReturnValueGrammar returnValue_g; - - Template methodTemplate; - TemplateGrammar methodTemplate_g, classTemplate_g; - - std::string methodName; - bool isConst, T, F; - - // Parent class - Qualified possibleParent; - TypeGrammar classParent_g; - - classic::rule constructor_p, methodName_p, method_p, - staticMethodName_p, static_method_p, templateList_p, classParent_p, - functions_p, class_p; - - definition(ClassGrammar const& self) : - argumentList_g(args), returnValue_g(retVal), // - methodTemplate_g(methodTemplate), classTemplate_g(self.template_), // - T(true), F(false), classParent_g(possibleParent) { - - using namespace classic; - bool verbose = false; // TODO - - // ConstructorGrammar - constructor_p = (className_p >> argumentList_g >> ';' >> !comments_p) // - [bl::bind(&Constructor::push_back, bl::var(constructor), - bl::var(args))] // - [clear_a(args)]; - - // MethodGrammar - methodName_p = lexeme_d[(upper_p | lower_p) >> *(alnum_p | '_')]; - - // gtsam::Values retract(const gtsam::VectorValues& delta) const; - method_p = !methodTemplate_g - >> (returnValue_g >> methodName_p[assign_a(methodName)] - >> argumentList_g >> !str_p("const")[assign_a(isConst, T)] >> ';' - >> *comments_p) // - [bl::bind(&Class::addMethod, bl::var(self.cls_), verbose, - bl::var(isConst), bl::var(methodName), bl::var(args), - bl::var(retVal), bl::var(methodTemplate))] // - [assign_a(retVal, retVal0)][clear_a(args)] // - [clear_a(methodTemplate)][assign_a(isConst, F)]; - - // StaticMethodGrammar - staticMethodName_p = lexeme_d[(upper_p | lower_p) >> *(alnum_p | '_')]; - - static_method_p = (str_p("static") >> returnValue_g - >> staticMethodName_p[assign_a(methodName)] >> argumentList_g >> ';' - >> *comments_p) // - [bl::bind(&StaticMethod::addOverload, - bl::var(self.cls_.static_methods)[bl::var(methodName)], - bl::var(methodName), bl::var(args), bl::var(retVal), boost::none, - verbose)] // - [assign_a(retVal, retVal0)][clear_a(args)]; - - // template - templateList_p = (str_p("template") >> '<' - >> name_p[push_back_a(self.cls_.templateArgs)] - >> *(',' >> name_p[push_back_a(self.cls_.templateArgs)]) >> '>'); - - // parse a full class - classParent_p = (':' >> classParent_g >> '{') // - [bl::bind(&Class::assignParent, bl::var(self.cls_), - bl::var(possibleParent))][clear_a(possibleParent)]; - - functions_p = constructor_p | method_p | static_method_p; - - // parse a full class - class_p = (!(classTemplate_g[push_back_a(self.cls_.templateArgs, - self.template_.argName())] | templateList_p) - >> !(str_p("virtual")[assign_a(self.cls_.isVirtual, T)]) - >> str_p("class") >> className_p[assign_a(self.cls_.name_)] - >> (classParent_p | '{') >> // - *(functions_p | comments_p) >> str_p("};")) // - [bl::bind(&Constructor::initializeOrCheck, bl::var(constructor), - bl::var(self.cls_.name_), boost::none, verbose)][assign_a( - self.cls_.constructor, constructor)] // - [assign_a(self.cls_.deconstructor.name, self.cls_.name_)] // - [assign_a(constructor, constructor0)]; - } - - classic::rule const& start() const { - return class_p; - } - - }; -}; -// ClassGrammar - -}// \namespace wrap - diff --git a/wrap/Constructor.cpp b/wrap/Constructor.cpp deleted file mode 100644 index 74719b289..000000000 --- a/wrap/Constructor.cpp +++ /dev/null @@ -1,160 +0,0 @@ -/* ---------------------------------------------------------------------------- - - * GTSAM Copyright 2010, Georgia Tech Research Corporation, - * Atlanta, Georgia 30332-0415 - * All Rights Reserved - * Authors: Frank Dellaert, et al. (see THANKS for the full author list) - - * See LICENSE for the license information - - * -------------------------------------------------------------------------- */ - -/** - * @file Constructor.ccp - * @author Frank Dellaert - * @author Andrew Melim - * @author Richard Roberts - **/ - -#include -#include -#include - -#include - -#include "utilities.h" -#include "Constructor.h" -#include "Class.h" - -using namespace std; -using namespace wrap; - -/* ************************************************************************* */ -string Constructor::matlab_wrapper_name(Str className) const { - string str = "new_" + className; - return str; -} - -/* ************************************************************************* */ -void Constructor::proxy_fragment(FileWriter& file, - const std::string& wrapperName, bool hasParent, - const int id, const ArgumentList args) const { - size_t nrArgs = args.size(); - // check for number of arguments... - file.oss << " elseif nargin == " << nrArgs; - if (nrArgs > 0) file.oss << " && "; - // ...and their types - bool first = true; - for (size_t i = 0; i < nrArgs; i++) { - if (!first) file.oss << " && "; - file.oss << "isa(varargin{" << i + 1 << "},'" << args[i].matlabClass(".") - << "')"; - first = false; - } - // emit code for calling constructor - if (hasParent) - file.oss << "\n [ my_ptr, base_ptr ] = "; - else - file.oss << "\n my_ptr = "; - file.oss << wrapperName << "(" << id; - // emit constructor arguments - for (size_t i = 0; i < nrArgs; i++) { - file.oss << ", "; - file.oss << "varargin{" << i + 1 << "}"; - } - file.oss << ");\n"; -} - -/* ************************************************************************* */ -string Constructor::wrapper_fragment(FileWriter& file, Str cppClassName, - Str matlabUniqueName, - boost::optional cppBaseClassName, - int id, const ArgumentList& al) const { - const string wrapFunctionName = - matlabUniqueName + "_constructor_" + boost::lexical_cast(id); - - file.oss << "void " << wrapFunctionName - << "(int nargout, mxArray *out[], int nargin, const mxArray *in[])" - << endl; - file.oss << "{\n"; - file.oss << " mexAtExit(&_deleteAllObjects);\n"; - // Typedef boost::shared_ptr - file.oss << " typedef boost::shared_ptr<" << cppClassName << "> Shared;\n"; - file.oss << "\n"; - - // Check to see if there will be any arguments and remove {} for consiseness - if (al.size() > 0) al.matlab_unwrap(file); // unwrap arguments - file.oss << " Shared *self = new Shared(new " << cppClassName << "(" - << al.names() << "));" << endl; - file.oss << " collector_" << matlabUniqueName << ".insert(self);\n"; - - if (verbose_) - file.oss << " std::cout << \"constructed \" << self << std::endl;" << endl; - file.oss - << " out[0] = mxCreateNumericMatrix(1, 1, mxUINT32OR64_CLASS, mxREAL);" - << endl; - file.oss << " *reinterpret_cast (mxGetData(out[0])) = self;" - << endl; - - // If we have a base class, return the base class pointer (MATLAB will call - // the base class collectorInsertAndMakeBase to add this to the collector and - // recurse the heirarchy) - if (cppBaseClassName) { - file.oss << "\n"; - file.oss << " typedef boost::shared_ptr<" << *cppBaseClassName - << "> SharedBase;\n"; - file.oss << " out[1] = mxCreateNumericMatrix(1, 1, mxUINT32OR64_CLASS, " - "mxREAL);\n"; - file.oss << " *reinterpret_cast(mxGetData(out[1])) = new " - "SharedBase(*self);\n"; - } - - file.oss << "}" << endl; - - return wrapFunctionName; -} - -/* ************************************************************************* */ -void Constructor::python_wrapper(FileWriter& wrapperFile, Str className) const { - wrapperFile.oss << " .def(\"" << name_ << "\", &" << className - << "::" << name_ << ");\n"; -} - -/* ************************************************************************* */ -bool Constructor::hasDefaultConstructor() const { - for (size_t i = 0; i < nrOverloads(); i++) { - if (argumentList(i).size() == 0) return true; - } - return false; -} - -/* ************************************************************************* */ -void Constructor::emit_cython_pxd(FileWriter& pxdFile, const Class& cls) const { - for (size_t i = 0; i < nrOverloads(); i++) { - ArgumentList args = argumentList(i); - - // generate the constructor - pxdFile.oss << " " << cls.pxdClassName() << "("; - args.emit_cython_pxd(pxdFile, cls.pxdClassName(), cls.templateArgs); - pxdFile.oss << ") " << "except +\n"; - } -} - -/* ************************************************************************* */ -void Constructor::emit_cython_pyx(FileWriter& pyxFile, const Class& cls) const { - for (size_t i = 0; i < nrOverloads(); i++) { - ArgumentList args = argumentList(i); - pyxFile.oss << " try:\n"; - pyxFile.oss << pyx_resolveOverloadParams(args, true, 3); - pyxFile.oss - << argumentList(i).pyx_convertEigenTypeAndStorageOrder(" "); - - pyxFile.oss << " self." << cls.shared_pxd_obj_in_pyx() << " = " - << cls.shared_pxd_class_in_pyx() << "(new " << cls.pxd_class_in_pyx() - << "(" << args.pyx_asParams() << "))\n"; - pyxFile.oss << " except (AssertionError, ValueError):\n"; - pyxFile.oss << " pass\n"; - } -} - -/* ************************************************************************* */ diff --git a/wrap/Constructor.h b/wrap/Constructor.h deleted file mode 100644 index 172cd24a4..000000000 --- a/wrap/Constructor.h +++ /dev/null @@ -1,99 +0,0 @@ -/* ---------------------------------------------------------------------------- - - * GTSAM Copyright 2010, Georgia Tech Research Corporation, - * Atlanta, Georgia 30332-0415 - * All Rights Reserved - * Authors: Frank Dellaert, et al. (see THANKS for the full author list) - - * See LICENSE for the license information - - * -------------------------------------------------------------------------- */ - -/** - * @file Constructor.h - * @brief class describing a constructor + code generation - * @author Frank Dellaert - * @author Richard Roberts - **/ - -#pragma once - -#include "OverloadedFunction.h" -#include -#include -#include - -namespace wrap { - -// Forward declaration -class Class; - -// Constructor class -struct Constructor: public OverloadedFunction { - - typedef const std::string& Str; - - /// Constructor creates an empty class - Constructor(bool verbose = false) { - verbose_ = verbose; - } - - Constructor expandTemplate(const TemplateSubstitution& ts) const { - Constructor inst = *this; - inst.argLists_ = expandArgumentListsTemplate(ts); - inst.name_ = ts.expandedClassName(); - return inst; - } - - /// return true if the default constructor exists - bool hasDefaultConstructor() const; - - // MATLAB code generation - // toolboxPath is main toolbox directory, e.g., ../matlab - // classFile is class proxy file, e.g., ../matlab/@Point2/Point2.m - - /// wrapper name - std::string matlab_wrapper_name(Str className) const; - - void comment_fragment(FileWriter& proxyFile) const { - if (nrOverloads() > 0) - proxyFile.oss << "%\n%-------Constructors-------\n"; - for (size_t i = 0; i < nrOverloads(); i++) { - proxyFile.oss << "%"; - argumentList(i).emit_prototype(proxyFile, name_); - proxyFile.oss << "\n"; - } - } - - /** - * Create fragment to select constructor in proxy class, e.g., - * if nargin == 2, obj.self = new_Pose3_RP(varargin{1},varargin{2}); end - */ - void proxy_fragment(FileWriter& file, Str wrapperName, bool hasParent, - const int id, const ArgumentList args) const; - - /// cpp wrapper - std::string wrapper_fragment(FileWriter& file, Str cppClassName, - Str matlabUniqueName, boost::optional cppBaseClassName, int id, - const ArgumentList& al) const; - - /// constructor function - void generate_construct(FileWriter& file, Str cppClassName, - std::vector& args_list) const; - - // emit python wrapper - void python_wrapper(FileWriter& wrapperFile, Str className) const; - - // emit cython wrapper - void emit_cython_pxd(FileWriter& pxdFile, const Class& cls) const; - void emit_cython_pyx(FileWriter& pyxFile, const Class& cls) const; - - friend std::ostream& operator<<(std::ostream& os, const Constructor& m) { - for (size_t i = 0; i < m.nrOverloads(); i++) - os << m.name_ << m.argLists_[i]; - return os; - } - -}; - -} // \namespace wrap diff --git a/wrap/Deconstructor.cpp b/wrap/Deconstructor.cpp deleted file mode 100644 index 7bb366e3f..000000000 --- a/wrap/Deconstructor.cpp +++ /dev/null @@ -1,73 +0,0 @@ -/* ---------------------------------------------------------------------------- - - * GTSAM Copyright 2010, Georgia Tech Research Corporation, - * Atlanta, Georgia 30332-0415 - * All Rights Reserved - * Authors: Frank Dellaert, et al. (see THANKS for the full author list) - - * See LICENSE for the license information - - * -------------------------------------------------------------------------- */ - -/** - * @file Deconstructor.ccp - * @author Frank Dellaert - * @author Andrew Melim - * @author Richard Roberts - **/ - -#include -#include - -#include - -#include "utilities.h" -#include "Deconstructor.h" - -using namespace std; -using namespace wrap; - -/* ************************************************************************* */ -string Deconstructor::matlab_wrapper_name(const string& className) const { - string str = "delete_" + className; - return str; -} - -/* ************************************************************************* */ -void Deconstructor::proxy_fragment(FileWriter& file, - const std::string& wrapperName, - const std::string& matlabUniqueName, int id) const { - - file.oss << " function delete(obj)\n"; - file.oss << " " << wrapperName << "(" << id << ", obj.ptr_" << matlabUniqueName << ");\n"; - file.oss << " end\n"; -} - -/* ************************************************************************* */ -string Deconstructor::wrapper_fragment(FileWriter& file, - const string& cppClassName, - const string& matlabUniqueName, - int id) const { - - const string matlabName = matlab_wrapper_name(matlabUniqueName); - - const string wrapFunctionName = matlabUniqueName + "_deconstructor_" + boost::lexical_cast(id); - - file.oss << "void " << wrapFunctionName << "(int nargout, mxArray *out[], int nargin, const mxArray *in[])" << endl; - file.oss << "{" << endl; - file.oss << " typedef boost::shared_ptr<" << cppClassName << "> Shared;" << endl; - //Deconstructor takes 1 arg, the mxArray obj - file.oss << " checkArguments(\"" << matlabName << "\",nargout,nargin," << "1" << ");" << endl; - file.oss << " Shared *self = *reinterpret_cast(mxGetData(in[0]));\n"; - file.oss << " Collector_" << matlabUniqueName << "::iterator item;\n"; - file.oss << " item = collector_" << matlabUniqueName << ".find(self);\n"; - file.oss << " if(item != collector_" << matlabUniqueName << ".end()) {\n"; - file.oss << " delete self;\n"; - file.oss << " collector_" << matlabUniqueName << ".erase(item);\n"; - file.oss << " }\n"; - file.oss << "}" << endl; - - return wrapFunctionName; -} - -/* ************************************************************************* */ diff --git a/wrap/Deconstructor.h b/wrap/Deconstructor.h deleted file mode 100644 index ee2f4ea19..000000000 --- a/wrap/Deconstructor.h +++ /dev/null @@ -1,61 +0,0 @@ -/* ---------------------------------------------------------------------------- - - * GTSAM Copyright 2010, Georgia Tech Research Corporation, - * Atlanta, Georgia 30332-0415 - * All Rights Reserved - * Authors: Frank Dellaert, et al. (see THANKS for the full author list) - - * See LICENSE for the license information - - * -------------------------------------------------------------------------- */ - -/** - * @file Deconstructor.h - * @brief class describing a constructor + code generation - * @author Frank Dellaert - * @author Andrew Melim - * @author Richard Roberts - **/ - -#pragma once - -#include -#include - -#include "Argument.h" - -namespace wrap { - -// Deconstructor class -struct Deconstructor { - - /// Deconstructor creates an empty class - Deconstructor(bool verbose = true) : - verbose_(verbose) { - } - - // Then the instance variables are set directly by the Module deconstructor - std::string name; - bool verbose_; - - // MATLAB code generation - // toolboxPath is main toolbox directory, e.g., ../matlab - // classFile is class proxy file, e.g., ../matlab/@Point2/Point2.m - - /// wrapper name - std::string matlab_wrapper_name(const std::string& className) const; - - /// m-file - void proxy_fragment(FileWriter& file, - const std::string& wrapperName, - const std::string& matlabUniqueName, int id) const; - - /// cpp wrapper - std::string wrapper_fragment(FileWriter& file, - const std::string& cppClassName, - const std::string& matlabUniqueName, - int id) const; -}; - -} // \namespace wrap - diff --git a/wrap/FileWriter.cpp b/wrap/FileWriter.cpp deleted file mode 100644 index c07de0eb0..000000000 --- a/wrap/FileWriter.cpp +++ /dev/null @@ -1,52 +0,0 @@ -/** - * @file FileWriter.cpp - * - * @date Jan 15, 2012 - * @author Alex Cunningham - */ - -#include "FileWriter.h" -#include "utilities.h" - -#include -#include - -using namespace std; -using namespace wrap; - -/* ************************************************************************* */ -FileWriter::FileWriter(const string& filename, bool verbose, - const string& comment_str) : - verbose_(verbose), filename_(filename), comment_str_(comment_str) { -} - -/* ************************************************************************* */ -void FileWriter::emit(bool add_header, bool force_overwrite) const { - if (verbose_) - cerr << "generating " << filename_ << " "; - // read in file if it exists - string existing_contents; - bool file_exists = true; - try { - existing_contents = file_contents(filename_.c_str(), add_header); - } catch (const CantOpenFile& ) { - file_exists = false; - } - - // Only write a file if it is new, an update, or overwrite is forced - string new_contents = oss.str(); - if (force_overwrite || !file_exists || existing_contents != new_contents) { - // Binary to use LF line endings instead of CRLF - ofstream ofs(filename_.c_str(), ios::binary); - if (!ofs) - throw CantOpenFile(filename_); - - // dump in stringstream - ofs << new_contents; - ofs.close(); - } - if (verbose_) - cerr << " ...no update" << endl; -} -/* ************************************************************************* */ - diff --git a/wrap/FileWriter.h b/wrap/FileWriter.h deleted file mode 100644 index 12e033fdf..000000000 --- a/wrap/FileWriter.h +++ /dev/null @@ -1,35 +0,0 @@ -/** - * @file FileWriter.h - * - * @brief Wrapper for writing files and avoiding overwriting existing files - * This class wraps a stream object and will check that the file is - * actually different to write the new generated file. - * - * @date Jan 15, 2012 - * @author Alex Cunningham - */ - -#pragma once - -#include - -namespace wrap { - -class FileWriter { -protected: - bool verbose_; - std::string filename_; - std::string comment_str_; - -public: - std::ostringstream oss; ///< Primary stream for operating on the file - - /** Create a writer with a filename and delimiter for the header comment */ - FileWriter(const std::string& filename, bool verbose, const std::string& comment_str); - - /** Writes the contents of the stringstream to the file, checking if actually new */ - void emit(bool add_header, bool force=false) const; - -}; - -} // \namespace wrap diff --git a/wrap/ForwardDeclaration.h b/wrap/ForwardDeclaration.h deleted file mode 100644 index 190387ecc..000000000 --- a/wrap/ForwardDeclaration.h +++ /dev/null @@ -1,36 +0,0 @@ -/* ---------------------------------------------------------------------------- - - * GTSAM Copyright 2010, Georgia Tech Research Corporation, - * Atlanta, Georgia 30332-0415 - * All Rights Reserved - * Authors: Frank Dellaert, et al. (see THANKS for the full author list) - - * See LICENSE for the license information - - * -------------------------------------------------------------------------- */ - -/** - * @file Class.h - * @brief describe the C++ class that is being wrapped - * @author Frank Dellaert - * @author Andrew Melim - * @author Richard Roberts - **/ - -#pragma once - -#include - -namespace wrap { - - class Class; - - struct ForwardDeclaration { - Class cls; - bool isVirtual; - ForwardDeclaration() : isVirtual(false) {} - explicit ForwardDeclaration(const std::string& s) : cls(s), isVirtual(false) {} - std::string name() const { return cls.qualifiedName("::"); } - }; - -} diff --git a/wrap/FullyOverloadedFunction.cpp b/wrap/FullyOverloadedFunction.cpp deleted file mode 100644 index 4db4c8713..000000000 --- a/wrap/FullyOverloadedFunction.cpp +++ /dev/null @@ -1,34 +0,0 @@ -#include "FullyOverloadedFunction.h" - -using namespace std; - -namespace wrap { -const std::array FullyOverloadedFunction::pythonKeywords{ - {"print", "lambda"}}; - -/* ************************************************************************* */ -std::string FullyOverloadedFunction::pyx_functionCall( - const std::string& caller, - const std::string& funcName, size_t iOverload) const { - - string ret; - if (!returnVals_[iOverload].isPair && !returnVals_[iOverload].type1.isPtr && - returnVals_[iOverload].type1.isNonBasicType()) { - ret = returnVals_[iOverload].type1.make_shared_pxd_class_in_pyx() + "("; - } - - // actual function call ... - if (!caller.empty()) ret += caller + "."; - ret += funcName; - if (templateArgValue_) ret += "[" + templateArgValue_->pxd_class_in_pyx() + "]"; - //... with argument list - ret += "(" + argumentList(iOverload).pyx_asParams() + ")"; - - if (!returnVals_[iOverload].isPair && !returnVals_[iOverload].type1.isPtr && - returnVals_[iOverload].type1.isNonBasicType()) - ret += ")"; - - return ret; -} - -} diff --git a/wrap/FullyOverloadedFunction.h b/wrap/FullyOverloadedFunction.h deleted file mode 100644 index 6b40f6a70..000000000 --- a/wrap/FullyOverloadedFunction.h +++ /dev/null @@ -1,147 +0,0 @@ -/* ---------------------------------------------------------------------------- - - * GTSAM Copyright 2010, Georgia Tech Research Corporation, - * Atlanta, Georgia 30332-0415 - * All Rights Reserved - * Authors: Frank Dellaert, et al. (see THANKS for the full author list) - - * See LICENSE for the license information - - * -------------------------------------------------------------------------- */ - -/** - * @file FullyOverloadedFunction.h - * @brief Function that can be fully overloaded: arguments and return values - * @author Frank Dellaert - * @date Nov 13, 2014 - **/ - -#pragma once - -#include "OverloadedFunction.h" -#include - -namespace wrap { - -/** - * Signature Overload (including return value) - */ -class SignatureOverloads: public ArgumentOverloads { - -public: - - std::vector returnVals_; - -public: - - const ReturnValue& returnValue(size_t i) const { - return returnVals_.at(i); - } - - void push_back(const ArgumentList& args, const ReturnValue& retVal) { - argLists_.push_back(args); - returnVals_.push_back(retVal); - } - - void verifyReturnTypes(const std::vector& validtypes, - const std::string& s) const { - for(const ReturnValue& retval: returnVals_) { - retval.type1.verify(validtypes, s); - if (retval.isPair) - retval.type2.verify(validtypes, s); - } - } - - // TODO use transform ? - std::vector expandReturnValuesTemplate( - const TemplateSubstitution& ts) const { - std::vector result; - for(const ReturnValue& retVal: returnVals_) { - ReturnValue instRetVal = retVal.expandTemplate(ts); - result.push_back(instRetVal); - } - return result; - } - - /// Expand templates, imperative ! - void expandTemplate(const TemplateSubstitution& ts) { - // substitute template in arguments - argLists_ = expandArgumentListsTemplate(ts); - // do the same for return types - returnVals_ = expandReturnValuesTemplate(ts); - } - - // emit a list of comments, one for each overload - void usage_fragment(FileWriter& proxyFile, const std::string& name) const { - unsigned int argLCount = 0; - for(ArgumentList argList: argLists_) { - argList.emit_prototype(proxyFile, name); - if (argLCount != nrOverloads() - 1) - proxyFile.oss << ", "; - else - proxyFile.oss << " : returns " << returnValue(0).returnType() - << std::endl; - argLCount++; - } - } - - // emit a list of comments, one for each overload - void comment_fragment(FileWriter& proxyFile, const std::string& name) const { - size_t i = 0; - for(ArgumentList argList: argLists_) { - proxyFile.oss << "%"; - argList.emit_prototype(proxyFile, name); - proxyFile.oss << " : returns " << returnVals_[i++].returnType() - << std::endl; - } - } - - friend std::ostream& operator<<(std::ostream& os, - const SignatureOverloads& overloads) { - for (size_t i = 0; i < overloads.nrOverloads(); i++) - os << overloads.returnVals_[i] << overloads.argLists_[i] << std::endl; - return os; - } - -}; - -class FullyOverloadedFunction: public Function, public SignatureOverloads { - -public: - - bool addOverload(const std::string& name, const ArgumentList& args, - const ReturnValue& retVal, boost::optional instName = - boost::none, bool verbose = false) { - bool first = initializeOrCheck(name, instName, verbose); - SignatureOverloads::push_back(args, retVal); - return first; - } - - // emit cython pyx function call - std::string pyx_functionCall(const std::string& caller, const std::string& funcName, - size_t iOverload) const; - - /// Cython: Rename functions which names are python keywords - static const std::array pythonKeywords; - static std::string pyRename(const std::string& name) { - if (std::find(pythonKeywords.begin(), pythonKeywords.end(), name) == - pythonKeywords.end()) - return name; - else - return name + "_"; - } -}; - -// Templated checking functions -// TODO: do this via polymorphism, use transform ? - -template -inline void verifyReturnTypes(const std::vector& validTypes, - const std::map& vt) { - typedef typename std::map::value_type NamedMethod; - for(const NamedMethod& namedMethod: vt) - namedMethod.second.verifyReturnTypes(validTypes); -} - -} // \namespace wrap - diff --git a/wrap/Function.cpp b/wrap/Function.cpp deleted file mode 100644 index 80b0adbbe..000000000 --- a/wrap/Function.cpp +++ /dev/null @@ -1,78 +0,0 @@ -/* ---------------------------------------------------------------------------- - - * GTSAM Copyright 2010, Georgia Tech Research Corporation, - * Atlanta, Georgia 30332-0415 - * All Rights Reserved - * Authors: Frank Dellaert, et al. (see THANKS for the full author list) - - * See LICENSE for the license information - - * -------------------------------------------------------------------------- */ - -/** - * @file Function.ccp - * @author Frank Dellaert - * @date Nov 13, 2014 - **/ - -#include "Function.h" -#include "utilities.h" - -#include -#include - -#include -#include - -using namespace std; -using namespace wrap; - -/* ************************************************************************* */ -bool Function::initializeOrCheck(const string& name, - boost::optional instName, bool verbose) { - - if (name.empty()) - throw runtime_error("Function::initializeOrCheck called with empty name"); - - // Check if this overload is give to the correct method - if (name_.empty()) { - name_ = name; - templateArgValue_ = instName; - verbose_ = verbose; - return true; - } else { - if (name_ != name || verbose_ != verbose - || ((bool) templateArgValue_ != (bool) instName) - || ((bool) templateArgValue_ && (bool) instName - && !(*templateArgValue_ == *instName))) - throw runtime_error( - "Function::initializeOrCheck called with different arguments"); - - return false; - } -} - -/* ************************************************************************* */ -void Function::emit_call(FileWriter& proxyFile, const ReturnValue& returnVal, - const string& wrapperName, int id) const { - returnVal.emit_matlab(proxyFile); - proxyFile.oss << wrapperName << "(" << id; - if (!isStatic()) - proxyFile.oss << ", this"; - proxyFile.oss << ", varargin{:});\n"; -} - -/* ************************************************************************* */ -void Function::emit_conditional_call(FileWriter& proxyFile, - const ReturnValue& returnVal, const ArgumentList& args, - const string& wrapperName, int id) const { - - // Check all arguments - args.proxy_check(proxyFile); - - // output call to C++ wrapper - proxyFile.oss << " "; - emit_call(proxyFile, returnVal, wrapperName, id); -} - -/* ************************************************************************* */ diff --git a/wrap/Function.h b/wrap/Function.h deleted file mode 100644 index c39b3231c..000000000 --- a/wrap/Function.h +++ /dev/null @@ -1,73 +0,0 @@ -/* ---------------------------------------------------------------------------- - - * GTSAM Copyright 2010, Georgia Tech Research Corporation, - * Atlanta, Georgia 30332-0415 - * All Rights Reserved - * Authors: Frank Dellaert, et al. (see THANKS for the full author list) - - * See LICENSE for the license information - - * -------------------------------------------------------------------------- */ - -/** - * @file Function.h - * @brief Base class for global functions and methods - * @author Frank Dellaert - * @date Nov 13, 2014 - **/ - -#pragma once - -#include "Argument.h" -#include - -namespace wrap { - -/// Function class -class Function { - -protected: - - std::string name_; ///< name of method - boost::optional templateArgValue_; ///< value of template argument if applicable - bool verbose_; - -public: - - /** - * @brief first time, fill in instance variables, otherwise check if same - * @return true if first time, false thereafter - */ - bool initializeOrCheck(const std::string& name, - boost::optional instName = boost::none, bool verbose = - false); - - std::string name() const { - return name_; - } - - /// Only Methods are non-static - virtual bool isStatic() const { - return true; - } - - std::string matlabName() const { - if (templateArgValue_) - return name_ + templateArgValue_->name(); - else - return name_; - } - - /// Emit function call to MATLAB (no argument checking) - void emit_call(FileWriter& proxyFile, const ReturnValue& returnVal, - const std::string& wrapperName, int id) const; - - /// Emit checking arguments and function call to MATLAB - void emit_conditional_call(FileWriter& proxyFile, - const ReturnValue& returnVal, const ArgumentList& args, - const std::string& wrapperName, int id) const; - -}; - -} // \namespace wrap - diff --git a/wrap/GlobalFunction.cpp b/wrap/GlobalFunction.cpp deleted file mode 100644 index 02ab19657..000000000 --- a/wrap/GlobalFunction.cpp +++ /dev/null @@ -1,227 +0,0 @@ -/** - * @file GlobalFunction.cpp - * - * @date Jul 22, 2012 - * @author Alex Cunningham - */ - -#include "GlobalFunction.h" -#include "Class.h" -#include "utilities.h" - -#include - -namespace wrap { - -using namespace std; - -/* ************************************************************************* */ -void GlobalFunction::addOverload(const Qualified& overload, - const ArgumentList& args, const ReturnValue& retVal, const std::string& _includeFile, - boost::optional instName, bool verbose) { - FullyOverloadedFunction::addOverload(overload.name(), args, retVal, instName, - verbose); - overloads.push_back(overload); - includeFile = _includeFile; -} - -/* ************************************************************************* */ -void GlobalFunction::matlab_proxy(const string& toolboxPath, - const string& wrapperName, const TypeAttributesTable& typeAttributes, - FileWriter& file, vector& functionNames) const { - - // cluster overloads with same namespace - // create new GlobalFunction structures around namespaces - same namespaces and names are overloads - // map of namespace to global function - typedef map GlobalFunctionMap; - GlobalFunctionMap grouped_functions; - for (size_t i = 0; i < overloads.size(); ++i) { - Qualified overload = overloads.at(i); - // use concatenated namespaces as key - string str_ns = qualifiedName("", overload.namespaces()); - const ReturnValue& ret = returnValue(i); - const ArgumentList& args = argumentList(i); - grouped_functions[str_ns].addOverload(overload, args, ret); - } - - size_t lastcheck = grouped_functions.size(); - for(const GlobalFunctionMap::value_type& p: grouped_functions) { - p.second.generateSingleFunction(toolboxPath, wrapperName, typeAttributes, - file, functionNames); - if (--lastcheck != 0) - file.oss << endl; - } -} - -/* ************************************************************************* */ -void GlobalFunction::generateSingleFunction(const string& toolboxPath, - const string& wrapperName, const TypeAttributesTable& typeAttributes, - FileWriter& file, vector& functionNames) const { - - // create the folder for the namespace - const Qualified& overload1 = overloads.front(); - createNamespaceStructure(overload1.namespaces(), toolboxPath); - - // open destination mfunctionFileName - string mfunctionFileName = overload1.matlabName(toolboxPath); - FileWriter mfunctionFile(mfunctionFileName, verbose_, "%"); - - // get the name of actual matlab object - const string matlabQualName = overload1.qualifiedName("."); - const string matlabUniqueName = overload1.qualifiedName(""); - const string cppName = overload1.qualifiedName("::"); - - mfunctionFile.oss << "function varargout = " << name_ << "(varargin)\n"; - - for (size_t i = 0; i < nrOverloads(); ++i) { - const ArgumentList& args = argumentList(i); - const ReturnValue& returnVal = returnValue(i); - - const int id = functionNames.size(); - - // Output proxy matlab code - mfunctionFile.oss << " " << (i == 0 ? "" : "else"); - emit_conditional_call(mfunctionFile, returnVal, args, wrapperName, id); - - // Output C++ wrapper code - - const string wrapFunctionName = matlabUniqueName + "_" - + boost::lexical_cast(id); - - // call - file.oss << "void " << wrapFunctionName - << "(int nargout, mxArray *out[], int nargin, const mxArray *in[])\n"; - // start - file.oss << "{\n"; - - // check arguments - // NOTE: for static functions, there is no object passed - file.oss << " checkArguments(\"" << matlabUniqueName - << "\",nargout,nargin," << args.size() << ");\n"; - - // unwrap arguments, see Argument.cpp - args.matlab_unwrap(file, 0); // We start at 0 because there is no self object - - // call method with default type and wrap result - if (returnVal.type1.name() != "void") - returnVal.wrap_result(cppName + "(" + args.names() + ")", file, - typeAttributes); - else - file.oss << cppName + "(" + args.names() + ");\n"; - - // finish - file.oss << "}\n"; - - // Add to function list - functionNames.push_back(wrapFunctionName); - } - - mfunctionFile.oss << " else\n"; - mfunctionFile.oss - << " error('Arguments do not match any overload of function " - << matlabQualName << "');" << endl; - mfunctionFile.oss << " end" << endl; - - // Close file - mfunctionFile.emit(true); -} - -/* ************************************************************************* */ -void GlobalFunction::python_wrapper(FileWriter& wrapperFile) const { - wrapperFile.oss << "def(\"" << name_ << "\", " << name_ << ");\n"; -} - -/* ************************************************************************* */ -void GlobalFunction::emit_cython_pxd(FileWriter& file) const { - file.oss << "cdef extern from \"" << includeFile << "\" namespace \"" - << overloads[0].qualifiedNamespaces("::") - << "\":" << endl; - for (size_t i = 0; i < nrOverloads(); ++i) { - file.oss << " "; - returnVals_[i].emit_cython_pxd(file, "", vector()); - file.oss << pxdName() + " \"" + overloads[0].qualifiedName("::") + - "\"("; - argumentList(i).emit_cython_pxd(file, "", vector()); - file.oss << ")"; - file.oss << " except +"; - file.oss << "\n"; - } -} - -/* ************************************************************************* */ -void GlobalFunction::emit_cython_pyx_no_overload(FileWriter& file) const { - string funcName = pyxName(); - - // Function definition - file.oss << "def " << funcName; - - // modify name of function instantiation as python doesn't allow overloads - // e.g. template funcName(...) --> funcNameA, funcNameB, funcNameC - if (templateArgValue_) file.oss << templateArgValue_->pyxClassName(); - - // funtion arguments - file.oss << "("; - argumentList(0).emit_cython_pyx(file); - file.oss << "):\n"; - - /// Call cython corresponding function and return - file.oss << argumentList(0).pyx_convertEigenTypeAndStorageOrder(" "); - string ret = pyx_functionCall("", pxdName(), 0); - if (!returnVals_[0].isVoid()) { - file.oss << " cdef " << returnVals_[0].pyx_returnType() - << " ret = " << ret << "\n"; - file.oss << " return " << returnVals_[0].pyx_casting("ret") << "\n"; - } else { - file.oss << " " << ret << "\n"; - } -} - -/* ************************************************************************* */ -void GlobalFunction::emit_cython_pyx(FileWriter& file) const { - string funcName = pyxName(); - - size_t N = nrOverloads(); - if (N == 1) { - emit_cython_pyx_no_overload(file); - return; - } - - // Dealing with overloads.. - file.oss << "def " << funcName << "(*args, **kwargs):\n"; - for (size_t i = 0; i < N; ++i) { - file.oss << " success, results = " << funcName << "_" << i - << "(args, kwargs)\n"; - file.oss << " if success:\n return results\n"; - } - file.oss << " raise TypeError('Could not find the correct overload')\n"; - - for (size_t i = 0; i < N; ++i) { - ArgumentList args = argumentList(i); - file.oss << "def " + funcName + "_" + to_string(i) + "(args, kwargs):\n"; - file.oss << " cdef list __params\n"; - if (!returnVals_[i].isVoid()) { - file.oss << " cdef " << returnVals_[i].pyx_returnType() << " return_value\n"; - } - file.oss << " try:\n"; - file.oss << pyx_resolveOverloadParams(args, false, 2); // lazy: always return None even if it's a void function - - /// Call corresponding cython function - file.oss << argumentList(i).pyx_convertEigenTypeAndStorageOrder(" "); - // catch exception which indicates the parameters passed are incorrect. - file.oss << " except:\n"; - file.oss << " return False, None\n\n"; - - string call = pyx_functionCall("", pxdName(), i); - if (!returnVals_[i].isVoid()) { - file.oss << " return_value = " << call << "\n"; - file.oss << " return True, " << returnVals_[i].pyx_casting("return_value") << "\n"; - } else { - file.oss << " " << call << "\n"; - file.oss << " return True, None\n"; - } - } -} -/* ************************************************************************* */ - -} // \namespace wrap - diff --git a/wrap/GlobalFunction.h b/wrap/GlobalFunction.h deleted file mode 100644 index 099cefa70..000000000 --- a/wrap/GlobalFunction.h +++ /dev/null @@ -1,148 +0,0 @@ -/** - * @file GlobalFunction.h - * - * @brief Implements codegen for a global function wrapped in matlab - * - * @date Jul 22, 2012 - * @author Alex Cunningham - */ - -#pragma once - -#include "FullyOverloadedFunction.h" - -#ifdef __GNUC__ -#pragma GCC diagnostic push -#pragma GCC diagnostic ignored "-Wunused-variable" -#endif -#include -#include -#ifdef __GNUC__ -#pragma GCC diagnostic pop -#endif - -namespace bl = boost::lambda; - -namespace wrap { - -struct GlobalFunction: public FullyOverloadedFunction { - - std::vector overloads; ///< Stack of qualified names - std::string includeFile; - - // adds an overloaded version of this function, - void addOverload(const Qualified& overload, const ArgumentList& args, - const ReturnValue& retVal, const std::string& _includeFile = "", boost::optional instName = - boost::none, bool verbose = false); - - void verifyArguments(const std::vector& validArgs) const { - SignatureOverloads::verifyArguments(validArgs, name_); - } - - void verifyReturnTypes(const std::vector& validtypes) const { - SignatureOverloads::verifyReturnTypes(validtypes, name_); - } - - // codegen function called from Module to build the cpp and matlab versions of the function - void matlab_proxy(const std::string& toolboxPath, - const std::string& wrapperName, const TypeAttributesTable& typeAttributes, - FileWriter& file, std::vector& functionNames) const; - - // emit python wrapper - void python_wrapper(FileWriter& wrapperFile) const; - - // function name in Cython pxd - std::string pxdName() const { return "pxd_" + pyRename(name_); } - // function name in Python pyx - std::string pyxName() const { - std::string result = ""; - for(size_t i=0; i= 1) { - result += (overloads[0].namespaces_[i] + "_"); - } - } - result += pyRename(name_); - return result; - } - - // emit cython wrapper - void emit_cython_pxd(FileWriter& pxdFile) const; - void emit_cython_pyx(FileWriter& pyxFile) const; - void emit_cython_pyx_no_overload(FileWriter& pyxFile) const; - -private: - - // Creates a single global function - all in same namespace - void generateSingleFunction(const std::string& toolboxPath, - const std::string& wrapperName, const TypeAttributesTable& typeAttributes, - FileWriter& file, std::vector& functionNames) const; - -}; - -typedef std::map GlobalFunctions; - -/* ************************************************************************* */ -// http://boost-spirit.com/distrib/spirit_1_8_2/libs/spirit/doc/grammar.html -struct GlobalFunctionGrammar: public classic::grammar { - - GlobalFunctions& global_functions_; ///< successful parse will be placed in here - std::vector& namespaces_; - std::string& includeFile; - - /// Construct type grammar and specify where result is placed - GlobalFunctionGrammar(GlobalFunctions& global_functions, - std::vector& namespaces, - std::string& includeFile) - : global_functions_(global_functions), - namespaces_(namespaces), - includeFile(includeFile) {} - - /// Definition of type grammar - template - struct definition: BasicRules { - -// using BasicRules::name_p; -// using BasicRules::className_p; - using BasicRules::comments_p; - - ArgumentList args; - ArgumentListGrammar argumentList_g; - - ReturnValue retVal0, retVal; - ReturnValueGrammar returnValue_g; - - Qualified globalFunction; - - classic::rule globalFunctionName_p, global_function_p; - - definition(GlobalFunctionGrammar const& self) : - argumentList_g(args), returnValue_g(retVal) { - - using namespace classic; - bool verbose = false; // TODO - - globalFunctionName_p = lexeme_d[(upper_p | lower_p) >> *(alnum_p | '_')]; - - // parse a global function - global_function_p = (returnValue_g >> globalFunctionName_p[assign_a( - globalFunction.name_)] >> - argumentList_g >> ';' >> *comments_p) // - [assign_a(globalFunction.namespaces_, self.namespaces_)] // - [bl::bind( - &GlobalFunction::addOverload, - bl::var(self.global_functions_)[bl::var(globalFunction.name_)], - bl::var(globalFunction), bl::var(args), bl::var(retVal), bl::var(self.includeFile), - boost::none, verbose)] // - [assign_a(retVal, retVal0)][clear_a(globalFunction)][clear_a(args)]; - } - - classic::rule const& start() const { - return global_function_p; - } - - }; -}; -// GlobalFunctionGrammar - -}// \namespace wrap - diff --git a/wrap/Method.cpp b/wrap/Method.cpp deleted file mode 100644 index 2a4b0b3af..000000000 --- a/wrap/Method.cpp +++ /dev/null @@ -1,205 +0,0 @@ -/* ---------------------------------------------------------------------------- - - * GTSAM Copyright 2010, Georgia Tech Research Corporation, - * Atlanta, Georgia 30332-0415 - * All Rights Reserved - * Authors: Frank Dellaert, et al. (see THANKS for the full author list) - - * See LICENSE for the license information - - * -------------------------------------------------------------------------- */ - -/** - * @file Method.ccp - * @author Frank Dellaert - * @author Richard Roberts - **/ - -#include "Method.h" -#include "Class.h" -#include "utilities.h" - -#include -#include - -#include -#include - -using namespace std; -using namespace wrap; - -/* ************************************************************************* */ -bool Method::addOverload(Str name, const ArgumentList& args, - const ReturnValue& retVal, bool is_const, - boost::optional instName, - bool verbose) { - bool first = MethodBase::addOverload(name, args, retVal, instName, verbose); - if (first) - is_const_ = is_const; - else if (is_const && !is_const_) - throw std::runtime_error( - "Method::addOverload: " + name + - " now designated as const whereas before it was not"); - else if (!is_const && is_const_) - throw std::runtime_error( - "Method::addOverload: " + name + - " now designated as non-const whereas before it was"); - return first; -} - -/* ************************************************************************* */ -void Method::proxy_header(FileWriter& proxyFile) const { - proxyFile.oss << " function varargout = " << matlabName() - << "(this, varargin)\n"; -} - -/* ************************************************************************* */ -string Method::wrapper_call(FileWriter& wrapperFile, Str cppClassName, - Str matlabUniqueName, - const ArgumentList& args) const { - // check arguments - // extra argument obj -> nargin-1 is passed ! - // example: checkArguments("equals",nargout,nargin-1,2); - wrapperFile.oss << " checkArguments(\"" << matlabName() - << "\",nargout,nargin-1," << args.size() << ");\n"; - - // get class pointer - // example: auto obj = unwrap_shared_ptr< Test >(in[0], "Test"); - wrapperFile.oss << " auto obj = unwrap_shared_ptr<" << cppClassName - << ">(in[0], \"ptr_" << matlabUniqueName << "\");" << endl; - - // unwrap arguments, see Argument.cpp, we start at 1 as first is obj - args.matlab_unwrap(wrapperFile, 1); - - // call method and wrap result - // example: out[0]=wrap(obj->return_field(t)); - string expanded = "obj->" + name_; - if (templateArgValue_) - expanded += ("<" + templateArgValue_->qualifiedName("::") + ">"); - - return expanded; -} - -/* ************************************************************************* */ -void Method::emit_cython_pxd(FileWriter& file, const Class& cls) const { - for (size_t i = 0; i < nrOverloads(); ++i) { - file.oss << " "; - returnVals_[i].emit_cython_pxd(file, cls.pxdClassName(), cls.templateArgs); - const string renamed = pyRename(name_); - if (renamed != name_) { - file.oss << pyRename(name_) + " \"" + name_ + "\"" << "("; - } else { - file.oss << name_ << "("; - } - argumentList(i).emit_cython_pxd(file, cls.pxdClassName(), cls.templateArgs); - file.oss << ")"; - // if (is_const_) file.oss << " const"; - file.oss << " except +"; - file.oss << "\n"; - } -} - -/* ************************************************************************* */ -void Method::emit_cython_pyx_no_overload(FileWriter& file, - const Class& cls) const { - string funcName = pyRename(name_); - - // leverage python's special treatment for print - if (funcName == "print_") { - file.oss << " def __repr__(self):\n"; - file.oss << " strBuf = RedirectCout()\n"; - file.oss << " self.print_('')\n"; - file.oss << " return strBuf.str()\n"; - } - - // Function definition - file.oss << " def " << funcName; - - // modify name of function instantiation as python doesn't allow overloads - // e.g. template funcName(...) --> funcNameA, funcNameB, funcNameC - if (templateArgValue_) file.oss << templateArgValue_->pyxClassName(); - - // function arguments - file.oss << "(self"; - if (argumentList(0).size() > 0) file.oss << ", "; - argumentList(0).emit_cython_pyx(file); - file.oss << "):\n"; - - /// Call cython corresponding function and return - file.oss << argumentList(0).pyx_convertEigenTypeAndStorageOrder(" "); - string caller = "self." + cls.shared_pxd_obj_in_pyx() + ".get()"; - string ret = pyx_functionCall(caller, funcName, 0); - if (!returnVals_[0].isVoid()) { - file.oss << " cdef " << returnVals_[0].pyx_returnType() - << " ret = " << ret << "\n"; - file.oss << " return " << returnVals_[0].pyx_casting("ret") << "\n"; - } else { - file.oss << " " << ret << "\n"; - } -} - -/* ************************************************************************* */ -void Method::emit_cython_pyx(FileWriter& file, const Class& cls) const { - string funcName = pyRename(name_); - // For template function: modify name of function instantiation as python - // doesn't allow overloads - // e.g. template funcName(...) --> funcNameA, funcNameB, funcNameC - string instantiatedName = - (templateArgValue_) ? funcName + templateArgValue_->pyxClassName() : - funcName; - - size_t N = nrOverloads(); - // It's easy if there's no overload - if (N == 1) { - emit_cython_pyx_no_overload(file, cls); - return; - } - - // Dealing with overloads.. - file.oss << " def " << instantiatedName << "(self, *args, **kwargs):\n"; - file.oss << " cdef list __params\n"; - - // Define return values for all possible overloads - vector return_type; // every overload has a return type, possibly void - map return_value; // we only define one return value for every distinct type - size_t j = 1; - for (size_t i = 0; i < nrOverloads(); ++i) { - if (returnVals_[i].isVoid()) { - return_type.push_back("void"); - } else { - const string type = returnVals_[i].pyx_returnType(); - return_type.push_back(type); - if (return_value.count(type) == 0) { - const string value = "return_value_" + to_string(j++); - return_value[type] = value; - file.oss << " cdef " << type << " " << value << "\n"; - } - } - } - - for (size_t i = 0; i < nrOverloads(); ++i) { - ArgumentList args = argumentList(i); - file.oss << " try:\n"; - file.oss << pyx_resolveOverloadParams(args, false, 3); // lazy: always return None even if it's a void function - - /// Call corresponding cython function - file.oss << args.pyx_convertEigenTypeAndStorageOrder(" "); - string caller = "self." + cls.shared_pxd_obj_in_pyx() + ".get()"; - string call = pyx_functionCall(caller, funcName, i); - if (!returnVals_[i].isVoid()) { - const string type = return_type[i]; - const string value = return_value[type]; - file.oss << " " << value << " = " << call << "\n"; - file.oss << " return " << returnVals_[i].pyx_casting(value) - << "\n"; - } else { - file.oss << " " << call << "\n"; - file.oss << " return\n"; - } - file.oss << " except (AssertionError, ValueError):\n"; - file.oss << " pass\n"; - } - file.oss - << " raise TypeError('Incorrect arguments or types for method call.')\n\n"; -} -/* ************************************************************************* */ diff --git a/wrap/Method.h b/wrap/Method.h deleted file mode 100644 index 4d3c8d909..000000000 --- a/wrap/Method.h +++ /dev/null @@ -1,74 +0,0 @@ -/* ---------------------------------------------------------------------------- - - * GTSAM Copyright 2010, Georgia Tech Research Corporation, - * Atlanta, Georgia 30332-0415 - * All Rights Reserved - * Authors: Frank Dellaert, et al. (see THANKS for the full author list) - - * See LICENSE for the license information - - * -------------------------------------------------------------------------- */ - -/** - * @file Method.h - * @brief describes and generates code for methods - * @author Frank Dellaert - * @author Richard Roberts - **/ - -#pragma once - -#include "MethodBase.h" - -namespace wrap { - -/// Method class -class Method: public MethodBase { - -protected: - bool is_const_; - -public: - - typedef const std::string& Str; - - bool addOverload(Str name, const ArgumentList& args, - const ReturnValue& retVal, bool is_const, - boost::optional instName = boost::none, bool verbose = - false); - - bool isStatic() const override { - return false; - } - - virtual bool isConst() const { - return is_const_; - } - - bool isSameModifiers(const Method& other) const { - return is_const_ == other.is_const_ && - ((templateArgValue_ && other.templateArgValue_) || - (!templateArgValue_ && !other.templateArgValue_)); - } - - friend std::ostream& operator<<(std::ostream& os, const Method& m) { - for (size_t i = 0; i < m.nrOverloads(); i++) - os << m.returnVals_[i] << " " << m.name_ << m.argLists_[i]; - return os; - } - - void emit_cython_pxd(FileWriter& file, const Class& cls) const; - void emit_cython_pyx(FileWriter& file, const Class& cls) const; - void emit_cython_pyx_no_overload(FileWriter& file, const Class& cls) const; - -private: - - // Emit method header - void proxy_header(FileWriter& proxyFile) const override; - - std::string wrapper_call(FileWriter& wrapperFile, Str cppClassName, - Str matlabUniqueName, const ArgumentList& args) const override; -}; - -} // \namespace wrap - diff --git a/wrap/MethodBase.cpp b/wrap/MethodBase.cpp deleted file mode 100644 index a2ed68780..000000000 --- a/wrap/MethodBase.cpp +++ /dev/null @@ -1,135 +0,0 @@ -/* ---------------------------------------------------------------------------- - - * GTSAM Copyright 2010, Georgia Tech Research Corporation, - * Atlanta, Georgia 30332-0415 - * All Rights Reserved - * Authors: Frank Dellaert, et al. (see THANKS for the full author list) - - * See LICENSE for the license information - - * -------------------------------------------------------------------------- */ - -/** - * @file MethodBase.ccp - * @author Frank Dellaert - * @author Andrew Melim - * @author Richard Roberts - **/ - -#include "Method.h" -#include "Class.h" -#include "utilities.h" - -#include -#include - -#include -#include - -using namespace std; -using namespace wrap; - -/* ************************************************************************* */ -void MethodBase::proxy_wrapper_fragments( - FileWriter& proxyFile, FileWriter& wrapperFile, Str cppClassName, - Str matlabQualName, Str matlabUniqueName, Str wrapperName, - const TypeAttributesTable& typeAttributes, - vector& functionNames) const { - // emit header, e.g., function varargout = templatedMethod(this, varargin) - proxy_header(proxyFile); - - // Emit comments for documentation - string up_name = boost::to_upper_copy(matlabName()); - proxyFile.oss << " % " << up_name << " usage: "; - usage_fragment(proxyFile, matlabName()); - - // Emit URL to Doxygen page - proxyFile.oss << " % " - << "Doxygen can be found at " - "http://research.cc.gatech.edu/borg/sites/edu.borg/html/" - "index.html" << endl; - - // Handle special case of single overload with all numeric arguments - if (nrOverloads() == 1 && argumentList(0).allScalar()) { - // Output proxy matlab code - // TODO: document why is it OK to not check arguments in this case - proxyFile.oss << " "; - const int id = (int)functionNames.size(); - emit_call(proxyFile, returnValue(0), wrapperName, id); - - // Output C++ wrapper code - const string wrapFunctionName = wrapper_fragment( - wrapperFile, cppClassName, matlabUniqueName, 0, id, typeAttributes); - - // Add to function list - functionNames.push_back(wrapFunctionName); - } else { - // Check arguments for all overloads - for (size_t i = 0; i < nrOverloads(); ++i) { - // Output proxy matlab code - proxyFile.oss << " " << (i == 0 ? "" : "else"); - const int id = (int)functionNames.size(); - emit_conditional_call(proxyFile, returnValue(i), argumentList(i), - wrapperName, id); - - // Output C++ wrapper code - const string wrapFunctionName = wrapper_fragment( - wrapperFile, cppClassName, matlabUniqueName, i, id, typeAttributes); - - // Add to function list - functionNames.push_back(wrapFunctionName); - } - proxyFile.oss << " else\n"; - proxyFile.oss - << " error('Arguments do not match any overload of function " - << matlabQualName << "." << name_ << "');" << endl; - proxyFile.oss << " end\n"; - } - - proxyFile.oss << " end\n"; -} - -/* ************************************************************************* */ -string MethodBase::wrapper_fragment( - FileWriter& wrapperFile, Str cppClassName, Str matlabUniqueName, - int overload, int id, const TypeAttributesTable& typeAttributes) const { - // generate code - - const string wrapFunctionName = - matlabUniqueName + "_" + name_ + "_" + boost::lexical_cast(id); - - const ArgumentList& args = argumentList(overload); - const ReturnValue& returnVal = returnValue(overload); - - // call - wrapperFile.oss - << "void " << wrapFunctionName - << "(int nargout, mxArray *out[], int nargin, const mxArray *in[])\n"; - // start - wrapperFile.oss << "{\n"; - - // get call - // for static methods: cppClassName::staticMethod - // for instance methods: obj->instanceMethod - string expanded = - wrapper_call(wrapperFile, cppClassName, matlabUniqueName, args); - - expanded += ("(" + args.names() + ")"); - if (returnVal.type1.name() != "void") - returnVal.wrap_result(expanded, wrapperFile, typeAttributes); - else - wrapperFile.oss << " " + expanded + ";\n"; - - // finish - wrapperFile.oss << "}\n"; - - return wrapFunctionName; -} - -/* ************************************************************************* */ -void MethodBase::python_wrapper(FileWriter& wrapperFile, Str className) const { - wrapperFile.oss << " .def(\"" << name_ << "\", &" << className - << "::" << name_ << ");\n"; -} - -/* ************************************************************************* */ diff --git a/wrap/MethodBase.h b/wrap/MethodBase.h deleted file mode 100644 index ee72a6a53..000000000 --- a/wrap/MethodBase.h +++ /dev/null @@ -1,70 +0,0 @@ -/* ---------------------------------------------------------------------------- - - * GTSAM Copyright 2010, Georgia Tech Research Corporation, - * Atlanta, Georgia 30332-0415 - * All Rights Reserved - * Authors: Frank Dellaert, et al. (see THANKS for the full author list) - - * See LICENSE for the license information - - * -------------------------------------------------------------------------- */ - -/** - * @file MethodBase.h - * @brief describes and generates code for static methods - * @author Frank Dellaert - * @author Alex Cunningham - * @author Richard Roberts - **/ - -#pragma once - -#include "FullyOverloadedFunction.h" - -namespace wrap { - -// Forward declaration -class Class; - -/// MethodBase class -struct MethodBase : public FullyOverloadedFunction { - typedef const std::string& Str; - - // emit a list of comments, one for each overload - void comment_fragment(FileWriter& proxyFile) const { - SignatureOverloads::comment_fragment(proxyFile, matlabName()); - } - - void verifyArguments(const std::vector& validArgs) const { - SignatureOverloads::verifyArguments(validArgs, name_); - } - - void verifyReturnTypes(const std::vector& validtypes) const { - SignatureOverloads::verifyReturnTypes(validtypes, name_); - } - - // MATLAB code generation - // classPath is class directory, e.g., ../matlab/@Point2 - void proxy_wrapper_fragments(FileWriter& proxyFile, FileWriter& wrapperFile, - Str cppClassName, Str matlabQualName, - Str matlabUniqueName, Str wrapperName, - const TypeAttributesTable& typeAttributes, - std::vector& functionNames) const; - - // emit python wrapper - void python_wrapper(FileWriter& wrapperFile, Str className) const; - -protected: - virtual void proxy_header(FileWriter& proxyFile) const = 0; - - std::string wrapper_fragment( - FileWriter& wrapperFile, Str cppClassName, Str matlabUniqueName, - int overload, int id, - const TypeAttributesTable& typeAttributes) const; ///< cpp wrapper - - virtual std::string wrapper_call(FileWriter& wrapperFile, Str cppClassName, - Str matlabUniqueName, - const ArgumentList& args) const = 0; -}; - -} // \namespace wrap diff --git a/wrap/Module.cpp b/wrap/Module.cpp deleted file mode 100644 index 780c6f8da..000000000 --- a/wrap/Module.cpp +++ /dev/null @@ -1,649 +0,0 @@ -/* ---------------------------------------------------------------------------- - - * GTSAM Copyright 2010, Georgia Tech Research Corporation, - * Atlanta, Georgia 30332-0415 - * All Rights Reserved - * Authors: Frank Dellaert, et al. (see THANKS for the full author list) - - * See LICENSE for the license information - - * -------------------------------------------------------------------------- */ - -/** - * @file Module.ccp - * @author Frank Dellaert - * @author Alex Cunningham - * @author Andrew Melim - * @author Richard Roberts - **/ - -#include "Module.h" -#include "FileWriter.h" -#include "TypeAttributesTable.h" -#include "utilities.h" - -#include -#include - -#include -#include - -using namespace std; -using namespace wrap; -using namespace BOOST_SPIRIT_CLASSIC_NS; -namespace bl = boost::lambda; -namespace fs = boost::filesystem; - -/* ************************************************************************* */ -// We parse an interface file into a Module object. -// The grammar is defined using the boost/spirit combinatorial parser. -// For example, str_p("const") parses the string "const", and the >> -// operator creates a sequence parser. The grammar below, composed of rules -// and with start rule [class_p], doubles as the specs for our interface files. -/* ************************************************************************* */ - -/* ************************************************************************* */ -// If a number of template arguments were given, generate a number of expanded -// class names, e.g., PriorFactor -> PriorFactorPose2, and add those classes -static void handle_possible_template(vector& classes, - vector& uninstantiatedClasses, - const Class& cls, const Template& t) { - uninstantiatedClasses.push_back(cls); - if (cls.templateArgs.empty() || t.empty()) { - classes.push_back(cls); - } else { - if (cls.templateArgs.size() != 1) - throw std::runtime_error( - "In-line template instantiations only handle a single template argument"); - string arg = cls.templateArgs.front(); - vector classInstantiations = - (t.nrValues() > 0) ? cls.expandTemplate(arg, t.argValues()) : - cls.expandTemplate(arg, t.intList()); - for(const Class& c: classInstantiations) - classes.push_back(c); - } -} - -static void push_typedef_pair(vector& typedefs, - const Qualified& oldType, - const Qualified& newType, - const string& includeFile) { - typedefs.push_back(TypedefPair(oldType, newType, includeFile)); -} - -/* ************************************************************************* */ -Module::Module(const std::string& moduleName, bool enable_verbose) -: name(moduleName), verbose(enable_verbose) -{ -} - -/* ************************************************************************* */ -Module::Module(const string& interfacePath, - const string& moduleName, bool enable_verbose) -: name(moduleName), verbose(enable_verbose) -{ - // read interface file - string interfaceFile = interfacePath + "/" + moduleName + ".h"; - string contents = file_contents(interfaceFile); - - // execute parsing - parseMarkup(contents); -} - -/* ************************************************************************* */ -void Module::parseMarkup(const std::string& data) { - // The parse imperatively :-( updates variables gradually during parse - // The one with postfix 0 are used to reset the variables after parse. - - //---------------------------------------------------------------------------- - // Grammar with actions that build the Class object. Actions are - // defined within the square brackets [] and are executed whenever a - // rule is successfully parsed. Define BOOST_SPIRIT_DEBUG to debug. - // The grammar is allows a very restricted C++ header - // lexeme_d turns off white space skipping - // http://www.boost.org/doc/libs/1_37_0/libs/spirit/classic/doc/directives.html - // ---------------------------------------------------------------------------- - - // Define Rule and instantiate basic rules - typedef rule Rule; - BasicRules basic; - - vector namespaces; // current namespace tag - string currentInclude; - - // parse a full class - Class cls0(verbose),cls(verbose); - Template classTemplate; - ClassGrammar class_g(cls,classTemplate); - Rule class_p = class_g // - [assign_a(cls.namespaces_, namespaces)] - [assign_a(cls.includeFile, currentInclude)][bl::bind( - &handle_possible_template, bl::var(classes), - bl::var(uninstantiatedClasses), bl::var(cls), - bl::var(classTemplate))][clear_a(classTemplate)] // - [assign_a(cls, cls0)]; - - // parse "gtsam::Pose2" and add to singleInstantiation.typeList - TemplateInstantiationTypedef singleInstantiation, singleInstantiation0; - TypeListGrammar<'<','>'> typelist_g(singleInstantiation.typeList); - - // typedef gtsam::RangeFactor RangeFactor2D; - TypeGrammar instantiationClass_g(singleInstantiation.class_); - Rule templateSingleInstantiation_p = - (str_p("typedef") >> instantiationClass_g >> - typelist_g >> - basic.className_p[assign_a(singleInstantiation.name_)] >> - ';') - [assign_a(singleInstantiation.namespaces_, namespaces)] - [push_back_a(templateInstantiationTypedefs, singleInstantiation)] - [assign_a(singleInstantiation, singleInstantiation0)]; - - Qualified oldType, newType; - TypeGrammar typedefOldClass_g(oldType), typedefNewClass_g(newType); - Rule typedef_p = - (str_p("typedef") >> typedefOldClass_g >> typedefNewClass_g >> - ';') - [assign_a(oldType.namespaces_, namespaces)] - [assign_a(newType.namespaces_, namespaces)] - [bl::bind(&push_typedef_pair, bl::var(typedefs), bl::var(oldType), - bl::var(newType), bl::var(currentInclude))]; - - // Create grammar for global functions - GlobalFunctionGrammar global_function_g(global_functions, namespaces, - currentInclude); - - Rule include_p = str_p("#include") >> ch_p('<') >> - (*(anychar_p - '>'))[push_back_a(includes)] - [assign_a(currentInclude)] >> - ch_p('>'); - -#ifdef __clang__ -#pragma clang diagnostic push -#pragma clang diagnostic ignored "-Wuninitialized" -#endif - - Rule namespace_def_p = - (str_p("namespace") - >> basic.namespace_p[push_back_a(namespaces)] - >> ch_p('{') - >> *(include_p | class_p | templateSingleInstantiation_p | typedef_p | global_function_g | namespace_def_p | basic.comments_p) - >> ch_p('}')) - [pop_a(namespaces)]; - -#ifdef __clang__ -#pragma clang diagnostic pop -#endif - - // parse forward declaration - ForwardDeclaration fwDec0, fwDec; - Class fwParentClass; - TypeGrammar className_g(fwDec.cls); - TypeGrammar classParent_g(fwParentClass); - Rule classParent_p = (':' >> classParent_g >> ';') // - [bl::bind(&Class::assignParent, bl::var(fwDec.cls), - bl::var(fwParentClass))][clear_a(fwParentClass)]; - - Rule forward_declaration_p = - !(str_p("virtual")[assign_a(fwDec.isVirtual, T)]) - >> str_p("class") >> className_g - >> (classParent_p | ';') - [push_back_a(forward_declarations, fwDec)] - [assign_a(cls,cls0)] // also clear class to avoid partial parse - [assign_a(fwDec, fwDec0)]; - - Rule module_content_p = basic.comments_p | include_p | class_p - | templateSingleInstantiation_p | forward_declaration_p - | global_function_g | namespace_def_p; - - Rule module_p = *module_content_p >> !end_p; - - // and parse contents - parse_info info = parse(data.c_str(), module_p, space_p); - if(!info.full) { - printf("parsing stopped at \n%.20s\n",info.stop); - cout << "Stopped in:\n" - "class '" << cls.name_ << "'" << endl; - throw ParseFailed((int)info.length); - } - - // Post-process classes for serialization markers - for(Class& cls: classes) - cls.erase_serialization(); - - for(Class& cls: uninstantiatedClasses) - cls.erase_serialization(); - - // Explicitly add methods to the classes from parents so it shows in documentation - for(Class& cls: classes) - cls.appendInheritedMethods(cls, classes); - - // - Remove inherited methods for Cython classes in the pxd, otherwise Cython can't decide which one to call. - // - Only inherited nontemplateMethods_ in uninstantiatedClasses need to be removed - // because that what we serialized to the pxd. - // - However, we check against the class parent's *methods_* to avoid looking into - // its grand parent and grand-grand parent, etc., because all those are already - // added in its direct parent. - // - So this must be called *after* the above code appendInheritedMethods!! - for(Class& cls: uninstantiatedClasses) - cls.removeInheritedNontemplateMethods(uninstantiatedClasses); - - // Expand templates - This is done first so that template instantiations are - // counted in the list of valid types, have their attributes and dependencies - // checked, etc. - expandedClasses = ExpandTypedefInstantiations(classes, - templateInstantiationTypedefs); - - // Dependency check list - vector validTypes = GenerateValidTypes(expandedClasses, - forward_declarations, typedefs); - - // Check that all classes have been defined somewhere - verifyArguments(validTypes, global_functions); - verifyReturnTypes(validTypes, global_functions); - - hasSerialiable = false; - for(const Class& cls: expandedClasses) - cls.verifyAll(validTypes,hasSerialiable); - - // Create type attributes table and check validity - typeAttributes.addClasses(expandedClasses); - typeAttributes.addForwardDeclarations(forward_declarations); - for (const TypedefPair& p: typedefs) - typeAttributes.addType(p.newType); - // add Eigen types as template arguments are also checked ? - vector eigen; - eigen.push_back(ForwardDeclaration("Vector")); - eigen.push_back(ForwardDeclaration("Matrix")); - typeAttributes.addForwardDeclarations(eigen); - typeAttributes.checkValidity(expandedClasses); -} - -/* ************************************************************************* */ -void Module::generate_matlab_wrapper(const string& toolboxPath) const { - - fs::create_directories(toolboxPath); - - // create the unified .cpp switch file - const string wrapperName = name + "_wrapper"; - string wrapperFileName = toolboxPath + "/" + wrapperName + ".cpp"; - FileWriter wrapperFile(wrapperFileName, verbose, "//"); - wrapperFile.oss << "#include \n"; - wrapperFile.oss << "#include \n"; - wrapperFile.oss << "\n"; - - // Include boost.serialization archive headers before other class headers - if (hasSerialiable) { - wrapperFile.oss << "#include \n"; - wrapperFile.oss << "#include \n"; - wrapperFile.oss << "#include \n\n"; - } - - // Generate includes while avoiding redundant includes - generateIncludes(wrapperFile); - - // create typedef classes - we put this at the top of the wrap file so that - // collectors and method arguments can use these typedefs - for(const Class& cls: expandedClasses) - if(!cls.typedefName.empty()) - wrapperFile.oss << cls.getTypedef() << "\n"; - wrapperFile.oss << "\n"; - - // Generate boost.serialization export flags (needs typedefs from above) - if (hasSerialiable) { - for(const Class& cls: expandedClasses) - if(cls.isSerializable) - wrapperFile.oss << cls.getSerializationExport() << "\n"; - wrapperFile.oss << "\n"; - } - - // Generate collectors and cleanup function to be called from mexAtExit - WriteCollectorsAndCleanupFcn(wrapperFile, name, expandedClasses); - - // generate RTTI registry (for returning derived-most types) - WriteRTTIRegistry(wrapperFile, name, expandedClasses); - - vector functionNames; // Function names stored by index for switch - - // create proxy class and wrapper code - for(const Class& cls: expandedClasses) - cls.matlab_proxy(toolboxPath, wrapperName, typeAttributes, wrapperFile, functionNames); - - // create matlab files and wrapper code for global functions - for(const GlobalFunctions::value_type& p: global_functions) - p.second.matlab_proxy(toolboxPath, wrapperName, typeAttributes, wrapperFile, functionNames); - - // finish wrapper file - wrapperFile.oss << "\n"; - finish_wrapper(wrapperFile, functionNames); - - wrapperFile.emit(true); -} - -/* ************************************************************************* */ -void Module::generate_cython_wrapper(const string& toolboxPath, const std::string& pxdImports) const { - fs::create_directories(toolboxPath); - string pxdFileName = toolboxPath + "/" + name + ".pxd"; - FileWriter pxdFile(pxdFileName, verbose, "#"); - pxdFile.oss << pxdImports << "\n"; - emit_cython_pxd(pxdFile); - string pyxFileName = toolboxPath + "/" + name + ".pyx"; - FileWriter pyxFile(pyxFileName, verbose, "#"); - emit_cython_pyx(pyxFile); -} - -/* ************************************************************************* */ -void Module::emit_cython_pxd(FileWriter& pxdFile) const { - // headers - pxdFile.oss << "from gtsam_eigency.core cimport *\n" - "from libcpp.string cimport string\n" - "from libcpp.vector cimport vector\n" - "from libcpp.pair cimport pair\n" - "from libcpp.set cimport set\n" - "from libcpp.map cimport map\n" - "from libcpp cimport bool\n\n"; - - // boost shared_ptr - pxdFile.oss << "cdef extern from \"boost/shared_ptr.hpp\" namespace \"boost\":\n" - " cppclass shared_ptr[T]:\n" - " shared_ptr()\n" - " shared_ptr(T*)\n" - " T* get()\n" - " long use_count() const\n" - " T& operator*()\n\n" - " cdef shared_ptr[T] dynamic_pointer_cast[T,U](const shared_ptr[U]& r)\n\n"; - - // gtsam alignment-friendly shared_ptr - pxdFile.oss << "cdef extern from \"gtsam/base/make_shared.h\" namespace \"gtsam\":\n" - " cdef shared_ptr[T] make_shared[T](const T& r)\n\n"; - - for(const TypedefPair& types: typedefs) - types.emit_cython_pxd(pxdFile); - - //... wrap all classes - for (const Class& cls : uninstantiatedClasses) { - cls.emit_cython_pxd(pxdFile); - - for (const Class& expCls : expandedClasses) { - bool matchingNonTemplated = !expCls.templateClass - && expCls.pxdClassName() == cls.pxdClassName(); - bool isTemplatedFromCls = expCls.templateClass - && expCls.templateClass->pxdClassName() == cls.pxdClassName(); - - // ctypedef for template instantiations - if (isTemplatedFromCls) { - pxdFile.oss << "\n"; - pxdFile.oss << "ctypedef " << expCls.templateClass->pxdClassName() - << "["; - for (size_t i = 0; i < expCls.templateInstTypeList.size(); ++i) - pxdFile.oss << expCls.templateInstTypeList[i].pxdClassName() - << ((i == expCls.templateInstTypeList.size() - 1) ? "" : ", "); - pxdFile.oss << "] " << expCls.pxdClassName() << "\n"; - } - - // Python wrapper class - if (isTemplatedFromCls || matchingNonTemplated) { - expCls.emit_cython_wrapper_pxd(pxdFile); - } - } - pxdFile.oss << "\n\n"; - } - - //... wrap global functions - for(const GlobalFunctions::value_type& p: global_functions) - p.second.emit_cython_pxd(pxdFile); - - pxdFile.emit(true); -} - -/* ************************************************************************* */ -void Module::emit_cython_pyx(FileWriter& pyxFile) const { - // directives... - // allow str to automatically coerce to std::string and back (for python3) - pyxFile.oss << "# cython: c_string_type=str, c_string_encoding=ascii\n\n"; - - // headers... - string pxdHeader = name; - pyxFile.oss << "cimport numpy as np\n" - "import numpy as npp\n" - "cimport " << pxdHeader << "\n" - "from ."<< pxdHeader << " cimport shared_ptr\n" - "from ."<< pxdHeader << " cimport dynamic_pointer_cast\n" - "from ."<< pxdHeader << " cimport make_shared\n"; - - pyxFile.oss << "# C helper function that copies all arguments into a positional list.\n" - "cdef list process_args(list keywords, tuple args, dict kwargs):\n" - " cdef str keyword\n" - " cdef int n = len(args), m = len(keywords)\n" - " cdef list params = list(args)\n" - " assert len(args)+len(kwargs) == m, 'Expected {} arguments'.format(m)\n" - " try:\n" - " return params + [kwargs[keyword] for keyword in keywords[n:]]\n" - " except:\n" - " raise ValueError('Epected arguments ' + str(keywords))\n"; - - // import all typedefs, e.g. from gtsam_wrapper cimport Key, so we don't need to say gtsam.Key - for(const Qualified& q: Qualified::BasicTypedefs) { - pyxFile.oss << "from " << pxdHeader << " cimport " << q.pxdClassName() << "\n"; - } - pyxFile.oss << "from gtsam_eigency.core cimport *\n" - "from libcpp cimport bool\n\n" - "from libcpp.pair cimport pair\n" - "from libcpp.string cimport string\n" - "from cython.operator cimport dereference as deref\n\n\n"; - - // all classes include all forward declarations - std::vector allClasses = expandedClasses; - for(const ForwardDeclaration& fd: forward_declarations) - allClasses.push_back(fd.cls); - - for(const Class& cls: expandedClasses) - cls.emit_cython_pyx(pyxFile, allClasses); - pyxFile.oss << "\n"; - - //... wrap global functions - for(const GlobalFunctions::value_type& p: global_functions) - p.second.emit_cython_pyx(pyxFile); - pyxFile.emit(true); -} - -/* ************************************************************************* */ -void Module::generateIncludes(FileWriter& file) const { - - // collect includes - vector all_includes(includes); - - // sort and remove duplicates - sort(all_includes.begin(), all_includes.end()); - vector::const_iterator last_include = unique(all_includes.begin(), all_includes.end()); - vector::const_iterator it = all_includes.begin(); - // add includes to file - for (; it != last_include; ++it) - file.oss << "#include <" << *it << ">" << endl; - file.oss << "\n"; -} - - -/* ************************************************************************* */ - void Module::finish_wrapper(FileWriter& file, const std::vector& functionNames) const { - file.oss << "void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[])\n"; - file.oss << "{\n"; - file.oss << " mstream mout;\n"; // Send stdout to MATLAB console - file.oss << " std::streambuf *outbuf = std::cout.rdbuf(&mout);\n\n"; - file.oss << " _" << name << "_RTTIRegister();\n\n"; - file.oss << " int id = unwrap(in[0]);\n\n"; - file.oss << " try {\n"; - file.oss << " switch(id) {\n"; - for(size_t id = 0; id < functionNames.size(); ++id) { - file.oss << " case " << id << ":\n"; - file.oss << " " << functionNames[id] << "(nargout, out, nargin-1, in+1);\n"; - file.oss << " break;\n"; - } - file.oss << " }\n"; - file.oss << " } catch(const std::exception& e) {\n"; - file.oss << " mexErrMsgTxt((\"Exception from gtsam:\\n\" + std::string(e.what()) + \"\\n\").c_str());\n"; - file.oss << " }\n"; - file.oss << "\n"; - file.oss << " std::cout.rdbuf(outbuf);\n"; // Restore cout - file.oss << "}\n"; - } - -/* ************************************************************************* */ -vector Module::ExpandTypedefInstantiations(const vector& classes, const vector instantiations) { - - vector expandedClasses = classes; - - for(const TemplateInstantiationTypedef& inst: instantiations) { - // Add the new class to the list - expandedClasses.push_back(inst.findAndExpand(classes)); - } - - // Remove all template classes - for(size_t i = 0; i < expandedClasses.size(); ++i) - if(!expandedClasses[i].templateArgs.empty()) { - expandedClasses.erase(expandedClasses.begin() + size_t(i)); - -- i; - } - - return expandedClasses; -} - -/* ************************************************************************* */ -vector Module::GenerateValidTypes(const vector& classes, const vector& forwardDeclarations, const vector& typedefs) { - vector validTypes; - for(const ForwardDeclaration& fwDec: forwardDeclarations) { - validTypes.push_back(fwDec.name()); - } - validTypes.push_back("void"); - validTypes.push_back("string"); - validTypes.push_back("int"); - validTypes.push_back("bool"); - validTypes.push_back("char"); - validTypes.push_back("unsigned char"); - validTypes.push_back("size_t"); - validTypes.push_back("double"); - validTypes.push_back("Vector"); - validTypes.push_back("Matrix"); - //Create a list of parsed classes for dependency checking - for(const Class& cls: classes) { - validTypes.push_back(cls.qualifiedName("::")); - } - for(const TypedefPair& p: typedefs) { - validTypes.push_back(p.newType.qualifiedName("::")); - } - - return validTypes; -} - -/* ************************************************************************* */ -void Module::WriteCollectorsAndCleanupFcn(FileWriter& wrapperFile, const std::string& moduleName, const std::vector& classes) { - // Generate all collectors - for(const Class& cls: classes) { - const string matlabUniqueName = cls.qualifiedName(), - cppName = cls.qualifiedName("::"); - wrapperFile.oss << "typedef std::set*> " - << "Collector_" << matlabUniqueName << ";\n"; - wrapperFile.oss << "static Collector_" << matlabUniqueName << - " collector_" << matlabUniqueName << ";\n"; - } - - // generate mexAtExit cleanup function - wrapperFile.oss << - "\nvoid _deleteAllObjects()\n" - "{\n" - " mstream mout;\n" // Send stdout to MATLAB console - " std::streambuf *outbuf = std::cout.rdbuf(&mout);\n\n" - " bool anyDeleted = false;\n"; - for(const Class& cls: classes) { - const string matlabUniqueName = cls.qualifiedName(); - const string cppName = cls.qualifiedName("::"); - const string collectorType = "Collector_" + matlabUniqueName; - const string collectorName = "collector_" + matlabUniqueName; - // The extra curly-braces around the for loops work around a limitation in MSVC (existing - // since 2005!) preventing more than 248 blocks. - wrapperFile.oss << - " { for(" << collectorType << "::iterator iter = " << collectorName << ".begin();\n" - " iter != " << collectorName << ".end(); ) {\n" - " delete *iter;\n" - " " << collectorName << ".erase(iter++);\n" - " anyDeleted = true;\n" - " } }\n"; - } - wrapperFile.oss << - " if(anyDeleted)\n" - " cout <<\n" - " \"WARNING: Wrap modules with variables in the workspace have been reloaded due to\\n\"\n" - " \"calling destructors, call 'clear all' again if you plan to now recompile a wrap\\n\"\n" - " \"module, so that your recompiled module is used instead of the old one.\" << endl;\n" - " std::cout.rdbuf(outbuf);\n" // Restore cout - "}\n\n"; -} - -/* ************************************************************************* */ -void Module::WriteRTTIRegistry(FileWriter& wrapperFile, const std::string& moduleName, const std::vector& classes) { - wrapperFile.oss << - "void _" << moduleName << "_RTTIRegister() {\n" - " const mxArray *alreadyCreated = mexGetVariablePtr(\"global\", \"gtsam_" + moduleName + "_rttiRegistry_created\");\n" - " if(!alreadyCreated) {\n" - " std::map types;\n"; - for(const Class& cls: classes) { - if(cls.isVirtual) - wrapperFile.oss << - " types.insert(std::make_pair(typeid(" << cls.qualifiedName("::") << ").name(), \"" << cls.qualifiedName(".") << "\"));\n"; - } - wrapperFile.oss << "\n"; - - wrapperFile.oss << - " mxArray *registry = mexGetVariable(\"global\", \"gtsamwrap_rttiRegistry\");\n" - " if(!registry)\n" - " registry = mxCreateStructMatrix(1, 1, 0, NULL);\n" - " typedef std::pair StringPair;\n" - " for(const StringPair& rtti_matlab: types) {\n" - " int fieldId = mxAddField(registry, rtti_matlab.first.c_str());\n" - " if(fieldId < 0)\n" - " mexErrMsgTxt(\"gtsam wrap: Error indexing RTTI types, inheritance will not work correctly\");\n" - " mxArray *matlabName = mxCreateString(rtti_matlab.second.c_str());\n" - " mxSetFieldByNumber(registry, 0, fieldId, matlabName);\n" - " }\n" - " if(mexPutVariable(\"global\", \"gtsamwrap_rttiRegistry\", registry) != 0)\n" - " mexErrMsgTxt(\"gtsam wrap: Error indexing RTTI types, inheritance will not work correctly\");\n" - " mxDestroyArray(registry);\n" - " \n" - " mxArray *newAlreadyCreated = mxCreateNumericMatrix(0, 0, mxINT8_CLASS, mxREAL);\n" - " if(mexPutVariable(\"global\", \"gtsam_" + moduleName + "_rttiRegistry_created\", newAlreadyCreated) != 0)\n" - " mexErrMsgTxt(\"gtsam wrap: Error indexing RTTI types, inheritance will not work correctly\");\n" - " mxDestroyArray(newAlreadyCreated);\n" - " }\n" - "}\n" - "\n"; -} - -/* ************************************************************************* */ -void Module::generate_python_wrapper(const string& toolboxPath) const { - - fs::create_directories(toolboxPath); - - // create the unified .cpp switch file - const string wrapperName = name + "_python"; - string wrapperFileName = toolboxPath + "/" + wrapperName + ".cpp"; - FileWriter wrapperFile(wrapperFileName, verbose, "//"); - wrapperFile.oss << "#include \n\n"; - wrapperFile.oss << "using namespace boost::python;\n"; - wrapperFile.oss << "BOOST_PYTHON_MODULE(" + name + ")\n"; - wrapperFile.oss << "{\n"; - - // write out classes - for(const Class& cls: expandedClasses) { - cls.python_wrapper(wrapperFile); - } - - // write out global functions - for(const GlobalFunctions::value_type& p: global_functions) - p.second.python_wrapper(wrapperFile); - - // finish wrapper file - wrapperFile.oss << "}\n"; - - wrapperFile.emit(true); -} - -/* ************************************************************************* */ diff --git a/wrap/Module.h b/wrap/Module.h deleted file mode 100644 index 2a8344551..000000000 --- a/wrap/Module.h +++ /dev/null @@ -1,95 +0,0 @@ -/* ---------------------------------------------------------------------------- - - * GTSAM Copyright 2010, Georgia Tech Research Corporation, - * Atlanta, Georgia 30332-0415 - * All Rights Reserved - * Authors: Frank Dellaert, et al. (see THANKS for the full author list) - - * See LICENSE for the license information - - * -------------------------------------------------------------------------- */ - -/** - * @file Module.h - * @brief describes module to be wrapped - * @author Frank Dellaert - * @author Richard Roberts - **/ - -#pragma once - -#include "Class.h" -#include "GlobalFunction.h" -#include "TemplateInstantiationTypedef.h" -#include "ForwardDeclaration.h" -#include "TypedefPair.h" - -#include -#include -#include - -namespace wrap { - -/** - * A module just has a name and a list of classes - */ -struct Module { - - // Filled during parsing: - std::string name; ///< module name - bool verbose; ///< verbose flag - std::vector classes; ///< list of classes - std::vector uninstantiatedClasses; ///< list of template classes after instantiated - std::vector templateInstantiationTypedefs; ///< list of template instantiations - std::vector forward_declarations; - std::vector includes; ///< Include statements - GlobalFunctions global_functions; - std::vector typedefs; - - // After parsing: - std::vector expandedClasses; - bool hasSerialiable; - TypeAttributesTable typeAttributes; - - /// constructor that parses interface file - Module(const std::string& interfacePath, const std::string& moduleName, - bool enable_verbose = true); - - /// Dummy constructor that does no parsing - use only for testing - Module(const std::string& moduleName, bool enable_verbose = true); - - /// non-const function that performs parsing - typically called by constructor - /// Throws exception on failure - void parseMarkup(const std::string& data); - - /// MATLAB code generation: - void generate_matlab_wrapper(const std::string& path) const; - - /// Cython code generation: - void generate_cython_wrapper(const std::string& path, const std::string& pxdImports = "") const; - void emit_cython_pxd(FileWriter& file) const; - void emit_cython_pyx(FileWriter& file) const; - - void generateIncludes(FileWriter& file) const; - - void finish_wrapper(FileWriter& file, - const std::vector& functionNames) const; - - /// Python code generation: - void generate_python_wrapper(const std::string& path) const; - -private: - static std::vector ExpandTypedefInstantiations( - const std::vector& classes, - const std::vector instantiations); - static std::vector GenerateValidTypes( - const std::vector& classes, - const std::vector& forwardDeclarations, - const std::vector& typedefs); - static void WriteCollectorsAndCleanupFcn(FileWriter& wrapperFile, - const std::string& moduleName, const std::vector& classes); - static void WriteRTTIRegistry(FileWriter& wrapperFile, - const std::string& moduleName, const std::vector& classes); -}; - -} // \namespace wrap diff --git a/wrap/OverloadedFunction.h b/wrap/OverloadedFunction.h deleted file mode 100644 index 6bcb72d94..000000000 --- a/wrap/OverloadedFunction.h +++ /dev/null @@ -1,140 +0,0 @@ -/* ---------------------------------------------------------------------------- - - * GTSAM Copyright 2010, Georgia Tech Research Corporation, - * Atlanta, Georgia 30332-0415 - * All Rights Reserved - * Authors: Frank Dellaert, et al. (see THANKS for the full author list) - - * See LICENSE for the license information - - * -------------------------------------------------------------------------- */ - -/** - * @file OverloadedFunction.h - * @brief Function that can overload its arguments only - * @author Frank Dellaert - * @date Nov 13, 2014 - **/ - -#pragma once - -#include "Function.h" -#include "Argument.h" -#include -namespace wrap { - -/** - * ArgumentList Overloads - */ -class ArgumentOverloads { -public: - std::vector argLists_; - -public: - size_t nrOverloads() const { return argLists_.size(); } - - const ArgumentList& argumentList(size_t i) const { return argLists_.at(i); } - - void push_back(const ArgumentList& args) { argLists_.push_back(args); } - - std::vector expandArgumentListsTemplate( - const TemplateSubstitution& ts) const { - std::vector result; - for (const ArgumentList& argList : argLists_) { - ArgumentList instArgList = argList.expandTemplate(ts); - result.push_back(instArgList); - } - return result; - } - - /// Expand templates, imperative ! - virtual void ExpandTemplate(const TemplateSubstitution& ts) { - argLists_ = expandArgumentListsTemplate(ts); - } - - void verifyArguments(const std::vector& validArgs, - const std::string s) const { - for (const ArgumentList& argList : argLists_) { - for (Argument arg : argList) { - std::string fullType = arg.type.qualifiedName("::"); - if (find(validArgs.begin(), validArgs.end(), fullType) == - validArgs.end()) - throw DependencyMissing(fullType, "checking argument of " + s); - } - } - } - - friend std::ostream& operator<<(std::ostream& os, - const ArgumentOverloads& overloads) { - for (const ArgumentList& argList : overloads.argLists_) - os << argList << std::endl; - return os; - } - - std::string pyx_resolveOverloadParams(const ArgumentList& args, bool isVoid, - size_t indentLevel = 2) const { - std::string indent; - for (size_t i = 0; i < indentLevel; ++i) - indent += " "; - std::string s; - s += indent + "__params = process_args([" + args.pyx_paramsList() - + "], args, kwargs)\n"; - s += args.pyx_castParamsToPythonType(indent); - if (args.size() > 0) { - for (size_t i = 0; i < args.size(); ++i) { - // For python types we can do the assert after the assignment and save list accesses - if (args[i].type.isNonBasicType() || args[i].type.isEigen()) { - std::string param = args[i].name; - s += indent + "assert isinstance(" + param + ", " - + args[i].type.pyxArgumentType() + ")"; - if (args[i].type.isEigen()) { - s += " and " + param + ".ndim == " - + ((args[i].type.pyxClassName() == "Vector") ? "1" : "2"); - } - s += "\n"; - } - } - } - return s; - } -}; - -class OverloadedFunction : public Function, public ArgumentOverloads { -public: - bool addOverload(const std::string& name, const ArgumentList& args, - boost::optional instName = boost::none, - bool verbose = false) { - bool first = initializeOrCheck(name, instName, verbose); - ArgumentOverloads::push_back(args); - return first; - } - -private: -}; - -// Templated checking functions -// TODO: do this via polymorphism, use transform ? - -template -static std::map expandMethodTemplate( - const std::map& methods, const TemplateSubstitution& ts) { - std::map result; - typedef std::pair NamedMethod; - for (NamedMethod namedMethod : methods) { - F instMethod = namedMethod.second; - instMethod.expandTemplate(ts); - namedMethod.second = instMethod; - result.insert(namedMethod); - } - return result; -} - -template -inline void verifyArguments(const std::vector& validArgs, - const std::map& vt) { - typedef typename std::map::value_type NamedMethod; - for (const NamedMethod& namedMethod : vt) - namedMethod.second.verifyArguments(validArgs); -} - -} // \namespace wrap diff --git a/wrap/Qualified.cpp b/wrap/Qualified.cpp deleted file mode 100644 index 947e51d54..000000000 --- a/wrap/Qualified.cpp +++ /dev/null @@ -1,5 +0,0 @@ -#include - -namespace wrap { - std::vector Qualified::BasicTypedefs; -} diff --git a/wrap/Qualified.h b/wrap/Qualified.h deleted file mode 100644 index 416db239d..000000000 --- a/wrap/Qualified.h +++ /dev/null @@ -1,370 +0,0 @@ -/* ---------------------------------------------------------------------------- - - * GTSAM Copyright 2010, Georgia Tech Research Corporation, - * Atlanta, Georgia 30332-0415 - * All Rights Reserved - * Authors: Frank Dellaert, et al. (see THANKS for the full author list) - - * See LICENSE for the license information - - * -------------------------------------------------------------------------- */ - -/** - * @file Qualified.h - * @brief Qualified name - * @author Frank Dellaert - * @date Nov 11, 2014 - **/ - -#pragma once - -#include -#include -#include -#include - -namespace wrap { - -/** - * Class to encapuslate a qualified name, i.e., with (nested) namespaces - */ -class Qualified { - -//protected: -public: - - std::vector namespaces_; ///< Stack of namespaces - std::string name_; ///< type name - static std::vector BasicTypedefs; - - friend struct TypeGrammar; - friend class TemplateSubstitution; - -public: - - /// the different categories - typedef enum { - CLASS = 1, EIGEN = 2, BASIS = 3, VOID = 4 - } Category; - Category category; - - /// Default constructor - Qualified() : - category(VOID) { - } - - /// Construct from name and optional category - Qualified(const std::string& n, Category c = CLASS) : - name_(n), category(c) { - } - - /// Construct from scoped name and optional category - Qualified(const std::string& ns1, const std::string& n, Category c = CLASS) : - name_(n), category(c) { - namespaces_.push_back(ns1); - } - - /// Construct from doubly scoped name and optional category - Qualified(const std::string& ns1, const std::string& ns2, - const std::string& n, Category c = CLASS) : - name_(n), category(c) { - namespaces_.push_back(ns1); - namespaces_.push_back(ns2); - } - - /// Construct from arbitrarily scoped name - Qualified(std::vector ns, const std::string& name) : - namespaces_(ns), name_(name), category(CLASS) { - } - - // Destructor - virtual ~Qualified() {} - - std::string name() const { - return name_; - } - - std::vector namespaces() const { - return namespaces_; - } - - // Qualified is 'abused' as template argument name as well - // this function checks whether *this matches with templateArg - bool match(const std::string& templateArg) const { - return (name_ == templateArg && namespaces_.empty()); //TODO && category == CLASS); - } - - bool match(const std::vector& templateArgs) const { - for(const std::string& s: templateArgs) - if (match(s)) return true; - return false; - } - - void rename(const Qualified& q) { - namespaces_ = q.namespaces_; - name_ = q.name_; - category = q.category; - } - - void expand(const std::string& expansion) { - name_ += expansion; - } - - bool operator==(const Qualified& other) const { - return namespaces_ == other.namespaces_ && name_ == other.name_ - && category == other.category; - } - - bool empty() const { - return namespaces_.empty() && name_.empty(); - } - - virtual void clear() { - namespaces_.clear(); - name_.clear(); - category = VOID; - } - - bool isScalar() const { - return (name() == "bool" || name() == "char" - || name() == "unsigned char" || name() == "int" - || name() == "size_t" || name() == "double"); - } - - bool isVoid() const { - return name() == "void"; - } - - bool isString() const { - return name() == "string"; - } - - bool isEigen() const { - return name() == "Vector" || name() == "Matrix"; - } - - bool isBasicTypedef() const { - return std::find(Qualified::BasicTypedefs.begin(), - Qualified::BasicTypedefs.end(), - *this) != Qualified::BasicTypedefs.end(); - } - - bool isNonBasicType() const { - return name() != "This" && !isString() && !isScalar() && !isEigen() && - !isVoid() && !isBasicTypedef(); - } - -public: - - static Qualified MakeClass(std::vector namespaces, - const std::string& name) { - return Qualified(namespaces, name); - } - - static Qualified MakeEigen(const std::string& name) { - return Qualified(name, EIGEN); - } - - static Qualified MakeBasis(const std::string& name) { - return Qualified(name, BASIS); - } - - static Qualified MakeVoid() { - return Qualified("void", VOID); - } - - /// Return a qualified namespace using given delimiter - std::string qualifiedNamespaces(const std::string& delimiter = "") const { - std::string result; - for (std::size_t i = 0; i < namespaces_.size(); ++i) - result += (namespaces_[i] + ((i VectorXd, Matrix --> MatrixXd - std::string pxdClassName() const { - if (isEigen()) - return name_ + "Xd"; - else if (isNonBasicType()) - return "C" + qualifiedName("_", 1); - else return name_; - } - - /// name of Python classes in pyx - /// They have the same name with the corresponding Cython classes in pxd - /// But note that they are different: These are Python classes in the pyx file - /// To refer to a Cython class in pyx, we need to add "pxd.", e.g. pxd.noiseModel_Gaussian - /// see the other function pxd_class_in_pyx for that purpose. - std::string pyxClassName() const { - if (isEigen()) - return name_; - else - return qualifiedName("_", 1); - } - - /// Python type of function arguments in pyx to interface with normal python scripts - /// Eigen types become np.ndarray (There's no Eigen types, e.g. VectorXd, in - /// Python. We have to pass in numpy array in the arguments, which will then be - /// converted to Eigen types in Cython) - std::string pyxArgumentType() const { - if (isEigen()) - return "np.ndarray"; - else - return qualifiedName("_", 1); - } - - /// return the Cython class in pxd corresponding to a Python class in pyx - std::string pxd_class_in_pyx() const { - if (isNonBasicType()) { - return pxdClassName(); - } else if (isEigen()) { - return name_ + "Xd"; - } else // basic types and not Eigen - return name_; - } - - /// the internal Cython shared obj in a Python class wrappper - std::string shared_pxd_obj_in_pyx() const { - return pxdClassName() + "_"; - } - - std::string make_shared_pxd_class_in_pyx() const { - return "make_shared[" + pxd_class_in_pyx() + "]"; - } - - std::string shared_pxd_class_in_pyx() const { - return "shared_ptr[" + pxd_class_in_pyx() + "]"; - } - - friend std::ostream& operator<<(std::ostream& os, const Qualified& q) { - os << q.qualifiedName("::"); - return os; - } -}; - -/* ************************************************************************* */ -// http://boost-spirit.com/distrib/spirit_1_8_2/libs/spirit/doc/grammar.html -struct TypeGrammar: classic::grammar { - - wrap::Qualified& result_; ///< successful parse will be placed in here - - /// Construct type grammar and specify where result is placed - TypeGrammar(wrap::Qualified& result) : - result_(result) { - } - - /// Definition of type grammar - template - struct definition: BasicRules { - - typedef classic::rule Rule; - - Rule void_p, basisType_p, eigenType_p, namespace_del_p, class_p, type_p; - - definition(TypeGrammar const& self) { - - using namespace wrap; - using namespace classic; - typedef BasicRules Basic; - - // HACK: use const values instead of using enums themselves - somehow this doesn't result in values getting assigned to gibberish - static const Qualified::Category EIGEN = Qualified::EIGEN; - static const Qualified::Category BASIS = Qualified::BASIS; - static const Qualified::Category CLASS = Qualified::CLASS; - static const Qualified::Category VOID = Qualified::VOID; - - void_p = str_p("void") // - [assign_a(self.result_.name_)] // - [assign_a(self.result_.category, VOID)]; - - basisType_p = Basic::basisType_p // - [assign_a(self.result_.name_)] // - [assign_a(self.result_.category, BASIS)]; - - eigenType_p = Basic::eigenType_p // - [assign_a(self.result_.name_)] // - [assign_a(self.result_.category, EIGEN)]; - - namespace_del_p = Basic::namespace_p // - [push_back_a(self.result_.namespaces_)] >> str_p("::"); - - class_p = *namespace_del_p >> Basic::className_p // - [assign_a(self.result_.name_)] // - [assign_a(self.result_.category, CLASS)]; - - type_p = void_p | basisType_p | class_p | eigenType_p; - } - - Rule const& start() const { - return type_p; - } - - }; -}; -// type_grammar - -/* ************************************************************************* */ -// http://boost-spirit.com/distrib/spirit_1_8_2/libs/spirit/doc/grammar.html -template -struct TypeListGrammar: public classic::grammar > { - - typedef std::vector TypeList; - TypeList& result_; ///< successful parse will be placed in here - - /// Construct type grammar and specify where result is placed - TypeListGrammar(TypeList& result) : - result_(result) { - } - - /// Definition of type grammar - template - struct definition { - - wrap::Qualified type; ///< temporary for use during parsing - TypeGrammar type_g; ///< Individual Type grammars - - classic::rule type_p, typeList_p; - - definition(TypeListGrammar const& self) : - type_g(type) { - using namespace classic; - - type_p = type_g[push_back_a(self.result_, type)][clear_a(type)]; - - typeList_p = OPEN >> !type_p >> *(',' >> type_p) >> CLOSE; - } - - classic::rule const& start() const { - return typeList_p; - } - - }; -}; -// TypeListGrammar - -/* ************************************************************************* */ -// Needed for other parsers in Argument.h and ReturnType.h -static const bool T = true; - -} // \namespace wrap - diff --git a/wrap/README.md b/wrap/README.md deleted file mode 100644 index 014577b5a..000000000 --- a/wrap/README.md +++ /dev/null @@ -1,27 +0,0 @@ -# WRAP README - -The wrap library wraps the GTSAM library into a MATLAB toolbox. - -It was designed to be more general than just wrapping GTSAM, but a small amount of GTSAM specific code exists in matlab.h, the include file that is included by the mex files. The GTSAM-specific functionality consists primarily of handling of Eigen Matrix and Vector classes. - -For notes on creating a wrap interface, see gtsam.h for what features can be wrapped into a toolbox, as well as the current state of the toolbox for gtsam. For more technical details on the interface, please read comments in matlab.h - -Some good things to know: - -OBJECT CREATION - -- Classes are created by special constructors, e.g., new_GaussianFactorGraph_.cpp. - These constructors are called from the MATLAB class @GaussianFactorGraph. - new_GaussianFactorGraph_ calls wrap_constructed in matlab.h, see documentation there - -METHOD (AND CONSTRUCTOR) ARGUMENTS - -- Simple argument types of methods, such as "double", will be converted in the - mex wrappers by calling unwrap, defined in matlab.h -- Vector and Matrix arguments are normally passed by reference in GTSAM, but - in gtsam.h you need to pretend they are passed by value, to trigger the - generation of the correct conversion routines unwrap and unwrap -- passing classes as arguments works, provided they are passed by reference. - This triggers a call to unwrap_shared_ptr - - \ No newline at end of file diff --git a/wrap/ReturnType.cpp b/wrap/ReturnType.cpp deleted file mode 100644 index fdf86d975..000000000 --- a/wrap/ReturnType.cpp +++ /dev/null @@ -1,101 +0,0 @@ -/** - * @file ReturnType.cpp - * @date Nov 13, 2014 - * @author Frank Dellaert - */ - -#include "ReturnType.h" -#include "Class.h" -#include "utilities.h" -#include - -using namespace std; -using namespace wrap; - -/* ************************************************************************* */ -void ReturnType::wrap_result(const string& out, const string& result, - FileWriter& wrapperFile, - const TypeAttributesTable& typeAttributes) const { - string cppType = qualifiedName("::"), matlabType = qualifiedName("."); - - if (category == CLASS) { - // Handle Classes - string objCopy, ptrType; - const bool isVirtual = typeAttributes.attributes(cppType).isVirtual; - if (isPtr) - objCopy = result; // a shared pointer can always be passed as is - else { - // but if we want an actual new object, things get more complex - if (isVirtual) - // A virtual class needs to be cloned, so the whole hierarchy is - // returned - objCopy = result + ".clone()"; - else { - // ...but a non-virtual class can just be copied - objCopy = "boost::make_shared<" + cppType + ">(" + result + ")"; - } - } - // e.g. out[1] = wrap_shared_ptr(pairResult.second,"gtsam.Point3", false); - wrapperFile.oss << out << " = wrap_shared_ptr(" << objCopy << ",\"" - << matlabType << "\", " << (isVirtual ? "true" : "false") - << ");\n"; - - } else if (isPtr) { - // Handle shared pointer case for BASIS/EIGEN/VOID - // This case does not actually occur in GTSAM wrappers, so untested! - wrapperFile.oss << " {\n boost::shared_ptr<" << qualifiedName("::") - << "> shared(" << result << ");" << endl; - wrapperFile.oss << out << " = wrap_shared_ptr(shared,\"" << matlabType - << "\");\n }\n"; - - } else if (matlabType != "void") - // Handle normal case case for BASIS/EIGEN - wrapperFile.oss << out << " = wrap< " << qualifiedName("::") << " >(" << result - << ");\n"; -} - -/* ************************************************************************* */ -void ReturnType::emit_cython_pxd( - FileWriter& file, const std::string& className, - const std::vector& templateArgs) const { - string cythonType; - if (name() == "This") - cythonType = className; - else if (match(templateArgs)) - cythonType = name(); - else - cythonType = pxdClassName(); - if (isPtr) cythonType = "shared_ptr[" + cythonType + "]"; - file.oss << cythonType; -} - -/* ************************************************************************* */ -std::string ReturnType::pyx_returnType(bool addShared) const { - string retType = pxd_class_in_pyx(); - if (isPtr || (isNonBasicType() && addShared)) - retType = "shared_ptr[" + retType + "]"; - return retType; -} - -/* ************************************************************************* */ -std::string ReturnType::pyx_casting(const std::string& var, - bool isSharedVar) const { - if (isEigen()) { - string s = "ndarray_copy(" + var + ")"; - if (pyxClassName() == "Vector") - return s + ".squeeze()"; - else return s; - } - else if (isNonBasicType()) { - if (isPtr || isSharedVar) - return pyxClassName() + ".cyCreateFromShared(" + var + ")"; - else { - // construct a shared_ptr if var is not a shared ptr - return pyxClassName() + ".cyCreateFromShared(" + make_shared_pxd_class_in_pyx() + - + "(" + var + "))"; - } - } else - return var; -} - -/* ************************************************************************* */ diff --git a/wrap/ReturnType.h b/wrap/ReturnType.h deleted file mode 100644 index 8d78bb48f..000000000 --- a/wrap/ReturnType.h +++ /dev/null @@ -1,89 +0,0 @@ -/** - * @file ReturnValue.h - * @brief Encapsulates a return type of a method - * @date Nov 13, 2014 - * @author Frank Dellaert - */ - -#include "Qualified.h" -#include "FileWriter.h" -#include "TypeAttributesTable.h" -#include "utilities.h" -#include - -#pragma once - -namespace wrap { - -/** - * Encapsulates return value of a method or function - */ -struct ReturnType : public Qualified { - bool isPtr; - - friend struct ReturnValueGrammar; - - /// Makes a void type - ReturnType() : isPtr(false) {} - - /// Constructor, no namespaces - ReturnType(const std::string& name, Category c = CLASS, bool ptr = false) - : Qualified(name, c), isPtr(ptr) {} - - void clear() override { - Qualified::clear(); - isPtr = false; - } - - /// Check if this type is in a set of valid types - template - void verify(TYPES validtypes, const std::string& s) const { - std::string key = qualifiedName("::"); - if (find(validtypes.begin(), validtypes.end(), key) == validtypes.end()) - throw DependencyMissing(key, "checking return type of " + s); - } - - /// @param className the actual class name to use when "This" is specified - void emit_cython_pxd(FileWriter& file, const std::string& className, - const std::vector& templateArgs) const; - - std::string pyx_returnType(bool addShared = true) const; - std::string pyx_casting(const std::string& var, - bool isSharedVar = true) const; - -private: - friend struct ReturnValue; - - /// Example: out[1] = wrap_shared_ptr(pairResult.second,"Test", false); - void wrap_result(const std::string& out, const std::string& result, - FileWriter& wrapperFile, - const TypeAttributesTable& typeAttributes) const; -}; - -//****************************************************************************** -// http://boost-spirit.com/distrib/spirit_1_8_2/libs/spirit/doc/grammar.html -struct ReturnTypeGrammar : public classic::grammar { - wrap::ReturnType& result_; ///< successful parse will be placed in here - - TypeGrammar type_g; - - /// Construct ReturnType grammar and specify where result is placed - ReturnTypeGrammar(wrap::ReturnType& result) - : result_(result), type_g(result_) {} - - /// Definition of type grammar - template - struct definition { - classic::rule type_p; - - definition(ReturnTypeGrammar const& self) { - using namespace classic; - type_p = self.type_g >> !ch_p('*')[assign_a(self.result_.isPtr, T)]; - } - - classic::rule const& start() const { return type_p; } - }; -}; -// ReturnTypeGrammar - -} // \namespace wrap diff --git a/wrap/ReturnValue.cpp b/wrap/ReturnValue.cpp deleted file mode 100644 index e58e85602..000000000 --- a/wrap/ReturnValue.cpp +++ /dev/null @@ -1,102 +0,0 @@ -/** - * @file ReturnValue.cpp - * @date Dec 1, 2011 - * @author Alex Cunningham - * @author Andrew Melim - * @author Richard Roberts - */ - -#include "ReturnValue.h" -#include "utilities.h" -#include - -using namespace std; -using namespace wrap; - -/* ************************************************************************* */ -ReturnValue ReturnValue::expandTemplate(const TemplateSubstitution& ts) const { - ReturnValue instRetVal = *this; - instRetVal.type1 = ts.tryToSubstitite(type1); - if (isPair) instRetVal.type2 = ts.tryToSubstitite(type2); - return instRetVal; -} - -/* ************************************************************************* */ -string ReturnValue::returnType() const { - if (isPair) - return "pair< " + type1.qualifiedName("::") + ", " + - type2.qualifiedName("::") + " >"; - else - return type1.qualifiedName("::"); -} - -/* ************************************************************************* */ -string ReturnValue::matlab_returnType() const { - return isPair ? "[first,second]" : "result"; -} - -/* ************************************************************************* */ -void ReturnValue::wrap_result(const string& result, FileWriter& wrapperFile, - const TypeAttributesTable& typeAttributes) const { - if (isPair) { - // For a pair, store the returned pair so we do not evaluate the function - // twice - wrapperFile.oss << " auto pairResult = " << result - << ";\n"; - type1.wrap_result(" out[0]", "pairResult.first", wrapperFile, - typeAttributes); - type2.wrap_result(" out[1]", "pairResult.second", wrapperFile, - typeAttributes); - } else { // Not a pair - type1.wrap_result(" out[0]", result, wrapperFile, typeAttributes); - } -} - -/* ************************************************************************* */ -void ReturnValue::emit_matlab(FileWriter& proxyFile) const { - string output; - if (isPair) - proxyFile.oss << "[ varargout{1} varargout{2} ] = "; - else if (type1.category != ReturnType::VOID) - proxyFile.oss << "varargout{1} = "; -} - -/* ************************************************************************* */ -void ReturnValue::emit_cython_pxd( - FileWriter& file, const std::string& className, - const std::vector& templateArgs) const { - if (isPair) { - file.oss << "pair["; - type1.emit_cython_pxd(file, className, templateArgs); - file.oss << ","; - type2.emit_cython_pxd(file, className, templateArgs); - file.oss << "] "; - } else { - type1.emit_cython_pxd(file, className, templateArgs); - file.oss << " "; - } -} - -/* ************************************************************************* */ -std::string ReturnValue::pyx_returnType() const { - if (isVoid()) return ""; - if (isPair) { - return "pair [" + type1.pyx_returnType(false) + "," + - type2.pyx_returnType(false) + "]"; - } else { - return type1.pyx_returnType(true); - } -} - -/* ************************************************************************* */ -std::string ReturnValue::pyx_casting(const std::string& var) const { - if (isVoid()) return ""; - if (isPair) { - return "(" + type1.pyx_casting(var + ".first", false) + "," + - type2.pyx_casting(var + ".second", false) + ")"; - } else { - return type1.pyx_casting(var); - } -} - -/* ************************************************************************* */ diff --git a/wrap/ReturnValue.h b/wrap/ReturnValue.h deleted file mode 100644 index 721132797..000000000 --- a/wrap/ReturnValue.h +++ /dev/null @@ -1,126 +0,0 @@ -/** - * @file ReturnValue.h - * - * @brief Encapsulates a return value from a method - * @date Dec 1, 2011 - * @author Alex Cunningham - * @author Richard Roberts - */ - -#include "ReturnType.h" -#include "TemplateSubstitution.h" -#include "FileWriter.h" -#include "TypeAttributesTable.h" -#include "utilities.h" - -#pragma once - -namespace wrap { - -/** - * Encapsulates return type of a method or function, possibly a pair - */ -struct ReturnValue { - - bool isPair; - ReturnType type1, type2; - - friend struct ReturnValueGrammar; - - /// Default constructor - ReturnValue() : - isPair(false) { - } - - /// Construct from type - ReturnValue(const ReturnType& type) : - isPair(false), type1(type) { - } - - /// Construct from pair type arguments - ReturnValue(const ReturnType& t1, const ReturnType& t2) : - isPair(true), type1(t1), type2(t2) { - } - - /// Destructor - virtual ~ReturnValue() {} - - virtual void clear() { - type1.clear(); - type2.clear(); - isPair = false; - } - - bool isVoid() const { - return !isPair && !type1.isPtr && (type1.name() == "void"); - } - - bool operator==(const ReturnValue& other) const { - return isPair == other.isPair && type1 == other.type1 - && type2 == other.type2; - } - - /// Substitute template argument - ReturnValue expandTemplate(const TemplateSubstitution& ts) const; - - std::string returnType() const; - - std::string matlab_returnType() const; - - void wrap_result(const std::string& result, FileWriter& wrapperFile, - const TypeAttributesTable& typeAttributes) const; - - void emit_matlab(FileWriter& proxyFile) const; - - /// @param className the actual class name to use when "This" is specified - void emit_cython_pxd(FileWriter& file, const std::string& className, - const std::vector& templateArgs) const; - std::string pyx_returnType() const; - std::string pyx_casting(const std::string& var) const; - - friend std::ostream& operator<<(std::ostream& os, const ReturnValue& r) { - if (!r.isPair && r.type1.category == ReturnType::VOID) - os << "void"; - else - os << r.returnType(); - return os; - } - -}; - -//****************************************************************************** -// http://boost-spirit.com/distrib/spirit_1_8_2/libs/spirit/doc/grammar.html -struct ReturnValueGrammar: public classic::grammar { - - wrap::ReturnValue& result_; ///< successful parse will be placed in here - ReturnTypeGrammar returnType1_g, returnType2_g; ///< Type parsers - - /// Construct type grammar and specify where result is placed - ReturnValueGrammar(wrap::ReturnValue& result) : - result_(result), returnType1_g(result.type1), returnType2_g(result.type2) { - } - - /// Definition of type grammar - template - struct definition { - - classic::rule pair_p, returnValue_p; - - definition(ReturnValueGrammar const& self) { - using namespace classic; - - pair_p = (str_p("pair") >> '<' >> self.returnType1_g >> ',' - >> self.returnType2_g >> '>')[assign_a(self.result_.isPair, T)]; - - returnValue_p = pair_p | self.returnType1_g; - } - - classic::rule const& start() const { - return returnValue_p; - } - - }; -}; -// ReturnValueGrammar - -}// \namespace wrap diff --git a/wrap/StaticMethod.cpp b/wrap/StaticMethod.cpp deleted file mode 100644 index 0f812ea61..000000000 --- a/wrap/StaticMethod.cpp +++ /dev/null @@ -1,151 +0,0 @@ -/* ---------------------------------------------------------------------------- - - * GTSAM Copyright 2010, Georgia Tech Research Corporation, - * Atlanta, Georgia 30332-0415 - * All Rights Reserved - * Authors: Frank Dellaert, et al. (see THANKS for the full author list) - - * See LICENSE for the license information - - * -------------------------------------------------------------------------- */ - -/** - * @file StaticMethod.ccp - * @author Frank Dellaert - * @author Andrew Melim - * @author Richard Roberts - **/ - -#include "StaticMethod.h" -#include "utilities.h" -#include "Class.h" - -#include -#include - -#include -#include - -using namespace std; -using namespace wrap; - -/* ************************************************************************* */ -void StaticMethod::proxy_header(FileWriter& proxyFile) const { - string upperName = matlabName(); - upperName[0] = toupper(upperName[0], locale()); - proxyFile.oss << " function varargout = " << upperName << "(varargin)\n"; -} - -/* ************************************************************************* */ -string StaticMethod::wrapper_call(FileWriter& wrapperFile, Str cppClassName, - Str matlabUniqueName, const ArgumentList& args) const { - // check arguments - // NOTE: for static functions, there is no object passed - wrapperFile.oss << " checkArguments(\"" << matlabUniqueName << "." << name_ - << "\",nargout,nargin," << args.size() << ");\n"; - - // unwrap arguments, see Argument.cpp - args.matlab_unwrap(wrapperFile, 0); // We start at 0 because there is no self object - - // call method and wrap result - // example: out[0]=wrap(staticMethod(t)); - string expanded = cppClassName + "::" + name_; - if (templateArgValue_) - expanded += ("<" + templateArgValue_->qualifiedName("::") + ">"); - - return expanded; -} - -/* ************************************************************************* */ -void StaticMethod::emit_cython_pxd(FileWriter& file, const Class& cls) const { - for(size_t i = 0; i < nrOverloads(); ++i) { - file.oss << " @staticmethod\n"; - file.oss << " "; - returnVals_[i].emit_cython_pxd(file, cls.pxdClassName(), cls.templateArgs); - file.oss << name_ + ((i>0)?"_" + to_string(i):"") << " \"" << name_ << "\"" << "("; - argumentList(i).emit_cython_pxd(file, cls.pxdClassName(), cls.templateArgs); - file.oss << ") except +\n"; - } -} - -/* ************************************************************************* */ -void StaticMethod::emit_cython_wrapper_pxd(FileWriter& file, - const Class& cls) const { - if (nrOverloads() > 1) { - for (size_t i = 0; i < nrOverloads(); ++i) { - string funcName = name_ + "_" + to_string(i); - file.oss << " @staticmethod\n"; - file.oss << " cdef tuple " + funcName + "(tuple args, dict kwargs)\n"; - } - } -} - -/* ************************************************************************* */ -void StaticMethod::emit_cython_pyx_no_overload(FileWriter& file, - const Class& cls) const { - assert(nrOverloads() == 1); - file.oss << " @staticmethod\n"; - file.oss << " def " << name_ << "("; - argumentList(0).emit_cython_pyx(file); - file.oss << "):\n"; - - /// Call cython corresponding function and return - file.oss << argumentList(0).pyx_convertEigenTypeAndStorageOrder(" "); - string call = pyx_functionCall(cls.pxd_class_in_pyx(), name_, 0); - file.oss << " "; - if (!returnVals_[0].isVoid()) { - file.oss << "return " << returnVals_[0].pyx_casting(call) << "\n"; - } else - file.oss << call << "\n"; - file.oss << "\n"; -} - -/* ************************************************************************* */ -void StaticMethod::emit_cython_pyx(FileWriter& file, const Class& cls) const { - size_t N = nrOverloads(); - if (N == 1) { - emit_cython_pyx_no_overload(file, cls); - return; - } - - // Dealing with overloads.. - file.oss << " @staticmethod # overloaded\n"; - file.oss << " def " << name_ << "(*args, **kwargs):\n"; - for (size_t i = 0; i < N; ++i) { - string funcName = name_ + "_" + to_string(i); - file.oss << " success, results = " << cls.pyxClassName() << "." - << funcName << "(args, kwargs)\n"; - file.oss << " if success:\n return results\n"; - } - file.oss << " raise TypeError('Could not find the correct overload')\n\n"; - - // Create cdef methods for all overloaded methods - for(size_t i = 0; i < N; ++i) { - string funcName = name_ + "_" + to_string(i); - file.oss << " @staticmethod\n"; - file.oss << " cdef tuple " + funcName + "(tuple args, dict kwargs):\n"; - file.oss << " cdef list __params\n"; - if (!returnVals_[i].isVoid()) { - file.oss << " cdef " << returnVals_[i].pyx_returnType() << " return_value\n"; - } - file.oss << " try:\n"; - ArgumentList args = argumentList(i); - file.oss << pyx_resolveOverloadParams(args, false, 3); - - /// Call cython corresponding function and return - file.oss << args.pyx_convertEigenTypeAndStorageOrder(" "); - string pxdFuncName = name_ + ((i>0)?"_" + to_string(i):""); - string call = pyx_functionCall(cls.pxd_class_in_pyx(), pxdFuncName, i); - if (!returnVals_[i].isVoid()) { - file.oss << " return_value = " << call << "\n"; - file.oss << " return True, " << returnVals_[i].pyx_casting("return_value") << "\n"; - } else { - file.oss << " " << call << "\n"; - file.oss << " return True, None\n"; - } - file.oss << " except:\n"; - file.oss << " return False, None\n\n"; - } -} - -/* ************************************************************************* */ diff --git a/wrap/StaticMethod.h b/wrap/StaticMethod.h deleted file mode 100644 index dbb918596..000000000 --- a/wrap/StaticMethod.h +++ /dev/null @@ -1,51 +0,0 @@ -/* ---------------------------------------------------------------------------- - - * GTSAM Copyright 2010, Georgia Tech Research Corporation, - * Atlanta, Georgia 30332-0415 - * All Rights Reserved - * Authors: Frank Dellaert, et al. (see THANKS for the full author list) - - * See LICENSE for the license information - - * -------------------------------------------------------------------------- */ - -/** - * @file StaticMethod.h - * @brief describes and generates code for static methods - * @author Frank Dellaert - * @author Alex Cunningham - * @author Richard Roberts - **/ - -#pragma once - -#include "MethodBase.h" - -namespace wrap { - -/// StaticMethod class -struct StaticMethod: public MethodBase { - - typedef const std::string& Str; - - friend std::ostream& operator<<(std::ostream& os, const StaticMethod& m) { - for (size_t i = 0; i < m.nrOverloads(); i++) - os << "static " << m.returnVals_[i] << " " << m.name_ << m.argLists_[i]; - return os; - } - - void emit_cython_pxd(FileWriter& file, const Class& cls) const; - void emit_cython_wrapper_pxd(FileWriter& file, const Class& cls) const; - void emit_cython_pyx(FileWriter& file, const Class& cls) const; - void emit_cython_pyx_no_overload(FileWriter& file, const Class& cls) const; - -protected: - - void proxy_header(FileWriter& proxyFile) const override; - - std::string wrapper_call(FileWriter& wrapperFile, Str cppClassName, - Str matlabUniqueName, const ArgumentList& args) const override; -}; - -} // \namespace wrap - diff --git a/wrap/Template.h b/wrap/Template.h deleted file mode 100644 index 32f8e9761..000000000 --- a/wrap/Template.h +++ /dev/null @@ -1,146 +0,0 @@ -/* ---------------------------------------------------------------------------- - - * GTSAM Copyright 2010, Georgia Tech Research Corporation, - * Atlanta, Georgia 30332-0415 - * All Rights Reserved - * Authors: Frank Dellaert, et al. (see THANKS for the full author list) - - * See LICENSE for the license information - - * -------------------------------------------------------------------------- */ - -/** - * @file Template.h - * @brief Template name - * @author Frank Dellaert - * @date Nov 11, 2014 - **/ - -#pragma once - -#include - -namespace wrap { - -/// The template specification that goes before a method or a class -class Template { - std::string argName_; - std::vector argValues_; - std::vector intList_; - friend struct TemplateGrammar; -public: - /// The only way to get values into a Template is via our friendly Grammar - Template() { - } - void clear() { - argName_.clear(); - argValues_.clear(); - intList_.clear(); - } - const std::string& argName() const { - return argName_; - } - const std::vector& intList() const { - return intList_; - } - const std::vector& argValues() const { - return argValues_; - } - bool empty() const { - return argValues_.empty() && intList_.empty(); - } - size_t nrValues() const { - return argValues_.size(); - } - const Qualified& operator[](size_t i) const { - return argValues_[i]; - } - bool valid() const { - return !argName_.empty() && argValues_.size() > 0; - } - -}; - -/* ************************************************************************* */ -// http://boost-spirit.com/distrib/spirit_1_8_2/libs/spirit/doc/grammar.html -struct IntListGrammar: public classic::grammar { - - typedef std::vector IntList; - IntList& result_; ///< successful parse will be placed in here - - /// Construct type grammar and specify where result is placed - IntListGrammar(IntList& result) : - result_(result) { - } - - /// Definition of type grammar - template - struct definition { - - classic::rule integer_p, intList_p; - - definition(IntListGrammar const& self) { - using namespace classic; - - integer_p = int_p[push_back_a(self.result_)]; - - intList_p = '{' >> !integer_p >> *(',' >> integer_p) >> '}'; - } - - classic::rule const& start() const { - return intList_p; - } - - }; -}; -// IntListGrammar - -/* ************************************************************************* */ -// http://boost-spirit.com/distrib/spirit_1_8_2/libs/spirit/doc/grammar.html -struct TemplateGrammar: public classic::grammar { - - Template& result_; ///< successful parse will be placed in here - TypeListGrammar<'{', '}'> argValues_g; ///< TypeList parser - IntListGrammar intList_g; ///< TypeList parser - - /// Construct type grammar and specify where result is placed - TemplateGrammar(Template& result) : - result_(result), argValues_g(result.argValues_), // - intList_g(result.intList_) { - } - - /// Definition of type grammar - template - struct definition: BasicRules { - - classic::rule templateArgValues_p; - - definition(TemplateGrammar const& self) { - using classic::str_p; - using classic::assign_a; - templateArgValues_p = (str_p("template") >> '<' - >> (BasicRules::name_p)[assign_a(self.result_.argName_)] - >> '=' >> (self.argValues_g | self.intList_g) >> '>'); - } - - classic::rule const& start() const { - return templateArgValues_p; - } - - }; -}; -// TemplateGrammar - -/// Cool initializer for tests -static inline boost::optional

    Ew=}apba7r<^;vmEYAydTieR{k14aMtQJ7p>63{G za1O2D_E+B-`v)|N1M%%2a3uw7%chH2izn|)S`9d8V<5XN1ujJg{Dz4sDc2WsHhduU zYKjBo&p>h7PE;uG6VOUdXVmKeNT9K?F;GKY02Jwz_a^;>@#3I(G4s?Bh@6bf#nlxo zBIv3!Kp1ZckVUJ9hs4Ch-ayO)eDeb*C%}Zt9%LJ0V_^lN6oFLD_mksG07Se>4s-Gy zDFS`4Oz}adQ@fYKhMb8Ex{H+tqV-=HsrFB0GCnBZsh6p6efXenBDxqeC?q3;>~sSf zifteZ$pDxMXlif@PA*s!B1_Oa04Ou=?(9%GV+vtg09OjQD2ZGMf2jWZW;R0V^8lpU zPj`{w;a|8=IrZE@Rtwf^`D(6AlRXb~^FsqAYCuT@bwB@kU|+~*b3hPEec}-$K-6*d z0X5XoJB7!c?IHw>BvmxAs|WPc@ma(U_}70p?x{FCUv_i|_^wruOecT_SvpcugFq?* z2xUS;L9HW)^_Kplg(NIoF;h{A*Qo)O@sg4~_rqoigQ9|-<2q(ykE4&^u2gzGSp=ky z0p>0uG7`&sZS?j>Q z!z^Oc-SJ`|$0aE%oAmDuOWI7TMZDWaKz{!h3Uz|S!SD4I@YQ>d7N@@&qN1XBYj3I` zrcb+;xy;8Y_bh3r=Q7x=Qm@|gdI9yd$<&cnY8sl(V94IRlSyUiYj0lx zb7J?BJPid1?Tv~O^VqHiSQ}7MQpRvmR<|8yea+1Uoz(V$x@cTn6^I2vCkPl=*nUFH zSU=#(RJrMCo#hH@-OkM^C@8=sV;@meNT`=EDxKOIX7xh_3tLA9z^h(rOiavABRKBuKuYKf7dChX3p5-Y z6VRNrNd7B;U-c3q0ym>fNly=ivHo$ifF8jZ*lPRxmi0gsm9)wOv=g#(a%ur`cp7CF zXJ@Ygp9UBvFwLKUzY0z$4i*-ryK|7n0}+B|qf=Rv{J($w|MZE?zu~*2no$1lZONZH zklW~+BXD#7A6k7&8Cjcvmfajo9REv`ZYyO;n>j|LmMzt*B8VDl^*Af6X}yXAU#sZ` z2p$KnpHaIm_WP63`3nzsV)E8$Bygy)m|d5m;YDFWXVz~zuFY#Wc#_`5`DyAI{b+zx zu+1N%e9u{jAhfp~R>o$HN1;+#wdc-05A~(GT$_QsWG<{+Ysr}>woaOzG~v4&N#FOK z#3REgbj{$?rt*Tt*l+6tYBYT<4hEmutix;z{1gtI2FMJ`%h^nA94zA4%W?eRtgWl+sLA5nsMFp3T^HFS&P;(1TUcISrd3=hXI(bOXA2dwq2mmO z+?cYWz*>8B$~*iMo2=S4h7y5AppDFk@22BDLQuJw2`(ZGn{P)Tnr9iWgRW#-XoZM( z=&lTYtD7GvUqEJLWYLs71uf8P>yq?s5 z@1kbIpNxo@I)$+riO^g^veb@(eDY_xjw%jZl#Xbijq_ZS&&|GhQoYxefPt{CA3un0 zt+1BL#^YGgDA^Jgvqx4-^}TPHvo5TqPZD9~>;HKnb--T3jCafH=YYG%+-vaRs1t&r z;lX#@B{3NXL?R;L z%J7y*;E(e+aSzbCo2`5Qo2|!0!btL8TTj5u!CubDPSD2cvyHWpwF3zU34@@GrH!59 zXFUTW5(Xh7Co=;hQ9C`?|HC#FGcq$Vbs%BkU?gEsbkuin{S3Y(Zlz}eeo=b*gPN?q zxsibb34^McA=uDtEZ~3sXLG-2X8KYrc?4oO zF%kBEv)0W2(^`v|SvnZmfpxUhb1)JzGO#fOYxKMlOe9Qfod3_dFq1GbF>|u~*FU}o zWBk{OF)_afE6vM`VDDgOq-TZTk{daxIs`IvfxuVUr2!yYH*T^qN-v{M)3^d z%E;F=sCBXl$N~n!hXvwa^LXoUf!_uBoxIO_k400HED~R6ig8WPLAT4n%@S{Yf#if9 z(mh!4Uprix^&^~b(|Hs~B>5h=L2RY=lf%x`|Dy~&zi>(`C&RlRkJF_-auCEILj_R> z)Z$?v8qzfF@8tOhI?=8G^b_S&5`|YM3ONd5Ac@U~mqc=TfRBYCq?iV<9h@LfKdGzV$St0 z_+cxA)6j^VJi$=?!TNehhKlN?vkwjd3b9XQS~Nx*Xtj&za(c3Iy5u@8_0c506R@ zqKS_szaKA!?C71Gyl?OxN$vqFeD8`W<~+EPcZ|2k3nslfEI|SvV^DV3Xk7 zKAuwxNbA;qM7KQ8HD#mMagteV-6sio-Aibi1M8Qn`Iw*DxfPYOz;(9dXw<%mjO|TJz)sB9Ha;^m4*l0?k|6|Tx$C?t z0h|AluM27U(@QRXT>%INo*M{S!t~JxT-rwhh~P8g0>05SoV*hovNq`D-*+ghFFu>z z6Tr7HNe(eX$Jj0Ns*TbMw-p&*I*uci_^G`*oRaX4WI4j%BuY zTay08qc20;*44{vqdtz;50JW5T#w)jes|C(&>Y#1J`B?JchCqB99oZ%y1NbcFYQ_} zPp&W?ruYZ7(=&8+3i;T#j5HoQym5n0BGzK|wId7jZ%)`>)Dy?%bFyzy z-%;St7>^Dc@_a(qDA68Y3@-DL5e+1?b$h&tdB;3I7=CH4r608d6jq-zmKKD*T1yq-t>m(Sf#q8Jhyf6JdUmS z0ZK_$+Fhd%KTsv+V@gSNDG`GgTy;xu$18i4>(JoVj(oUUONUi|6rGH48$E5V!OJP- zxj-tvByGMMbF*$`p@A5>nW3X$<6xS)zPnk*4c!ra7UIOm+3RFJ(J~=*v8Xz`Bv7qm zRF-1*P#u}Cch1eMyGg^#!3-j`=26kL^etDFVzoF7f(9)m)W|W>}3SQwdu+kS-6`!%g&-x2rOjGYLQXf8g*V~ zI4Z*sZXE|F$fbNEPNU6Xk`XPW`GmCM67`3sxx1-~7Au*75!V_PJL@BNPxFV^9lm09 zQ@rcV%BGnwEalPqytI9-6=V)sTDfv)0l(Q_HNUaV71YDlwrt3j^cd_CIhLaI7Y6KlXPs(A)8{*i(*Z)Fg>GWS+ij3 z+3KSfcNg4E=zbVwy)Z-DChnrOstNK1dJdUFNq$$uQp93iW(2*|tLy6k{a>v2w&`X+ z(-`zV`ODiHs0~MYIU{>GlHXt|;MCau9A7%kdutw$6Ddr)%*9q&jU^4C#?!d+DqrMm zYYxlHQD%IC+Oqn`J=;;}hH>%4n>1>>y4?7_x4sK%FvLbTB$uwk)4LfNQNMRS#z5W7 z5*nbj6K?!?Mdvf;2{rk&hLme%-Z;I)Y9^0o@MY>jwO0g^Af|G842Tru^-8|*-`VYQ@vLV?Fw zs-aEgU`phBlwKqiDGwN3nu|arzL#nSTe}pT1I}{fb#4$a7F!v&rFuivm-tcyW!yC1 z*k6lL{4pi(h=BQx$h%>_&(^0?q|K7PtHFNONgL_xg5S4-N=?7v>{>o~c(0UsRFIf> zzrXqR{Jll?SC`h*>eS%H<9XI(Rqb9QF{+`mHNO|MJX?FSjx`XDK7GX~s1mGYCS7N6 z*(^fuCMeK2cI9CCy~fYerDP^iuhBIloYr2}_FR5Q4Do9Xd)vpDssHORB+T*luk2j# zZ703^X6u?eoM6{mnvS+qP7}iXjm_+bSN_tUt#?#Y2eM?vd-6VBPFQMxnknFBh#}_m z9eYS-tR96oQc}r~PDQtW9hW=KeMx&-xm!AVr07!wi*gLNk`aiT@USa1nDZ%3BH4{_ zOo%ynxJme4g_XA7jbY%+_yPWFy`eICD$nfI9oshiz}0+%+I1tU7FK%;&g^JqoMZbX zBKqr@1bC-W6D_MbX6=I)t~bP^a&zd|7KCWCb{KRe3LBmI?~+6V5bb3@9viF$sYeHE zh^)w7&(~PAqR@9wCt7=3GQ&<;2NCZ z?snkd?wa5b+zIaP?(XjH?(RWy`PaR7YNqDS!*q2&?CQ1l+Iv^O_4oUh3yh3169n!7 zp|JoMZ7zAm8CWt>_-09TY}SCOmSfyEG@p1XW2W`nx#s5E&&TY(E*Y^;ntnov_S_Ei zcbXk{UqcMUysTge68`naw{lv4HVi3)ou^6x=r>M?Co{1Cx87iFY^bV^l2DA-?4)K_5?aBl(#53~ zCBdi+1iDMq&)d!lyd6Y*yUv$!=J3@J=O_JI3Xr7XIkENHV4yc7{gePg90aX_)!)_J zifW|c;!`*Sjh_?pW;Wjr;T|&_qeDu>Ca;&^Qc}*QbxgD)V->3tc5l`0(%sL%Sl(WvL#V&kZ z*x<@KFZk}aYq6pK8ZMS~%G71DD-~?9y4;SHGXU!!XyV!P!Dvy$z$0k}9}0 zo2!$iBP{g2i!xlCU!K`zJS_~9KWc!x^2@RY$)~321J6wh)-Y$E4Yu*RU(ljB_5WI& zAK8VDo~r{bnTQ6<2r-lkM6Y6&OjRyKXkLZY@ek{tZEi7|gp3%gw6E#Ls=HzHXax?2 z58-6W7VGSIJQ4JK$TEQQwVNkbgI4(YVcbHbPe;x2@|dV0E2-#C)aIEjDszEzRI7t6 z=us`yYda_%6CL?Jxd!+$NTYWzrmM*Z zCL10_O@2pAS8-ND|MQNP=)EI%Z)3eZ)z6R* zg`ONLt}qkb%cNv?(oq=}V-aze%{&!xDkjmTB88HA_*6hNp#vdaoxsG*yr#?(A)Jn= zO$BDlYEKdkq)~p0+5Mr=W>opiWJO>6*Yo5#V&>F{aFn=Y99{8pD8S)f4D@839Xu;K zz%=)W?cD*nX`04bT;%w9tdDC=KR;DY)4(k!c_J1=P&HY(BNJX{sCUSIPvQAhfeLI! zQaf`JFORyj5>8r9WChae6WDF@c<4QR*=U~DK|xO;RdppQeQ!?_Ah)#?u&;OCQ;m-} z(Ji^&C%8}~BtZ0za+?b2Qq`LAh;qS7jbYvtQIOeEP!j6ehDx=(D?mDR?Ef$_>^M-L zH$;B$a#Q`0BRZ$PQ4 z%-wW?!5#Dzq8KIU(7G24^bw!KQ!>NIm58>Td(XW zuPxSo%|(Y(!}-S(TPdLu1jWdF{y4Sqc;PZU(gir)=k$3k1H`-ahdSE z#!O(ZhA8|nFFT^TBsixg=by?zv&L+>W!a2v&8XPx==)b4mhnsryAwB=#PgIV1rBjC zZ(=sQd_7tDWMtXgBv^R5>xQLN22xtfbX0oHu6p=<2v6DYz2}vE(@piO`E!sE+JixutRzrA+kQU!KIammtX^ z0%Kk1f#1`6Bsc$AUHgENZhY3g0gQ|istWa_gcK+xTR!~e`;Lqzf!&?bgPh(&5ejk3 ziOEF%ir{=ja0a9QB`oV~4()5Bn&6Gb=#~6&P~7MFg~xCAw@>r6oPSK&SkxMGvdO4% zQt#JB+WZG}uhMVx4Y+pAd}U!Wwl3mE>MqqO$-a(X1QQ5;txFNPC0r-{HsRyS!T3U; z4dg^SJ&+9B$i7|j;0`-K-bECe&*=Awms7NFK9?;S%jYyBlJ933=ty;yACfqK6moXn z=L{Zv8nrf6f*Mr)-5s8<(943cF@GX<52^xovBOmGyicJ zIC&t8CQfR>br#r3&=gVOuFwa)?!b9hk!CXoKN)oUGLlSXcCLgEkb2;1C;48axoilp zA2(R{>EIt#`PIfc;j5fm@oJ%DUNGB>iPCCg?#WCZqT=o!!>3-twUjgJPl4Sqfkyk? zQemcj_&#b9ey~-O+oRLTx6PYLm<%r%2pH`Yk}Nj@d>M7#arDs1xe|K9HP*Pd?|3esYd@Lw`z zkS!N4FM9P^3-joe+r>lGdOY1LT`^%ri2N|@L_u%r9JLyw+Q3wqVcRcg77_XF>+0JA z!+VC3vtB9l&Q`YXa_ z12wSNjQU0MSRwATjNJOLyx1W3u*HTm&kkfhBYeO{7MjsRqL-N6Z{gx6TS$r<^+H7Q z6w{3XH7j*gn5X5TZdCc*ps8Z$5Q$9XejhirCU#1He^tulTj~YA*Xu^jQrZyrj6#$F zJ;3)KOOMSD+v`3Vf0S0tA&=7@UG9LT%{lWiT_q58MDwu$5zljEcIaC9)Xp5o*v z)$LNF$7%e_V9NT6XRGtyGF=$fHaql94P8#!lAf@DQ_rgDET}ND%+!t;Kl*nq-QX&Y zdj+C>u`QE1UZvO!cG0#4+>P3?=wasr=e&1mMP~mq{gu~h42BV>-P4??Oj{`KJL~%j za^EH3X)kMP z?y`@uuE7_0qFy?_H>3k=P^Q%5{j+bcmOXt(3G|#R`;+V@l)h64H*cVa7;gJ%Q*|>j zUFVbTyx_SwZ{fuFNLMgwAR2O8gSGb#0Vd`24+$=CyE60irkJW#`zB^dQtY~f*Q(Uz znvFrwkGuQYl7p-Gz&knA{cJL}iSGDmrnRAP+XYyJFluKa zUpQOoU?}jI;|>0iL-lChs$S0wnh>v;BflpUljVXE&981@p0`IB&6hbx7FuCYYtZY% zZIdxlRRtN6iCLCeCa>;e0%uCBodu)AGboEl8Eu2VVmsp`u?k><1dFQ+(YayumTNlj zFsJE396fVSMXas$@%LosK> z&aKz<$y(vM~qGi%msx+aM(D6tBhPDjY{N)W) zOtCPBRU0Tf#0dm5;7T>DrCTirUAT_cyhK7aY!pzwQw&*i&d zN3AwzjDRx~8c%97)rV|d*~15u6G0{-tU>DRkGtkCeSBJU65JZ$$>uBSY=0wj&p@Y{ z0`afO4f61N?GL{vHR8e_LmXN4-stP|NTtFH4P6{w?fR?mOfdI&#$VJohOvHRdTIN> zDqe`-6v{XFr^HH~^lVXCqFupJJjcbxqp6e)E1y9s_et&@4sI$MZe;>ihg@{@upNbD zk6NczPfO4nVU=!c`fD4yC1o;FNjKd>_zPs#KrW&gq)U>Mi4)ClF zqh97?s5Ou-!xo{c#I%mkN(`uiJ^iUpN_dXt5bf_s)tl|B6dSw*`IFiAM=SDf`@3O=Ct^)3@z&h*wX z=KAxYJSD_|GIs1KoqDuR9(pr68@ly3FS8>%ltcpRO^*P*)}%)KQtA|*u<_Xd^I53E z;$6E@*muF;k=oB5>^Z$XJgI_72| zk`LZ)v?axI-0U}fsYTbTqI)#A8ToqweXWSUfFpo%gs-_}ln{Wmz@ZE?y23{^y{?*M z?tnoE2Q%c?lW+Y&^1^;rwbGHy-OQ@^(Gaj^W9VO=78uh)>v$_{YwfhR47J*TWuG)` zRsNgW+dh5H2(jslLEX}frm$#w7^i8KIJu)>RJx#8iw4&jL%s{DhpIxe7BVvId7@ZS!1~)__u=I!q$fj7d?_R^VmxWzt2E1}OdTwA z642+SfdE7dp;=h3@j>F|WlNs|>7w%2QOUL?6)feA;^j{)fv>#ByATM+Z`M!hlfie{ zUT;BvM6i&Rw(So@t$&V`!x09xP1D06#l}|JMM>)$5}UuKcGNR3eh<_9vSgTZ>qf|L zON;0h$=tkjH?MpBD{M$7;CG+JrvVDxt0n1pgWsz+I(AB9ikM`=(>F{{O@q{N`Z~kqyYbu&(aZ{X$YN?zc z6YY!=!HnG8gKpI4>nD$5mil3zESDqezTe?L{oD?BtV6P0(0HSK38Q5{Jro=v>~fM{ zsxqFC*5_{jqXS00Ob#?S1L%(^sX59fuvNF;_+$9JWJ)X-X&Xh{`{cFS)7+StvWc-W zcg*BwD6S@LrWw*fM=UPiu6VW$>F|+K?r1<;rfSqV(OlD}z5bylWxPBPEBW^w_0#-Pm#O*)ogzEdVDNjvy#`FVw* zO=0w_7`EcJ#9kY5-&{tb#KNxcVyd>;Ox2#W$=0fF{WnY*`RoQQSQtTe%2A? z_ng}G7{mN9r=LcQ&zrp&V!56}PhY>>N(lYs`${)*Zwa zinD21^Vn~Wts@)jB7xVetc_N4)D_+8SkbC^Qj+roOlmZ_FJY*s^%?GB(7DY*ymMyC zo_Q-Hgy~BsUse2DgTkte#k^g@w=Eq7PRg1a8w7TbpQ3MGOvPRN9)(v6shJN?@}=vj ziQv^P&~&i9REwV{dhSIkqL1K;4O_$5rB>fxyXm1-F8q}!AE`WXhNpqkCvhK@{hmmsOgAm16?E5w%CPJ>9uU9P*;1x_7Mop7{vUG1m2+8%np$LC63kfBjFbquDM@3S!j5I6ohtW{ODV}r2vnoG1d}sc~Q@D z=m?A{J0vs?}&I-TUX`c(wQSK_+id6>kjDX-(mx4qu?g~BNqu@HEW9vQr8{mh;~G9qmE zx&0|OI1cNp$~flQ^yLyQIaNAO(OR*4xL|nOJiXF0I1|KVzM4pA`YDv8o1J)FV}aBr z{x-nUP4RKM@6O`fot@PPJ>l zf)2HM69(BhXj<@&9P7Wxzs}$OI?h&_(T_3JR~1XDmPLfW$vviRb!^VpPFv%KZCk!o z2K=Hc9VG+Uo>>Y*|JY#|m=2C5|$ zN!4ir7!f|}(87r7oBwq{_(!p-vi>uK7hsua92tli)tI1?y@5Yqjyv(?QuK+hf9xlx zsM1>BcR?>wv*OA>f#dwLDg3q3i`7H=%LO|0`W#GF)I(t^X`_$FsBJG_x7#*z?uWD| zbkFm<{t^bgY*byAbnSq{y-th>1^>!emGZ2x;rJ6UIE~69&@vHe)|gSHC6T}m?;wC& zQ-wD%a{HvPilaMliFrrR$U2AZVm3mL)6v0wt(l(`{XLt`2F65G3r^w*-rhyv)jzs| z#g(bq*nhY=P6&oHlUls@-;W*dQ4x1gngZ_{WS@pmwZO*PsTULk%^AV&aEHXsynL$J ze~p(^l4tIwyhRd&G9w@UG&L=`o@^IV=)tyD6xPa=b_y8EC-=PMqBj~#q|`KLQ+02v z@{`S|%Y8P?2qms9CS5+HwnmEJ_$@%&!T_sJm}cl=GHjx=3pl7~e@>e768I~cgtSgJ zgk5Djxk?ew*%C2Vg zZMe;@mZPPJx{ZUoM{?v*(*06r?lC`YDtBUbS7VDQJ@>DDSVYo2Kpg2m#g<^U)6tFWz2V_PGg#Ox%=dk-B!Hd}1&AlsX?67Ifh|xKA9{-GAqvC8v zp?=cu;S^nwd;2CG75#+dtWOaM^GhVZ^nyq@(siASAVRMK5Onm%HHc>d;`VO@}?CCZt&o|vZ)q-TAcXnS3 zY#P92F4M%N4}e`go#8ER-k1SpgZEXNU}K68q@fSnD9*G`@7{0KRvX%lsar{O>edXP z6T9oxBo~zF!_ESORUgR6u6LQh+IJ9x_0)g;mqWUUTPKpj|d#_WSoxYvpyG5_d~6m}~J*i^he$wj9RP^$or!StUp&G#AWAr(dG01p+Oz zqxSwBYB!cf2^*$Vy#_7!N-KBk^&{f+;Q`qYjks!iy6P{>{a!@pZK?SMOz|m}c+PfS zhc4?HyS92Zhh|8BN0+Dtzg0z|8$yB@G+q6%KL$;!<*z!j-B{AaXZ7;AlzRL>h-t-d9|ZN>4J<#q@7X zPacTLw_}Ho{@)?f=8C^0_UY8o$gpcs z7I1#)n!%f|>wO9g>kUL3{lPydly`b>>K=_a=ML)oS+4%*{-7~2f&mr{js&c)wUJWF z@u;4*>@#QLKxZ8@V$aSt=Up)tdcN43ZBYag6#uR}vt~ttW4+yb@KQY+=(M#13XN8P zN>$`&84b46DFcfN%!1XMpr?S`FL_-J48v6&PJqU(`T&`|#O9x!!JerN#m9?J!!o1G zN%@*ogs^y@f~2)Bsw&pxIv7pR5!xck?!2EY7M-~|T~kM%YxPQtsMpc2{(h=zyKrl0hdKn9X!Z(t8 zOt3PRTz&cjrWc>4c9)5hRR6_ZSB~~Nppe~io(kVGcPs(pM2`JvKNvsnSk#Za9}xYl z=bg-n^o=O&obhrifn|`$vm~}qEX$klM^J){x~#=lQU`|H`%0fIV8NCt=Xp}BwM|vyZvmpaJz_Ux8<7DOxq1&OOUvV+h^M|4qzL$Z6PM~Ms)XVg zysFSzKJ&V@z|iTO=-!LE&$ zjiVMF>(bV?uCECiaKW8b*Gwo4%h6auK5VRIHudU)EDz~_$|5LBms843R2)2xQe=aj zEgU(x)Ru(}un(#>>V1ihH!AG*)Oiw|8CE=PWThR5^Ja50V}8E1^6-_tQyHYGddZRw zEGKyJP}(G6vanxyl|MhE0&;tVkx8ZY@1@>3!}ik;Ck0a-Z7BGA?w(L3IK&(mXjsgT zrO4Fo&MV_*cLJ){cq;bVL^i`77Xj3U_|L(Pj7Qh>{dnw5g1@r*dYSYj9l{2(T8j5L zBsMR8tM2glmfvHqARC6U{frIM#mVX9OKxufG1I8LBd;f!;^k^pvI;#e-Cpm>6kJ(+ z^n!D{d=ELNRjEQ=4Y>X?P#K+W>G}R*V5GdYbCBUS)!Vdp<)6y&tWE2A88suAf(u}m zM9hp{=2>3_Du4Wn!o;lgSk!(3$(8jQ}v4QYHIc1J#zN`KbCL26^v9R}&1ns+U z({-eI7wZp1_%;o%{(g4exif0#4)MT^UZ#t|yhd0791qejKIs!T6-%B{M^uC9B2rr51}_$~dQ z%KE2@hF?cL6N0aN8L29OeAThVs$=EWYp^(5&#da+;7p^QC)lb#8PX3qiq#(SD5z|Z zuDz?<9+IzRY~Ql0vbZ7%N0|Jj{&Zei8y>4|pv8kpd7!7hWJqrE*&SX8>lu3O+p^TW z)mCgzc)a>$G7$^!KdZ6w0-p?1=}Kk$SCg?x6vLl<0}_sEKR=mX#KvHF7bTD*E0KIl zd<--_yc(EH5L%u~(f;w~Qs~KjnQhAqart$bdrtF`u0SG_(*z0kw)EYjAB6hH)UuDG zJWIS%$G(a;$;o5V1HE}Iy=)7KNGqPtTyc~A<;~#aq`Xvx5>OgGKX^D2tNl7|ysNbU5iT=hxYn*#9(U1= zsQl)je2npt8Qo2M0bKR1JE{;zDRM*D2ZbNlY^JeMxi6^P$-bo$7$M?1fp+ZCV0{dz7{iq)2AqY^xW^9qTWK%S{U>EtXX+pMnc%(m;--_H>l`Ojn zg_w_)IrzWEF7S)ACb^yxnm-qCO65u9g;Fs-bPR^ff>vXdLdNIrB<%i0#g#NoSAt}B zi9WxHY^B+h4lbgoMo2#r{{hVzSSU(YslhV>vEZ0+~-NrLCLfTsyANl|ftj_C; z$8x>4&U)HgN;1-Ag!Qt`;9IrCp5L@@OIjCHs*!2&eq#HaRxP<&lBf^L*RP&{LC&9_>R*NXJXpTK!@PH6P$je4 zJ4$GD3E%%}bnNIKwBOgyGyeyi;Xf4Nf1@iR9{_@rxvh=p2h9MW5#?cJVP#HTC^V^%YPBJ4geYzh{nfI*4Fs{J61tOOoK_>*~$uRXk+t1Nzka6nL7eLZaZU> zk8}or8pOfzqZ)vX2?zqRbF*@=GqN&qFanuCEKIB{0G Date: Fri, 3 Apr 2020 14:04:02 -0400 Subject: [PATCH 015/869] noise in robust should be gaussian, change variable names --- gtsam/linear/LossFunctions.cpp | 74 +++++++++++++++++----------------- gtsam/linear/LossFunctions.h | 40 +++++++++--------- gtsam/linear/NoiseModel.cpp | 7 ++++ gtsam/linear/NoiseModel.h | 13 +++--- 4 files changed, 71 insertions(+), 63 deletions(-) diff --git a/gtsam/linear/LossFunctions.cpp b/gtsam/linear/LossFunctions.cpp index 8bb670a92..45ad14f0f 100644 --- a/gtsam/linear/LossFunctions.cpp +++ b/gtsam/linear/LossFunctions.cpp @@ -137,12 +137,12 @@ Fair::Fair(double c, const ReweightScheme reweight) : Base(reweight), c_(c) { } } -double Fair::weight(double error) const { - return 1.0 / (1.0 + std::abs(error) / c_); +double Fair::weight(double distance) const { + return 1.0 / (1.0 + std::abs(distance) / c_); } -double Fair::loss(double error) const { - const double absError = std::abs(error); +double Fair::loss(double distance) const { + const double absError = std::abs(distance); const double normalizedError = absError / c_; const double c_2 = c_ * c_; return c_2 * (normalizedError - std::log1p(normalizedError)); @@ -170,15 +170,15 @@ Huber::Huber(double k, const ReweightScheme reweight) : Base(reweight), k_(k) { } } -double Huber::weight(double error) const { - const double absError = std::abs(error); +double Huber::weight(double distance) const { + const double absError = std::abs(distance); return (absError <= k_) ? (1.0) : (k_ / absError); } -double Huber::loss(double error) const { - const double absError = std::abs(error); +double Huber::loss(double distance) const { + const double absError = std::abs(distance); if (absError <= k_) { // |x| <= k - return error*error / 2; + return distance*distance / 2; } else { // |x| > k return k_ * (absError - (k_/2)); } @@ -208,12 +208,12 @@ Cauchy::Cauchy(double k, const ReweightScheme reweight) : Base(reweight), k_(k), } } -double Cauchy::weight(double error) const { - return ksquared_ / (ksquared_ + error*error); +double Cauchy::weight(double distance) const { + return ksquared_ / (ksquared_ + distance*distance); } -double Cauchy::loss(double error) const { - const double val = std::log1p(error * error / ksquared_); +double Cauchy::loss(double distance) const { + const double val = std::log1p(distance * distance / ksquared_); return ksquared_ * val * 0.5; } @@ -241,18 +241,18 @@ Tukey::Tukey(double c, const ReweightScheme reweight) : Base(reweight), c_(c), c } } -double Tukey::weight(double error) const { - if (std::abs(error) <= c_) { - const double one_minus_xc2 = 1.0 - error*error/csquared_; +double Tukey::weight(double distance) const { + if (std::abs(distance) <= c_) { + const double one_minus_xc2 = 1.0 - distance*distance/csquared_; return one_minus_xc2 * one_minus_xc2; } return 0.0; } -double Tukey::loss(double error) const { - double absError = std::abs(error); +double Tukey::loss(double distance) const { + double absError = std::abs(distance); if (absError <= c_) { - const double one_minus_xc2 = 1.0 - error*error/csquared_; + const double one_minus_xc2 = 1.0 - distance*distance/csquared_; const double t = one_minus_xc2*one_minus_xc2*one_minus_xc2; return csquared_ * (1 - t) / 6.0; } else { @@ -280,13 +280,13 @@ Tukey::shared_ptr Tukey::Create(double c, const ReweightScheme reweight) { Welsch::Welsch(double c, const ReweightScheme reweight) : Base(reweight), c_(c), csquared_(c * c) {} -double Welsch::weight(double error) const { - const double xc2 = (error*error)/csquared_; +double Welsch::weight(double distance) const { + const double xc2 = (distance*distance)/csquared_; return std::exp(-xc2); } -double Welsch::loss(double error) const { - const double xc2 = (error*error)/csquared_; +double Welsch::loss(double distance) const { + const double xc2 = (distance*distance)/csquared_; return csquared_ * 0.5 * -std::expm1(-xc2); } @@ -311,16 +311,16 @@ GemanMcClure::GemanMcClure(double c, const ReweightScheme reweight) : Base(reweight), c_(c) { } -double GemanMcClure::weight(double error) const { +double GemanMcClure::weight(double distance) const { const double c2 = c_*c_; const double c4 = c2*c2; - const double c2error = c2 + error*error; + const double c2error = c2 + distance*distance; return c4/(c2error*c2error); } -double GemanMcClure::loss(double error) const { +double GemanMcClure::loss(double distance) const { const double c2 = c_*c_; - const double error2 = error*error; + const double error2 = distance*distance; return 0.5 * (c2 * error2) / (c2 + error2); } @@ -345,8 +345,8 @@ DCS::DCS(double c, const ReweightScheme reweight) : Base(reweight), c_(c) { } -double DCS::weight(double error) const { - const double e2 = error*error; +double DCS::weight(double distance) const { + const double e2 = distance*distance; if (e2 > c_) { const double w = 2.0*c_/(c_ + e2); @@ -356,10 +356,10 @@ double DCS::weight(double error) const { return 1.0; } -double DCS::loss(double error) const { +double DCS::loss(double distance) const { // This is the simplified version of Eq 9 from (Agarwal13icra) // after you simplify and cancel terms. - const double e2 = error*error; + const double e2 = distance*distance; const double e4 = e2*e2; const double c2 = c_*c_; @@ -391,17 +391,17 @@ L2WithDeadZone::L2WithDeadZone(double k, const ReweightScheme reweight) } } -double L2WithDeadZone::weight(double error) const { +double L2WithDeadZone::weight(double distance) const { // note that this code is slightly uglier than residual, because there are three distinct // cases to handle (left of deadzone, deadzone, right of deadzone) instead of the two // cases (deadzone, non-deadzone) in residual. - if (std::abs(error) <= k_) return 0.0; - else if (error > k_) return (-k_+error)/error; - else return (k_+error)/error; + if (std::abs(distance) <= k_) return 0.0; + else if (distance > k_) return (-k_+distance)/distance; + else return (k_+distance)/distance; } -double L2WithDeadZone::loss(double error) const { - const double abs_error = std::abs(error); +double L2WithDeadZone::loss(double distance) const { + const double abs_error = std::abs(distance); return (abs_error < k_) ? 0.0 : 0.5*(k_-abs_error)*(k_-abs_error); } diff --git a/gtsam/linear/LossFunctions.h b/gtsam/linear/LossFunctions.h index 1b6f444e8..8d569a5df 100644 --- a/gtsam/linear/LossFunctions.h +++ b/gtsam/linear/LossFunctions.h @@ -80,10 +80,10 @@ class GTSAM_EXPORT Base { * functions. It would be better for this function to accept the vector and * internally call the norm if necessary. */ - virtual double loss(double error) const { return 0; }; + virtual double loss(double distance) const { return 0; }; #ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V4 - virtual double residual(double error) const { return loss(error); }; + virtual double residual(double distance) const { return loss(distance); }; #endif /* * This method is responsible for returning the weight function for a given @@ -93,12 +93,12 @@ class GTSAM_EXPORT Base { * for details. This method is required when optimizing cost functions with * robust penalties using iteratively re-weighted least squares. */ - virtual double weight(double error) const = 0; + virtual double weight(double distance) const = 0; virtual void print(const std::string &s) const = 0; virtual bool equals(const Base &expected, double tol = 1e-8) const = 0; - double sqrtWeight(double error) const { return std::sqrt(weight(error)); } + double sqrtWeight(double distance) const { return std::sqrt(weight(distance)); } /** produce a weight vector according to an error vector and the implemented * robust function */ @@ -157,8 +157,8 @@ class GTSAM_EXPORT Fair : public Base { typedef boost::shared_ptr shared_ptr; Fair(double c = 1.3998, const ReweightScheme reweight = Block); - double weight(double error) const override; - double loss(double error) const override; + double weight(double distance) const override; + double loss(double distance) const override; void print(const std::string &s) const override; bool equals(const Base &expected, double tol = 1e-8) const override; static shared_ptr Create(double c, const ReweightScheme reweight = Block); @@ -182,8 +182,8 @@ class GTSAM_EXPORT Huber : public Base { typedef boost::shared_ptr shared_ptr; Huber(double k = 1.345, const ReweightScheme reweight = Block); - double weight(double error) const override; - double loss(double error) const override; + double weight(double distance) const override; + double loss(double distance) const override; void print(const std::string &s) const override; bool equals(const Base &expected, double tol = 1e-8) const override; static shared_ptr Create(double k, const ReweightScheme reweight = Block); @@ -212,8 +212,8 @@ class GTSAM_EXPORT Cauchy : public Base { typedef boost::shared_ptr shared_ptr; Cauchy(double k = 0.1, const ReweightScheme reweight = Block); - double weight(double error) const override; - double loss(double error) const override; + double weight(double distance) const override; + double loss(double distance) const override; void print(const std::string &s) const override; bool equals(const Base &expected, double tol = 1e-8) const override; static shared_ptr Create(double k, const ReweightScheme reweight = Block); @@ -237,8 +237,8 @@ class GTSAM_EXPORT Tukey : public Base { typedef boost::shared_ptr shared_ptr; Tukey(double c = 4.6851, const ReweightScheme reweight = Block); - double weight(double error) const override; - double loss(double error) const override; + double weight(double distance) const override; + double loss(double distance) const override; void print(const std::string &s) const override; bool equals(const Base &expected, double tol = 1e-8) const override; static shared_ptr Create(double k, const ReweightScheme reweight = Block); @@ -262,8 +262,8 @@ class GTSAM_EXPORT Welsch : public Base { typedef boost::shared_ptr shared_ptr; Welsch(double c = 2.9846, const ReweightScheme reweight = Block); - double weight(double error) const override; - double loss(double error) const override; + double weight(double distance) const override; + double loss(double distance) const override; void print(const std::string &s) const override; bool equals(const Base &expected, double tol = 1e-8) const override; static shared_ptr Create(double k, const ReweightScheme reweight = Block); @@ -298,8 +298,8 @@ class GTSAM_EXPORT GemanMcClure : public Base { GemanMcClure(double c = 1.0, const ReweightScheme reweight = Block); ~GemanMcClure() {} - double weight(double error) const override; - double loss(double error) const override; + double weight(double distance) const override; + double loss(double distance) const override; void print(const std::string &s) const override; bool equals(const Base &expected, double tol = 1e-8) const override; static shared_ptr Create(double k, const ReweightScheme reweight = Block); @@ -328,8 +328,8 @@ class GTSAM_EXPORT DCS : public Base { DCS(double c = 1.0, const ReweightScheme reweight = Block); ~DCS() {} - double weight(double error) const override; - double loss(double error) const override; + double weight(double distance) const override; + double loss(double distance) const override; void print(const std::string &s) const override; bool equals(const Base &expected, double tol = 1e-8) const override; static shared_ptr Create(double k, const ReweightScheme reweight = Block); @@ -361,8 +361,8 @@ class GTSAM_EXPORT L2WithDeadZone : public Base { typedef boost::shared_ptr shared_ptr; L2WithDeadZone(double k = 1.0, const ReweightScheme reweight = Block); - double weight(double error) const override; - double loss(double error) const override; + double weight(double distance) const override; + double loss(double distance) const override; void print(const std::string &s) const override; bool equals(const Base &expected, double tol = 1e-8) const override; static shared_ptr Create(double k, const ReweightScheme reweight = Block); diff --git a/gtsam/linear/NoiseModel.cpp b/gtsam/linear/NoiseModel.cpp index e0ca3726b..5855ecad4 100644 --- a/gtsam/linear/NoiseModel.cpp +++ b/gtsam/linear/NoiseModel.cpp @@ -654,6 +654,13 @@ void Robust::WhitenSystem(Matrix& A1, Matrix& A2, Matrix& A3, Vector& b) const{ robust_->reweight(A1,A2,A3,b); } +Robust::shared_ptr Robust::Create(const RobustModel::shared_ptr& robust, + const noiseModel::Base::shared_ptr noise) { + SharedGaussian gaussian; + gaussian = boost::dynamic_pointer_cast(noise); + return shared_ptr(new Robust(robust, gaussian)); +} + Robust::shared_ptr Robust::Create( const RobustModel::shared_ptr &robust, const NoiseModel::shared_ptr noise){ return shared_ptr(new Robust(robust,noise)); diff --git a/gtsam/linear/NoiseModel.h b/gtsam/linear/NoiseModel.h index 627c0de2b..dff94c874 100644 --- a/gtsam/linear/NoiseModel.h +++ b/gtsam/linear/NoiseModel.h @@ -90,7 +90,7 @@ namespace gtsam { /// Unwhiten an error vector. virtual Vector unwhiten(const Vector& v) const = 0; - /// calculate the error value given error vector + /// calculate the error value given measurement error vector virtual double error(const Vector& v) const = 0; #ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V4 @@ -677,7 +677,7 @@ namespace gtsam { protected: typedef mEstimator::Base RobustModel; - typedef noiseModel::Base NoiseModel; + typedef noiseModel::Gaussian NoiseModel; const RobustModel::shared_ptr robust_; ///< robust error function used const NoiseModel::shared_ptr noise_; ///< noise model used @@ -712,9 +712,7 @@ namespace gtsam { { throw std::invalid_argument("unwhiten is not currently supported for robust noise models."); } // Fold the use of the m-estimator loss(...) function into error(...) inline virtual double error(const Vector& v) const - { return robust_->loss(this->unweightedWhiten(v).norm()); } - // inline virtual double distance_non_whitened(const Vector& v) const - // { return robust_->loss(v.norm()); } + { return robust_->loss(noise_->mahalanobisDistance(v)); } // TODO: these are really robust iterated re-weighting support functions virtual void WhitenSystem(Vector& b) const; virtual void WhitenSystem(std::vector& A, Vector& b) const; @@ -723,13 +721,16 @@ namespace gtsam { virtual void WhitenSystem(Matrix& A1, Matrix& A2, Matrix& A3, Vector& b) const; virtual Vector unweightedWhiten(const Vector& v) const { - return noise_->unweightedWhiten(v); + return noise_->whiten(v); } virtual double weight(const Vector& v) const { // Todo(mikebosse): make the robust weight function input a vector. return robust_->weight(v.norm()); } + static shared_ptr Create( + const RobustModel::shared_ptr &robust, const noiseModel::Base::shared_ptr noise); + static shared_ptr Create( const RobustModel::shared_ptr &robust, const NoiseModel::shared_ptr noise); From efc264d8ee3c4704471488c982b768c1dccd57c4 Mon Sep 17 00:00:00 2001 From: yetongumich Date: Sun, 5 Apr 2020 14:20:44 -0400 Subject: [PATCH 016/869] revised comments --- gtsam/linear/NoiseModel.h | 5 ++++- 1 file changed, 4 insertions(+), 1 deletion(-) diff --git a/gtsam/linear/NoiseModel.h b/gtsam/linear/NoiseModel.h index dff94c874..7349f6304 100644 --- a/gtsam/linear/NoiseModel.h +++ b/gtsam/linear/NoiseModel.h @@ -229,6 +229,9 @@ namespace gtsam { } #endif + /** + * error value 0.5 * v'*R'*R*v + */ inline virtual double error(const Vector& v) const { return 0.5 * squaredMahalanobisDistance(v); } @@ -478,7 +481,7 @@ namespace gtsam { } /** - * The distance function for a constrained noisemodel, + * The error function for a constrained noisemodel, * for non-constrained versions, uses sigmas, otherwise * uses the penalty function with mu */ From 90b286f553fc7a5fa3f6951a60181365a0ffd1b6 Mon Sep 17 00:00:00 2001 From: yetongumich Date: Sun, 5 Apr 2020 14:46:17 -0400 Subject: [PATCH 017/869] change test cases to use the updated names, remove 2nd Create in robust --- gtsam/linear/NoiseModel.cpp | 8 +-- gtsam/linear/NoiseModel.h | 4 +- gtsam/linear/tests/testNoiseModel.cpp | 72 +++++++++++++-------------- 3 files changed, 42 insertions(+), 42 deletions(-) diff --git a/gtsam/linear/NoiseModel.cpp b/gtsam/linear/NoiseModel.cpp index 5855ecad4..206cab3b1 100644 --- a/gtsam/linear/NoiseModel.cpp +++ b/gtsam/linear/NoiseModel.cpp @@ -661,10 +661,10 @@ Robust::shared_ptr Robust::Create(const RobustModel::shared_ptr& robust, return shared_ptr(new Robust(robust, gaussian)); } -Robust::shared_ptr Robust::Create( - const RobustModel::shared_ptr &robust, const NoiseModel::shared_ptr noise){ - return shared_ptr(new Robust(robust,noise)); -} +// Robust::shared_ptr Robust::Create( +// const RobustModel::shared_ptr &robust, const NoiseModel::shared_ptr noise){ +// return shared_ptr(new Robust(robust,noise)); +// } /* ************************************************************************* */ diff --git a/gtsam/linear/NoiseModel.h b/gtsam/linear/NoiseModel.h index 7349f6304..c8e0e78a5 100644 --- a/gtsam/linear/NoiseModel.h +++ b/gtsam/linear/NoiseModel.h @@ -734,8 +734,8 @@ namespace gtsam { static shared_ptr Create( const RobustModel::shared_ptr &robust, const noiseModel::Base::shared_ptr noise); - static shared_ptr Create( - const RobustModel::shared_ptr &robust, const NoiseModel::shared_ptr noise); + // static shared_ptr Create( + // const RobustModel::shared_ptr &robust, const NoiseModel::shared_ptr noise); private: /** Serialization function */ diff --git a/gtsam/linear/tests/testNoiseModel.cpp b/gtsam/linear/tests/testNoiseModel.cpp index d6b133b98..dd1d46b42 100644 --- a/gtsam/linear/tests/testNoiseModel.cpp +++ b/gtsam/linear/tests/testNoiseModel.cpp @@ -451,7 +451,7 @@ TEST(NoiseModel, WhitenInPlace) /* * These tests are responsible for testing the weight functions for the m-estimators in GTSAM. - * The weight function is related to the analytic derivative of the residual function. See + * The weight function is related to the analytic derivative of the loss function. See * https://members.loria.fr/MOBerger/Enseignement/Master2/Documents/ZhangIVC-97-01.pdf * for details. This weight function is required when optimizing cost functions with robust * penalties using iteratively re-weighted least squares. @@ -467,10 +467,10 @@ TEST(NoiseModel, robustFunctionFair) DOUBLES_EQUAL(0.3333333333333333, fair->weight(error3), 1e-8); DOUBLES_EQUAL(0.8333333333333333, fair->weight(error4), 1e-8); - DOUBLES_EQUAL(0.441961080151135, fair->residual(error1), 1e-8); - DOUBLES_EQUAL(22.534692783297260, fair->residual(error2), 1e-8); - DOUBLES_EQUAL(22.534692783297260, fair->residual(error3), 1e-8); - DOUBLES_EQUAL(0.441961080151135, fair->residual(error4), 1e-8); + DOUBLES_EQUAL(0.441961080151135, fair->loss(error1), 1e-8); + DOUBLES_EQUAL(22.534692783297260, fair->loss(error2), 1e-8); + DOUBLES_EQUAL(22.534692783297260, fair->loss(error3), 1e-8); + DOUBLES_EQUAL(0.441961080151135, fair->loss(error4), 1e-8); } TEST(NoiseModel, robustFunctionHuber) @@ -483,10 +483,10 @@ TEST(NoiseModel, robustFunctionHuber) DOUBLES_EQUAL(0.5, huber->weight(error3), 1e-8); DOUBLES_EQUAL(1.0, huber->weight(error4), 1e-8); - DOUBLES_EQUAL(0.5000, huber->residual(error1), 1e-8); - DOUBLES_EQUAL(37.5000, huber->residual(error2), 1e-8); - DOUBLES_EQUAL(37.5000, huber->residual(error3), 1e-8); - DOUBLES_EQUAL(0.5000, huber->residual(error4), 1e-8); + DOUBLES_EQUAL(0.5000, huber->loss(error1), 1e-8); + DOUBLES_EQUAL(37.5000, huber->loss(error2), 1e-8); + DOUBLES_EQUAL(37.5000, huber->loss(error3), 1e-8); + DOUBLES_EQUAL(0.5000, huber->loss(error4), 1e-8); } TEST(NoiseModel, robustFunctionCauchy) @@ -499,10 +499,10 @@ TEST(NoiseModel, robustFunctionCauchy) DOUBLES_EQUAL(0.2000, cauchy->weight(error3), 1e-8); DOUBLES_EQUAL(0.961538461538461, cauchy->weight(error4), 1e-8); - DOUBLES_EQUAL(0.490258914416017, cauchy->residual(error1), 1e-8); - DOUBLES_EQUAL(20.117973905426254, cauchy->residual(error2), 1e-8); - DOUBLES_EQUAL(20.117973905426254, cauchy->residual(error3), 1e-8); - DOUBLES_EQUAL(0.490258914416017, cauchy->residual(error4), 1e-8); + DOUBLES_EQUAL(0.490258914416017, cauchy->loss(error1), 1e-8); + DOUBLES_EQUAL(20.117973905426254, cauchy->loss(error2), 1e-8); + DOUBLES_EQUAL(20.117973905426254, cauchy->loss(error3), 1e-8); + DOUBLES_EQUAL(0.490258914416017, cauchy->loss(error4), 1e-8); } TEST(NoiseModel, robustFunctionGemanMcClure) @@ -514,10 +514,10 @@ TEST(NoiseModel, robustFunctionGemanMcClure) DOUBLES_EQUAL(9.80296e-5, gmc->weight(error3), 1e-8); DOUBLES_EQUAL(0.25 , gmc->weight(error4), 1e-8); - DOUBLES_EQUAL(0.2500, gmc->residual(error1), 1e-8); - DOUBLES_EQUAL(0.495049504950495, gmc->residual(error2), 1e-8); - DOUBLES_EQUAL(0.495049504950495, gmc->residual(error3), 1e-8); - DOUBLES_EQUAL(0.2500, gmc->residual(error4), 1e-8); + DOUBLES_EQUAL(0.2500, gmc->loss(error1), 1e-8); + DOUBLES_EQUAL(0.495049504950495, gmc->loss(error2), 1e-8); + DOUBLES_EQUAL(0.495049504950495, gmc->loss(error3), 1e-8); + DOUBLES_EQUAL(0.2500, gmc->loss(error4), 1e-8); } TEST(NoiseModel, robustFunctionWelsch) @@ -530,10 +530,10 @@ TEST(NoiseModel, robustFunctionWelsch) DOUBLES_EQUAL(0.018315638888734, welsch->weight(error3), 1e-8); DOUBLES_EQUAL(0.960789439152323, welsch->weight(error4), 1e-8); - DOUBLES_EQUAL(0.490132010595960, welsch->residual(error1), 1e-8); - DOUBLES_EQUAL(12.271054513890823, welsch->residual(error2), 1e-8); - DOUBLES_EQUAL(12.271054513890823, welsch->residual(error3), 1e-8); - DOUBLES_EQUAL(0.490132010595960, welsch->residual(error4), 1e-8); + DOUBLES_EQUAL(0.490132010595960, welsch->loss(error1), 1e-8); + DOUBLES_EQUAL(12.271054513890823, welsch->loss(error2), 1e-8); + DOUBLES_EQUAL(12.271054513890823, welsch->loss(error3), 1e-8); + DOUBLES_EQUAL(0.490132010595960, welsch->loss(error4), 1e-8); } TEST(NoiseModel, robustFunctionTukey) @@ -546,10 +546,10 @@ TEST(NoiseModel, robustFunctionTukey) DOUBLES_EQUAL(0.0, tukey->weight(error3), 1e-8); DOUBLES_EQUAL(0.9216, tukey->weight(error4), 1e-8); - DOUBLES_EQUAL(0.480266666666667, tukey->residual(error1), 1e-8); - DOUBLES_EQUAL(4.166666666666667, tukey->residual(error2), 1e-8); - DOUBLES_EQUAL(4.166666666666667, tukey->residual(error3), 1e-8); - DOUBLES_EQUAL(0.480266666666667, tukey->residual(error4), 1e-8); + DOUBLES_EQUAL(0.480266666666667, tukey->loss(error1), 1e-8); + DOUBLES_EQUAL(4.166666666666667, tukey->loss(error2), 1e-8); + DOUBLES_EQUAL(4.166666666666667, tukey->loss(error3), 1e-8); + DOUBLES_EQUAL(0.480266666666667, tukey->loss(error4), 1e-8); } TEST(NoiseModel, robustFunctionDCS) @@ -560,8 +560,8 @@ TEST(NoiseModel, robustFunctionDCS) DOUBLES_EQUAL(1.0 , dcs->weight(error1), 1e-8); DOUBLES_EQUAL(0.00039211, dcs->weight(error2), 1e-8); - DOUBLES_EQUAL(0.5 , dcs->residual(error1), 1e-8); - DOUBLES_EQUAL(0.9900990099, dcs->residual(error2), 1e-8); + DOUBLES_EQUAL(0.5 , dcs->loss(error1), 1e-8); + DOUBLES_EQUAL(0.9900990099, dcs->loss(error2), 1e-8); } TEST(NoiseModel, robustFunctionL2WithDeadZone) @@ -576,12 +576,12 @@ TEST(NoiseModel, robustFunctionL2WithDeadZone) DOUBLES_EQUAL(0.00990099009, lsdz->weight(e4), 1e-8); DOUBLES_EQUAL(0.9, lsdz->weight(e5), 1e-8); - DOUBLES_EQUAL(40.5, lsdz->residual(e0), 1e-8); - DOUBLES_EQUAL(0.00005, lsdz->residual(e1), 1e-8); - DOUBLES_EQUAL(0.0, lsdz->residual(e2), 1e-8); - DOUBLES_EQUAL(0.0, lsdz->residual(e3), 1e-8); - DOUBLES_EQUAL(0.00005, lsdz->residual(e4), 1e-8); - DOUBLES_EQUAL(40.5, lsdz->residual(e5), 1e-8); + DOUBLES_EQUAL(40.5, lsdz->loss(e0), 1e-8); + DOUBLES_EQUAL(0.00005, lsdz->loss(e1), 1e-8); + DOUBLES_EQUAL(0.0, lsdz->loss(e2), 1e-8); + DOUBLES_EQUAL(0.0, lsdz->loss(e3), 1e-8); + DOUBLES_EQUAL(0.00005, lsdz->loss(e4), 1e-8); + DOUBLES_EQUAL(40.5, lsdz->loss(e5), 1e-8); } /* ************************************************************************* */ @@ -665,11 +665,11 @@ TEST(NoiseModel, robustNoiseL2WithDeadZone) /* * TODO(mike): There is currently a bug in GTSAM, where none of the mEstimator classes - * implement a residual function, and GTSAM calls the weight function to evaluate the - * total penalty, rather than calling the residual function. The weight function should be + * implement a loss function, and GTSAM calls the weight function to evaluate the + * total penalty, rather than calling the loss function. The weight function should be * used during iteratively reweighted least squares optimization, but should not be used to * evaluate the total penalty. The long-term solution is for all mEstimators to implement - * both a weight and a residual function, and for GTSAM to call the residual function when + * both a weight and a loss function, and for GTSAM to call the loss function when * evaluating the total penalty. This bug causes the test below to fail, so I'm leaving it * commented out until the underlying bug in GTSAM is fixed. * From 3f8bb104053a3d1451c9d03878f310aa53b1c84e Mon Sep 17 00:00:00 2001 From: yetongumich Date: Sun, 5 Apr 2020 18:44:56 -0400 Subject: [PATCH 018/869] modified document, remove commented function, add deprecated distance --- doc/robust.pdf | Bin 197566 -> 197679 bytes gtsam/linear/NoiseModel.cpp | 5 ----- gtsam/linear/NoiseModel.h | 12 ++++++++---- 3 files changed, 8 insertions(+), 9 deletions(-) diff --git a/doc/robust.pdf b/doc/robust.pdf index 3404719b492e481bb77b96853eea0fa3a2fc39ba..ef8dc6fe624ef0af97973b383042940993273752 100644 GIT binary patch delta 2581 zcmbuB`9Bj51IKN1-$%J}tTG|Bi_J=7aurcx`1W0Fvr#?H2^FTfrYKj|q&bqucbHr5 z9GNQ;5$cPm_)4zOG{^IOJwH6J*Yo`Pe13SpUZ3}0@NP|%EoaK6LJ=r51`M?aUjf5m z7#J9CW(FpJq0V6V-_`~UN5Ehh6EM^X{5M?xmS`jbUP*)it{@Qz@c#^Y&Ki8h+=q;y z5-}!7D$I&r1cSklWFHKfXhI|+&?GX23OAu(C}af6 z42_|nGd=+f&&Xd^{G;-KH8(!Se(xE0c;^^1(;w8Y3OZ-2A*Xod8kCuQQ6eoQ!FwGF zQkkPa#8>pnCO^}=r6!QXCtrhZGiaL?xFgu#-eZ@c0L<> zL<1RzgjD}1NxtkO^mDV5Mxt+BeZc2L=ZFKk_^f#fXr!Un%bh~griQRJ zT-5u53K&xHgL+B@k|WDmW30FvoU&siXb|D)eqEJu_*t3z!j*l0)~32c%^9BWfWc8M z=Z+Kbcs4!f6(Lku)g;pmI64gTiU}sV{V^BW&xC8%ait^^w*OH}O)lB#rb0Zhq2A{O zEgu6Dxc;*!SH6Lv-=}Z~oP{yB07ADuDxKz~5Y^BbE5n}V)ejIBpr_SNh5K8)3(u#G zpbot^T}DJs;X6^1av#jf!k)kM^V`bZnmd9f(C=JoBJ3-NXTdLgx}Jh&)~s1J83jD4 zPD(L_8x$v{pX!N9LKzh$k{PR3Z5^U7FDMFD>W7r?;;zBON<=u_iOOoC_Yrrip zP0#!04yr#+ry9@U+iS-iui>OuV+WR(cI~nW9W&o#i#kqB-F{0bvdm}TpSGM9V#J3W z>2vj2%6r@vCmrYO|4h&J6SGUli{@Jtq_U+UQCCS#eo{k{9GjXUXLTz@q9-ctm*qi% zi)5vqjf;TdnJ=)7Us6K)Jv|Ve7aHt7?sIP8O+3NSD#c@R^!JHag3UAJ=_@k+CzA?7 zLZZ~eVlpyQPLBrbYEcjD@zzXaMGkHO=rOnBDwc2~t@y9eB~_3F->}f?QB!7CLH&A!A8yi!El(k^(ZA zxd4xnAXEP~7mE4$GK{0jk~%$WQl&EUj`8!Z7cqaefPLcffwy9(- zE7ADvNkz6OY;iKC^oBQcDnZAwpat|>U_#xU1|LB1;-^g&oR{D+Iwk|R@MWE5EBo{F zgNcZN=@S?*m`PgnqrdJa!^?Bot2vrK-q=QP&|e?Ib)u!`(hh(9Ud?YdD~Wq#u$-Mdf&xb2XaUon_=^+x{=}@1v0dycKT<+?HmBz?Q_nIq7NJz zr^0aWl#^UAF|Qm)D(6#oydNq%Wur7+)LEj?l$BpC#2x7BzN8D z^524B<87@c>9Hq>PHe5x`W0{d5&4;C6b|bGJ8*sSWk*q~*LZ{2#@BAIIEm<8w>-?W z>3AmhR&ov_QB6kk?y5zVa0FqwSzM-{YyUT z2VJqsZOx$yfvO;=p=;c^#zKwt1mMapc+1o>Xz750bPMqQ_9~Nh&keoin$H4#+y)L8 z4&Qlmyn>s2$vx()>np-X4euhoOp=yb;_x7y4j-|($kN)Wmr9xH;`BVock9ZRa^O#W zwz9ufxG{Rla9#YWgayYeC$QTE%ga5#J%r6H2x`GD7t++7u8n?04BiiX3tZFOhd<7& z(+g^8e6a6OFaBb2xrO|r;;Q~8Ua^SZxI&U_OUZ^K%3WrM>Y<%W6#qlYKm5q6`#GL; zoik%v^~oCMtY2-6e3jlWGCTJjwD@Qt?+}f?RId}m5Oz=-WJW3?;i}#$!Q#Eq3*3}_ zsQ7cA_!l3SaY3kJ%+KTgpg?7QJ`KcV+46B9hsAi*|Q7@yv1tg;Okng5s zIT4}i2RWk2bO1HAM+sE^NUYS!U_hFBL=m?y@t)R6jD^T0LgWB1AacN~8xp1ngb4x( zW8DLQApbda0MIJ{GX1(5D;)^3qyPVjgeCk}dyq*Y0DW72Nr%}G zc$3R{bAozU`Y(VBMXv}fm=kYvs%qCsR_~3dB1|+lvq=SLo4+WlTrQ)zDBT}?U}OkC z*x`$!iW9^0wX%c-5L9Vy;Uoxjx|u9=OE6DHILm1WxxNVk*YBap22lHPo zE^ZDw$B<}nGct3sf)?d!vV9QD6=F2wu|wI&tT~N}DIT(~YFyc^S^Ko>=G(?pzci8e zyWvuCBXlER6o0;iJQDFxB<#30qS)Rt*Y0HCsE&dThaf$C%b~3B>9?B~Bnvzk)0yv2 zOG`!M=|V}4!(q?1-R&Vc_B&71=X#*uqvm6myHrqzHhK-7kFx2?F+VWpnc>jS&;fYK zbT_Spf4y1nu4<ZS*ON)FH;-Mn{2^y6TSsn@2mit`Y!A|&I;MW0$;u%^#)(BnXJ>4xRDy0Ad9bE8s^ z=N=-i`*@eOMAY!3`b}&8*yl;=WGK2LbeVR2(S1!Xm_e>A`t?R2f39k@Hq%S0Cx9>* zdO7cRyq9ur7acmZv++z@p(B|Rp1eR+o^i07bg-?d$YO+}(UW%&^j~sGC%yKvbOUx4 zjYBK@8%_~0aZIvGj|PGxGongWeo>|Hf;rx0AK))`^ZD`D8nIaFJ@ZXVDjCpdrX}N_ zO&;{cc%o{LV7Fb$ejVrNH%Hh%oC|6nPrvXnjHRTawy$$uOY7!ui7}v~r1-kpv^a5( z9DiQ&3c1f<3`AZ*d=Rv+_=A}quf(#LfT$hT)XEkzRv*DxUr@ZpBLmK zZab_f_KV-1dL?Ad=x(xhtxa0_8aeX}%@+s+^PdUePUkvQpsn&X`Nx-r$CEuKn(U|j zj}6Nam-c|)%*C7dhS94AFNeg6q6&SHh~R*|U$QSFE8Is~Ug=f6a<=vFQE$QWEN2H* zsW_RpDt01O1M0#6Rn>x4lfMAI#>ZYJUwRAP+%N)F6U@Io4*OJX;9ls~p=-w5QWZ}0 zcD1Z7i5@pC-MGO~@(?>M75f+Sa4k9-NMY7}19;?DNjTaka<92xjtC!G{^u9{ z;d=3R^sb_z-mauOK|KzjOZHC=It<-tuVL$&gbypSZ0FX0%vY<-?TFp(`e8b|A<4)F zqRR(foKhRi565;@8hy0x*cQ2|xUl`^Kr%%A(nb9Qx+&(Jx$c2X0R&(+0h(zmt5$|%zXb(*f8bKS5jpVrcg%I~+gHR$q2=0kOh2Ix$! zFEX}>xHJ!oTTjcW!HMO1k4TMvt|3`t)|DsIC&W}F$ZV06I2nD1`@LsY3$cY#3($E< zU`=wA>nc(#H*pvnq`G;euJ}B}>fF5Q-c>*Sb;k#^9t~~vtiW}Fv?t#`MV~NL&xfRV zB{?9l!U_I_8@LEf^0HZr#mTmnoKh?iSof({3Ge7W4I}YTT$Morjhqb z7iGHoIBL*`cmWLh`e^w6j(c*QFC^-bl(d519V@OC6qMM@ws(}&_|e&c zYpZte4=7G5%$OPVca3-M8mm|S&W)ldzIp0u%(0nn>)GkFIcHJmc0_fRdZ+eVk})cC z`87^CCO7<5j2es0djB#EgkWq1rmWDyvOQLim0{`kb!ar!_%@yXR2wV#KuJPYz2aU!uI z*;Ch4-^wG46AuU- qW7#UC*2{_Hy!;E0&0UhVEu6c~T7`)UgbGVg|Dl&tg(||JBYy)Q=x|y9 diff --git a/gtsam/linear/NoiseModel.cpp b/gtsam/linear/NoiseModel.cpp index 206cab3b1..a7b48b034 100644 --- a/gtsam/linear/NoiseModel.cpp +++ b/gtsam/linear/NoiseModel.cpp @@ -661,11 +661,6 @@ Robust::shared_ptr Robust::Create(const RobustModel::shared_ptr& robust, return shared_ptr(new Robust(robust, gaussian)); } -// Robust::shared_ptr Robust::Create( -// const RobustModel::shared_ptr &robust, const NoiseModel::shared_ptr noise){ -// return shared_ptr(new Robust(robust,noise)); -// } - /* ************************************************************************* */ } diff --git a/gtsam/linear/NoiseModel.h b/gtsam/linear/NoiseModel.h index c8e0e78a5..73484799f 100644 --- a/gtsam/linear/NoiseModel.h +++ b/gtsam/linear/NoiseModel.h @@ -94,7 +94,9 @@ namespace gtsam { virtual double error(const Vector& v) const = 0; #ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V4 - virtual double distance(const Vector& v) const = 0; + virtual double distance(const Vector& v) { + return error(v) * 2; + } #endif virtual void WhitenSystem(std::vector& A, Vector& b) const = 0; @@ -713,6 +715,11 @@ namespace gtsam { { Vector b; Matrix B=A; this->WhitenSystem(B,b); return B; } inline virtual Vector unwhiten(const Vector& /*v*/) const { throw std::invalid_argument("unwhiten is not currently supported for robust noise models."); } +#ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V4 + inline virtual double distance(const Vector& v) { + return robust_->loss(this->unweightedWhiten(v).norm()); + } +#endif // Fold the use of the m-estimator loss(...) function into error(...) inline virtual double error(const Vector& v) const { return robust_->loss(noise_->mahalanobisDistance(v)); } @@ -734,9 +741,6 @@ namespace gtsam { static shared_ptr Create( const RobustModel::shared_ptr &robust, const noiseModel::Base::shared_ptr noise); - // static shared_ptr Create( - // const RobustModel::shared_ptr &robust, const NoiseModel::shared_ptr noise); - private: /** Serialization function */ friend class boost::serialization::access; From 99761a1a71e8b7ef84819f2fbd816140c2c91ab0 Mon Sep 17 00:00:00 2001 From: yetongumich Date: Sun, 5 Apr 2020 18:53:00 -0400 Subject: [PATCH 019/869] check if noisemodel is gaussian, if not throw exception --- gtsam/linear/NoiseModel.cpp | 5 ++++- 1 file changed, 4 insertions(+), 1 deletion(-) diff --git a/gtsam/linear/NoiseModel.cpp b/gtsam/linear/NoiseModel.cpp index a7b48b034..b2d05378f 100644 --- a/gtsam/linear/NoiseModel.cpp +++ b/gtsam/linear/NoiseModel.cpp @@ -657,7 +657,10 @@ void Robust::WhitenSystem(Matrix& A1, Matrix& A2, Matrix& A3, Vector& b) const{ Robust::shared_ptr Robust::Create(const RobustModel::shared_ptr& robust, const noiseModel::Base::shared_ptr noise) { SharedGaussian gaussian; - gaussian = boost::dynamic_pointer_cast(noise); + if (!(gaussian = boost::dynamic_pointer_cast(noise))) + { + throw std::invalid_argument("The noise model inside robust must be Gaussian"); + }; return shared_ptr(new Robust(robust, gaussian)); } From 646a4b7f0ff4a9c327ab5ada04f07f66e6fee77f Mon Sep 17 00:00:00 2001 From: yetongumich Date: Sun, 5 Apr 2020 19:00:09 -0400 Subject: [PATCH 020/869] change unweightedwhiten back --- gtsam/linear/NoiseModel.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/gtsam/linear/NoiseModel.h b/gtsam/linear/NoiseModel.h index 73484799f..a9f06693a 100644 --- a/gtsam/linear/NoiseModel.h +++ b/gtsam/linear/NoiseModel.h @@ -731,7 +731,7 @@ namespace gtsam { virtual void WhitenSystem(Matrix& A1, Matrix& A2, Matrix& A3, Vector& b) const; virtual Vector unweightedWhiten(const Vector& v) const { - return noise_->whiten(v); + return noise_->unweightedWhiten(v); } virtual double weight(const Vector& v) const { // Todo(mikebosse): make the robust weight function input a vector. From efcc5c908eb25290ee29f04b78e672baf40f0000 Mon Sep 17 00:00:00 2001 From: yetongumich Date: Mon, 6 Apr 2020 10:10:46 -0400 Subject: [PATCH 021/869] rename residual to loss --- gtsam.h | 18 +++++++++--------- gtsam/linear/LossFunctions.h | 14 +++++++------- 2 files changed, 16 insertions(+), 16 deletions(-) diff --git a/gtsam.h b/gtsam.h index 8ee778f4c..1094d9dd9 100644 --- a/gtsam.h +++ b/gtsam.h @@ -1458,7 +1458,7 @@ virtual class Null: gtsam::noiseModel::mEstimator::Base { void serializable() const; double weight(double error) const; - double residual(double error) const; + double loss(double error) const; }; virtual class Fair: gtsam::noiseModel::mEstimator::Base { @@ -1469,7 +1469,7 @@ virtual class Fair: gtsam::noiseModel::mEstimator::Base { void serializable() const; double weight(double error) const; - double residual(double error) const; + double loss(double error) const; }; virtual class Huber: gtsam::noiseModel::mEstimator::Base { @@ -1480,7 +1480,7 @@ virtual class Huber: gtsam::noiseModel::mEstimator::Base { void serializable() const; double weight(double error) const; - double residual(double error) const; + double loss(double error) const; }; virtual class Cauchy: gtsam::noiseModel::mEstimator::Base { @@ -1491,7 +1491,7 @@ virtual class Cauchy: gtsam::noiseModel::mEstimator::Base { void serializable() const; double weight(double error) const; - double residual(double error) const; + double loss(double error) const; }; virtual class Tukey: gtsam::noiseModel::mEstimator::Base { @@ -1502,7 +1502,7 @@ virtual class Tukey: gtsam::noiseModel::mEstimator::Base { void serializable() const; double weight(double error) const; - double residual(double error) const; + double loss(double error) const; }; virtual class Welsch: gtsam::noiseModel::mEstimator::Base { @@ -1513,7 +1513,7 @@ virtual class Welsch: gtsam::noiseModel::mEstimator::Base { void serializable() const; double weight(double error) const; - double residual(double error) const; + double loss(double error) const; }; virtual class GemanMcClure: gtsam::noiseModel::mEstimator::Base { @@ -1524,7 +1524,7 @@ virtual class GemanMcClure: gtsam::noiseModel::mEstimator::Base { void serializable() const; double weight(double error) const; - double residual(double error) const; + double loss(double error) const; }; virtual class DCS: gtsam::noiseModel::mEstimator::Base { @@ -1535,7 +1535,7 @@ virtual class DCS: gtsam::noiseModel::mEstimator::Base { void serializable() const; double weight(double error) const; - double residual(double error) const; + double loss(double error) const; }; virtual class L2WithDeadZone: gtsam::noiseModel::mEstimator::Base { @@ -1546,7 +1546,7 @@ virtual class L2WithDeadZone: gtsam::noiseModel::mEstimator::Base { void serializable() const; double weight(double error) const; - double residual(double error) const; + double loss(double error) const; }; }///\namespace mEstimator diff --git a/gtsam/linear/LossFunctions.h b/gtsam/linear/LossFunctions.h index d1c3adb35..6a5dc5a26 100644 --- a/gtsam/linear/LossFunctions.h +++ b/gtsam/linear/LossFunctions.h @@ -36,12 +36,12 @@ namespace noiseModel { * The mEstimator name space contains all robust error functions. * It mirrors the exposition at * https://members.loria.fr/MOBerger/Enseignement/Master2/Documents/ZhangIVC-97-01.pdf - * which talks about minimizing \sum \rho(r_i), where \rho is a residual function of choice. + * which talks about minimizing \sum \rho(r_i), where \rho is a loss function of choice. * * To illustrate, let's consider the least-squares (L2), L1, and Huber estimators as examples: * * Name Symbol Least-Squares L1-norm Huber - * Residual \rho(x) 0.5*x^2 |x| 0.5*x^2 if |x| shared_ptr; @@ -135,7 +135,7 @@ class GTSAM_EXPORT Null : public Base { Null(const ReweightScheme reweight = Block) : Base(reweight) {} ~Null() {} double weight(double /*error*/) const { return 1.0; } - double residual(double error) const { return error; } + double loss(double distance) const { return 0.5 * distance * distance; } void print(const std::string &s) const; bool equals(const Base & /*expected*/, double /*tol*/) const { return true; } static shared_ptr Create(); From c54346cc590a38431e34af954afe6cb311b5c2e3 Mon Sep 17 00:00:00 2001 From: yetongumich Date: Mon, 13 Apr 2020 15:17:36 -0400 Subject: [PATCH 022/869] modified document --- doc/robust.pdf | Bin 197679 -> 205572 bytes 1 file changed, 0 insertions(+), 0 deletions(-) diff --git a/doc/robust.pdf b/doc/robust.pdf index ef8dc6fe624ef0af97973b383042940993273752..45c023384c723a506f5bb48b2bfcab5aa5b338c3 100644 GIT binary patch delta 89002 zcmZ6y1B~EJ^exz$wrxz?wx_3U+jdXezqY4s+qOAv+qP}J@4s(%vu`V@-(ZydO{~plV#;J@%x28R#A?RGZNkjW%Fe`UXlBf1Y+}sJ#cj+iz-P$H#=>dJ z$%Spg%Eivi!D`CM!e(m7YQ|#1!p+9Q!Ns1i3rZk$(Q9LjJnBv`!SEvvACXwem^w@a z4m9qANVxD-9+~i3y9RD2W*t^xZ7G0PowSRyM#g~xR7znASHcpD1veJV*97?8{! zgoBh7aPVIZ4q%a>)Uf{-9(yAzSU$f0uo#+~IuWxo{cngW9uB6&j3S24hBo%*2^K%- z0cB$D|E^TV)Xv=5f|!|=gIGWS*2&q?)X)~zJ=560z`)4B;MT;z&|t^P9NEMVj4317 zA7jLXyEpe{4<;6+$9NFD1lw4&r2uo`Q-SVYH<~SgPQ}F=16r_w zRK$eiq$_ zPHC1k<;oVB6vyJ2v5bnY+*bsnc{B|;8s6JySh*3Y!6s>{tp&{g`un436g{CHeq5mF zNnHjzj-GP9JJ(0{D<^p0W3y#tqvzW#E7_QU^{PIToRJI78Fd#(rN2BNdz5u6ZI|EW zVlqNmlE%jBpg~*aovLJ4SY(ocKYukEZJT-J>7;6G zL0?x?#HD>j#OTI8y0?u>I@jiQ+r|Xxg2qpM-Q%v;C*OB5l;2(Ofs?fi*)D{FOI_>> zD`@-9$zrGTYHOh5b%LgIOSNJP=%4XX=dWBfDk~%zAMw^uR~m++ zkdygChn-=Es@E93Gg@K~jSPn(GepPC;ZdGIh$matY!)EVfeCFTXSZqOd01Uq{F+%@ z_Y_ZmHe{me;$D!XPclIiQ5@e!)3Q?2cm<>XQ-eFETXSwvRa%@?W*L~y@pEW9%z+$D zD+Et*cC_C#6FdOD_3#$k0UQ1ak1o~K4 zPGm!QYz4Th=Ln$=>K(0QOi<#U*Lda;$_V#TKlyp;DnrE#{gH}Er5|7eeV~||f!CjU z>$;60s#J0F0;`}0JBhMMPYB_}5h4e6hXo3MnFq&YVGrV%^$n)OVceK|+rjh)mEaZ= z9|VbgaLdlWr#XWWyCljGmB=R*ejxUEGk0@|&>!&2G@e5}V4IJJQf--J@SslC>Fq6f zxHyv&j%p>ZA8l;ESL*neZQx4+pSG|jq3EoUFpnBk8tO9E%T#gXe7m1t5=$W;>v~2C z(PR{mQzTUT8vjMI5L<+&!DEV?Dnnu`saYta5rh}RD0n?w=!2oqfgVpiX@28*P?Nbs zj{?M9c6?N+j|~_(jFQxS+h}ifp&x^(Wb_ixTBAgk?dSEr zpwc`gv(sxQ>G*fEC|FbD+p(viV!|haI2Gl9V=9@iuxjP?I6p1w8X3ccglu1rr$ zpGYCUVIrvW$-4ySGy?C1aZ{)SnYJg>xjZA?#&x>9a0=xyKR?}aE5Tr|EHu75zfc1!@fUE{3k-?TC9EmZ+Z2vM#w8_ zrNN~2^6T`N-L|!NnJg=cjGFXv%EDQ~K322!>;qt=xAF-55A^`}pIKCS9WyZG4ZtiP z?o#Q4EzrkU#ER#BuYCCci{MY0_|)__PvE}KG>H~uP06rk$9j^eaQY+k&XtS$$1i6H zl%zJlaBU+e#7TZS;GEJ)Dsl%ZD3BoL(hqp$LUzCDs*&W~W7Jl{zcodBwE=o8&!SI; z@@v0V-0ucL&9Fj@bO+@(f$Q_%-=E5=gul_GnBF;y3($IqD2 z&p(j;l}^K>N`-E0G^LUN9e-XT%Qr zKXjNBVA`?aX7f0i`cY4JiZ_R6L0J~ImCiH-!2Uwfe8yuGP8xqM69MhI8>KK;8<1d- zinu4Q6Q0uo4ehV^U~(#)hn4NGI*s9x7Vp6GzEeBVG4{NU(L`flcMu_YbSg||xwxJU z`~C|TEk(?v5$w+7li_@2xxuHLl>}sL2;8f0Nq_E)CCYpPG(7ov4rUu;Wg60ZoKZdXy zP2;gno6DJu&k)`NNw%!Rww?ZkOH{a${u1u=+xvkxH1#g{5CG$S>zpnvW_o%xacL-{ z9#?FWcO9`44?0Ttl>b-a(kZvJ-)oCd#jRGd_|{d$PF{+WaG*Z=I8^ zbSnER}$wss9^5X8xIvm2hJX;@gU-jHX{GoBhGu2-PE@xVi{g!R@^}Gc9n0ou2 zkuR*_+mcmy2Xy0Pb7^tGqg2a9UK!!Xcc}PI%#?%}ZK4F5Ji>-~1TV@2b1Rw#cXk?z z1cN;IglcU}a84HH|Dlb*f28t1Rw-ub=;Tby#>)PG(1=C6Rl9YGJD;9>BDcD*)n`z6 zu$KwuwjtNd3HUpq^{6VG)j0`Aiq)EJ9xWy1Lew=FObucNj*LZBT{reYY|26=J$J(Z z1+7%7OjHUOg8W+4FH6HDhc&p0;1)>@(qFaxS^$bN@)8U=`;L1aI!L4nSY_m|v;zn_ z1v!u1LIpw?>b!t>A%#*1q%0IIFmCf;HJGcc8ORfE#zr`?R^mn|9)|vCkkP)Wc=`T; z>ZH2<0W%Eb=USH^30r<_Ed6qZ=djg?qJFeClM@rNZUV5et~jSpF=fzrOcNa{lcPTWiSH2*{bM zAMd#-c9mg8nz_=J2OiCzbaBIXa1@KvKmljvOp&l;<-K5mXg>U~_xZ>+bq9Ww>_x%z`b05qPRO z$7u&2b)T7FG%GkYViB=MKE-kwQfxgqxbnU=T?2vgi(u5`U+kDY-1CfP=v&{|`Fy)M zdD+3ZT_U$fZW++Fzk_5)+_Qc2AnNAz`Fdi%5qM=!?lett@usrgoPOJUAK28_13B+{ z#&di}yx-xScw{;%&w1@z9Y4002PBW{531T7D-f+&qna+vKObIpPIn1weP1glwVy{e zRo|G}e9p{$AKnbUTU!3{`3AZr5^OnQU$0ER+k8I^R_NX}HSh3GE!DN)V;T!Q+;8!E zwY)!I?fATOPp-SBh0eg-_)9&1P5}I#zV&VaQ%iFmF=LyM=9~)qcGAv7070j_kJ!=^ zJ!8sdBc_u0p&j-~u%qNTdi3)2DFzYJ4yKqKB;S)cu$NYV33)2MMk zZI9%zmWa!CiM*TxMM>YmSp1``N7J(Ax2SPr@X)DIwEb z0`1yqN_9`axbr$qX}?VfC^=fRmH*Y<%D4^Z649t=F8D$wQijo<{#FOPfVYnpRywHR zFT5?xOK@f73fQZh#458#89Fn!S}-$t^T$hXt?BgjNJi;j@@5Ggr{80GNOrtE)0o>N zYHgEHHhG?|;M{IR$~W)J#{e7F#NH|bK1Fh(K|+tnMkztkE>tVPxpfIa*j9@c97lLX z!2eA+;w**zL1CH=vvje8GI7!CFWpAKXU1LniDK3@Ut59~H6_|289rkYh8ugIVfkgJL)^?o zL^l)+tITKBv)~iJGPo7>*$mz=_0a12kNi@>5Zx*G<#BF^_xUu{!tW5om?Vi&{{~KQn{0J^%vMY9)1=I^XwwhT&hn-+uau~1RtUgbzv_h~Gv@1Qyc4Dc*$&j!xzGz~O z)YV)+6z2RNI%btBg_c`C`iN)I+>g7l?WGQN#(rz2c);rcU}_FDH9M|AnZm>dL95p`sL4wUz?#mDvdG(UGxF_)$7VrgWf&$e4rZFgG0WU5`*T7_-o)@b z>9=IwjK35V5EbnmZZZLX`vWdL82qz>sh$+U4@Yob@0M!Llr0rAaSz+{QVIWn=%+$~EVPO&664s?^fS}}ql5{1Ar~-C z=j@3c=6A?3Ba`@CrU>SHFd`{ArJoVW62yj>PvO$Yw&a97srnJkfHs_PLHnk)50AiItZ=j4(nJH+MF?X`bA4lICT5nZ( z`e?DyERl3E!!$X_@!S@b6F;n#4GkKL%rewD`G|C3k?f;Ve^?cXKb#DM8(aN!?(k>x z=|a4Fds16fiUir?JrvZvPPb)0`Nge9a&7NRt>qtWNMB%1e*S3xSpxq`yZlrnZ%)>v z3ososp+Jc0qP`0G4S^$s+v2&ZX-F&3Vm^dgLS7=<_Lu&}#-NsX5DLddphLsw1{0NW zpyuq(EeP{`LSfb^#7xV_VBZ^A=i`5@YBg~+`sqP>k+iX-lyXv-2UPBjZlh0mMIk>>)oK!Jqf#`#hx7F++A)o! zy(5;_a4#yIk9kBo>r(7brMf6l+}9g5&?6kr5k``Jx;)XA?fc{}sY!}nI_~0IKO1qJ zD~7A48(m7gYSwjywp*N*nvTaV29_u25L+bU`nYy`#~T-LwXvy^PzDu9Seb%l0|iZK zJUJ{9yJ_9VF2DM<>)ghTx-gxcR7(BAlK4?#;Lc}l#)~~=Ni+JJ>Tm{TR)=HFO#{*8 z8z?b07uP6Hn5wB_Uax~?C`BTfBX#MQ@Uuu<+Bp>UV@v17bojDx#+ck6@<};T5zkRX z>AKy+H4MpdsktJ&iAuS}AudEwfvg!_LU9SH2pjyL7})kONI0~?f-ZBhc`=4f)(6T~ z1&Pq-(m(S{Iot1MH;r@+yfbyj-=OFpE@Ly?MIuzk{$7@_%H&T{jM>7g((2-k=*85x zjRo(APv!Kqifz-pA&1SsG=H3xdYe(;EUUX z!cChGU;H3_r_P3Q&k#(s&vZ4|wv- zDRxlZDxkBy(iq|rl)@-4=-u(MLu1kvKJd+GQ|o07qiA#4oG2f~dZ5ZIxF@qt8Fv)Z zr)?ODtPrHI%B)IBr4M2wuBJxAWp*YXm$mGqA)lNKTT7=01=bYb{J`k>Y@nS$dO!u- zd}lWpn4H3_da?y<0WtMu2R!}_y=7MK$FFItmbDth@`AI%@{0Sj{PxQ9v-0+8vBlQ* zGP?>%_BPvcP4*hh#l34u7xhnFpI59ez5WFvYBGSWy5{I7fK%VX`AX-D6_be-!{*99 zrhR5EaC2WU+v-317z15%mQj39yWb$nPpEsbr3cFLRoY+y*iGH+SKd8m?xp0O`6MH) z#T?dP2ckPb_X}2Jt236XFJ_!!qyJIsqD{Q5d*gb8NEzL%6lb2dTAL6{7(c5iimo=7 zZJ1j)J`)6YF;!51SsO2mu5R33SR7KP`D~9r{c7(=LRu=1FUp@Xe-vf46JU4}Q&&Il zxF7WNW^LC2w&{u&E4%S^7xwRGRoQzw+RCsBMlTO71PGS(m(U`Q?(>mB(-0p z3AZ12TdZSkw6tI|wANla^VOv}yp<&tw0m|HiU|}$7nL1|!U{B%8PjpNCv*POV?3L& z7x%|!hhvKNC#oqIy>+H*uJ>8Qj&I^QTy-hzXpHv(@Ej$a7^ZR!g4}tc%IH~QOJagr zCfpva4Ri`y*!iy@lSsPRPYX>s5=IBaR{s(64#iZY2JBZx^55jVzi`{AP2MX?Z6PBC zw}9tT3VgPGQQ6a5m>1TPk(5|6eUbE!VAR9Wle1#TB8T>Wz26O*1}BWetc6G(4@NB6 z8(={|SV^Xocg4{Ys&4n|c{QPN`k+ik!liqbeNB%{O@_9@D-p6trl-AltcUt57LY|* z%x09#-CVri!40vZ?}i2~;^`;px#bNOa6fyD?{r!C8E$klK0_50lvbeNiq>+9-u8s$ z+l4a<@Y-(A=ZhP3=vQpFmd2qZvlEW5*r)=l!Y5`NIH^8#Se58r@iD9D9iPmWJu8BI zT5f%RW({Xm<%OLe_$s&1XcpXTxi>ku5!N|1Eof}5#w|GyZGhT!T1u5S`!VWka>^l4 zYzG5Gt+xuP;`PK+S%0mZy@xS0s1YZ@jz3y?Cs&cS4~t$er}Z#Nd6dVl2ev-wtF!H{@lyg zcD|IyMT|yYlhSu+sJid})Q=?WTP&eD*M8=#p!qK)-;5^0oqBzwSs#f?$_2zK`KXFt zJ_+Nnrkdp?;7CzJ^iBy^+)S>f_5e=1sJmdJ@EhaQS=4R9LN{MSoYgc(g60to3j2SO z{{JoSvk-Iq=UAl7rh{StT>qH_|6is5Z{rUYv@a|UImtk0DrTWV!-5XwQ#r#ZP*M); zf(|?s7!1qUE7Vg=WQam?^1>pFGOW+1>uH%KOs;(;#i`bBvqmi$AB;LVRLpM=;x*Zbn8nG8+xn))0tW^wAdz% z74eRr_>~+;EC>i09U>|U6d34-Q0|I;1au*n5XuE;1E|Ff7$M1y0;jjykDy3SR5SCK z_P_Vb`XIbP;2@}IXuDswh_Ox~KMj$Y@N+@MRzK#F>N5C7;WF?oSu%txw`I)5?>Z_w}NIfCGrblok5Cv3fY46NI_ZzWaRWatjG4gtcs4lUYfZmkIDFs*+PXOxwpEZT&20ji4cyk3Nt25t~!#uIxtK?1TtMO%4O+jToL z@T<>61o771&3SASj%C71#H+!ZI931a-LtXLtO;XR;OF2P(ywUu(sQRAM3NV~-tBe& z$*m*K)sJ@dzC4Zz*;4nZ8uGUTE(a9<=nPR+`9t|wE$BOD0x<#%8g%eQG$f2uau?tq)MGt<4)DXP&we#NY&z}o|K1XnN{cgY0!|06+ zZ2%sa3$moZi;e$HblqZ9dP#J>{z_`72g15T|0x8rQ!~B&O=pK=7U;+8@m=uc_0Rh* zM9i_AM+Zp$;G|-VxdD5*yMY69e;EXV{6S)KV~K@+2NCUj>x-`$tmK4$jB6m+MS_HV z#$DSMe2uN{%cItQw~^rceZS59-cZ7VHTVuaJrW`zK6rwA_?~#)ruYWfz7G$-#~!{X zB~~{_PdTT)Li@j=pm+x|JHHoNi>i6gToKriTgE}Y^;Jnvh&n1joBZ2&zZrq@5U}m) zK>UrV(`&K*jYLB|1w319Sfg(!`QPEr~w)3#b1E;XgvkF7t6ULjzghl`#0pxZ9ht>Hd?Q( z#}|k;1nT#)%nyGM0c$dBFc%p=+m{*kNm zl^iJa0U|)QaDlT*LPS6N5xg@kM?#Ehh{$e8FIawX<#ksXBjIDD%jwzIw-4|}+PHj6MkVws zzVevBcu=IU%!sn|l>hUk;T?8A?3h;xMSHz!le-VzE;?l0ta~*3NK-8Dj(O#EZ0dS& zcjkMm$MaRM_6_NaPL(~mjL~S&-4qRPavBBPpGw^qpOU@5keQpR8x*NOQg`Z2GAXx+ zr}$bO0@#OnjN?Oa@PI*)m~lzh9T&H~hYK{#rD41w@#)r^Pq+Oau->vMuV_=0KA2+< zubVs;L^J7gGsfBRKGOTcMH4x>+wBBu>(F3 zi#|0}RF4wW+C-5NjGqQe+Q?s0WOBKjfl?oN9cIzNAGlkjRMf&>BTd7iSiGw#RPb@) z7FPepw7lK$Wx3Irwzwb#pQ(LDsg(>au6AF`L#e7AIQBv}2g+7h0>^z|83r9m+XA)@ zi^8=+_}`koB!NqK#&AA0I1|V+n=clgDcN6`meH_sQiF~&Tb_QG)8YY!y!ouh-GrlK zxRh;zV1T!!i5wEuyCH^j9Q#{a|aOlYiss8Lpr`1+*7&lfFwYx&%s`*E5x9nVAQ-jfxYoUpj_N6R; zOAAZuYEGlD5220H*O#&c&enw~BUhy=t&|;pS;DavlOB5sHWNlDD}Ah{$LPBbMw`0U zXL24@2e2>xTM|D#i}N4?JC6FT{ZSutrLhjVPFxU}$yV3K^0Y7-n?CKfc(X@y4Q1Je z6zc|kel>k}r|QKG9|>ESu#@S#r5}g*7}wo0>#2UxakOHMl-))e(`gzl?eobeD)(l_ z?($s;soq}BD4J8%Rb14QGuwgo-a?_qw}DEu3dA|qr<$zzaEBn<+f+twOsRVkY9qeu zw3r1=_w;^DVym8B|KPxA8QNXx_!@tj zB4QcIjtYn&S=ENtm5s~fcQ@ppIMPg!+fsC7pUb`J>_dW2$b4mT4& zm$JxJo8F|QO*Hi0_u+jv_R9ZE&*Ap;02E5_U*)Be7FKd5C@oVrb-|)qx;JNA=vl1S zEqeqH8fp(S_~re`6jS$VEI7GCycJI-uX~hdw1*U;|JZf-iuznJLohCHx6G%sWcV1p zGsr~#+%AnG&McJOxeeG{)=GWvJDPARefVr}nk>HgcbZ6KVrq}w(}C%4_TU~`3^=xB zH-l`8LrGP8Gd5bh?8Ip@A4VC!`ScKb`7w3H-~K9J9GTfVxDwg4-gcz;>Ycu)&#>W5 zmoR+uKPy?fU5$QC&SP^LG_GjXR$W%nTp$>H4pDbq;V~(&5cWx=1$*rN2ZbAhg&IgV z%|K`FrP2%ccIlY9bP~usATGy_8&n;-qiwSoV$KgoA#6`MJg3A5iXW87ky5HO-vH6TLF#S56>CjH}k&r;h;ra zWMOkVBje+9-T82_1CwFDQN$6t8`|!N?{VdfJhKp>_x;mX$v+2-hJ^fG5->seYEZ)7 zj^Q|WjyKHK4rk-)_%erHHej_rtRt`En;qdraYYOWi*#Td8}4UJVASnscd14k$-?|s zMtidbuhDiT>kb5(5@=f;HW`N7D0gujBBo-y}(f$ zWXPQZWwsiMV6Ku5Lmio-2fEOa-ZY*ZGLES`jHr-T+!dS+&P#=2L<})ARpWTBMe$mC zDGo7aEzwIoRb)WmdfiAFqDTrlY3`%=Vq&H%7RT%nST?G|U_*=K`63kbi(elS*r|h; z+~&M?e}u5$UXnL(`3}O5*nG9WYY*wN{(MQ)=KAlw0>uAhaXy|50@l!Hd8XyRt^+3) z;o0E^)3AJs$Zgu>2eSWq^D3)^FAQAGdN2_l1o-xtuv8L=Yup{3$CQI)f}0Iixps`o zAP=%&7=cB`NI$gxbQks9A}e5r*w4PTu8xQ)SXVtX-`};JwawaVUMLzW#Lc?z_{U9h zVG;~VbpcY-nmvgo0idXdC(#_NrbGR>x2{%{DMsj6gpl#1M8$raV7sO8lFh0Pqm(} zkb(k}eZ`HO0gC|FyKbpfCiTC9<0IKFZGA>cogE>+vX{-!(MqJyFlFr%3hho|Uo19M zz3K2BwlFme@!TLx>c8*OcYp7jLi$kCq&6!W9_qRHa{@)v2*_qRm`r(5^h(r4l*Sz{ zu%{l$rJ_b_0STScKUc`ZtTB#@R@`O+qmk9qfBBf*EJCB1p~T2Umb#nnzPd2qv*`*~ zld%R*_Wcw;+uN%%Sja+q^C54uEBiP@xg|lUf^pd9O3AzRTRp?GzWU*5enV%j3@> zZb)fVUgE9g;`j}3a2sv<0O{j-@%hT!t}YbBxW-A*na7s{DyiJ4{2PpMtX+TWX|oGF zE9B5`qOW>`X6cq?lS;JbnL=D*`l zenIP_8^E~MiDi8dGInAv8-safvfMV+tzbgpd@?H$03kRKfY3Aws^QVYPN54)r*L__O*em#!5LM_cKR7 z7y?0DP*od_h?GVzyErORyQQ}{r=aZYU`R#a3t-SIN@q=AJ2d%Km|0$q)hZ8D;Pri> zCj(XG9swIXdN!)M(m|S}<($LcXrWK4%*G$PswEGe&Fq9?nfkRsZ2BqxC*!GQQD%nX z??mir*I1tvk_(+r0B55K_2p5awQzXjmbZoW{qTB7wK6m*k@83i2nkR;newJ`oo>Z` z4%|8<#Y_EXLBi|mQCvlF5#`)e?pDE@mi!*t)-OLL2Nc~dE(?1yYfyn z%zgjq+t|Xj(^W4`0iQe)@Tbmeogv|R9mt@`N69Bxf#59a1}9{?wq-+WKQ>))5OkW) zrma7$T~GN7-={F^dEt~EK-AbgI~!Dz@_s=4>dY6Oq3AZp@uy{1t8ARFYmWjdL~rmy z(I%FIjHLT(Qs!9UdA@xGK8rM6R{LL@x%gP_pn59hEBYlC3Qw%-xhi|)B%EwU8}OEg zn8p$p+ezcm(>Q*)V2=h)l1=Y;b#-0j^XP>^|9flm0v>;*^5RWEka3uxM3?=SB4Myq zYpl4*z)`^Js8hF7nv*hGTdGzVN3+{8N0QgCOuD42%PAe#P68OEK7%$ufd96vy`jS2 zrsE?iF*qC==lDE`+N5-f-EUOF9Qabku77Skm_YPd6%&cd+eiB#G;eT4$gTd%0J{I^ z81)!0q;Z=3!OK|Lp@7=Ysu^3|l{}C|w5!s(dwjI54?pfD!WXXpqF{>rjKBjTk^A_V zBTyzcPWEIMx42t`UAP0O&}!qO0Grp*(e@M)-!j2mtAFV+$ntwe&e5tO4e-2d_;~7Y znkTq-h4+vOnR6g{kA*i8`KPN@)Oo=ql|gyXl})b8jNMTCCT1>F4KYP6NP^HHbIs8m zoMg(bT1V{%DXx+My6J6w@b7-mI@+LJfmyB2M(J$dIfIFRw--ih-yP>WjH`N4<`Fa@ zUz{k%eLP?aiZdJsl=tGP8-QegW)RO~Z=5Rf+8FcZux30lrZ`Dc6}=jD=0@)3ctGNo zJ{;b5=wB{(sy9>TKp{{g`D|0^qSP2%mxfp*9TKgmql&MrmdvkBe*9#LWgHHhs=yLu zGoU31J>gQGJ|9Ps+t+?s%ih?Ot}fC7P0}8X`FAFWV@QJHwxT~=1E7&mogi2DNSoI$ zF~9v@4kXlUA$KZ?*18`~+-+T3sYELM`n#L}Z`)QCH=0r8SO1qNEru2Qy0sww!7f`f zErg-sM2q>PWCiA;+!eOkM5f`dFwr@xX3_){ubBgTGQ(UoU3@IhOBGxA1Zi@HDtl9% z?r1)mB+=?$Be-a&E5Mfi_%)k#*k^F&AOAm1_Xk_M5V!N27sR8{JE{WM{)>r>je<9v z8m$mLICY~QY?z{fFyX9r1a*~9C++8hYo1Zpw&tj=5gEtSREM7WpXknemw{kJflHC4fAdhg(+zUE?KMDSL^S z^svwYkxpQHk1et6$mNrDIUDMk^Lx+DAZmiG+g^?aF49C)C40*y@#gA5vd%`{fsV*? zrHn(NE-8qZ_z(?!KgV`{cS~A48A=n8QWC02xL!?y_|{GcSq|Zsch&X-shh!dhN+2r z%0Plf_TT@?VF7o6jSQu6HhCTEOV3|J#3XHGwM=!gz2d)cVDzX-`e+{H4;sj%jx`BY zCyYcEm}V`jPHP7d)hc2#N4tsXvUg2cZgBZwTj3U6Vp(EwsTG_zOMO4gs80=xJ64u{ zEY(`Sh2T3{9VoefY4H-7Cd1f9z_ zzm|D_MxHdBX12mTjvd3fIF*g(l0ZdU`@yHUy#Usv9R@Y$z8Bf5umldwYVYggvi^yJ zx%PIx!aX|hp|i?MinPSGaPWv(j-ta2v&fYcQw)r_v9`DM)z>~nSCOIE*x9ouwOenk zAPvAIqV3vOT^v?}h&urrz%&{wA7mt?dvOZ>$=x#c zHy)gIe)zqs%U|a5bbdy zN8YBODF2@uch)Nc4JhWGY9pVhcL)mfEr5QhZ0C71;A?i79p0)BA1hJBUgnuK_yFsg zG$GJ9^ww+aTDFww7iYopYbq$bMjxFxy1R6}jDZxw5cD}|k=2f&hdIv>SG2!O5x2qM z8riqI9N-RH#9GTMROGsWPOC;&@Kfm7uP5%s(=>FD+WMm!4frM7W>P44R2p>74I z7D)a6$r_jApPQC87FgHF2$2OxrnnWZvRfzQADtt+tSqkib8DVbI)<~S+6S>=+lsas z$*86{mwPFl-SnpANn6uje=82gti&;pzO#@Odn=ZW;p2XCJhfgkua!vA!vlhWXB3qE zuKM@K@zFH(G1zG?_lmhHH-AA!FCKq)2&`(x00ydZgZ8fR$`*Um=!HGOF~P&W zSTBpL9op-qz77|2-&v~qj&XH%Tp4t!NW4`N!Hfba60RZ7`RlNI{UzhRa z)G(QkI9McjYSYfNNF&DgJMK-uVW*+>Q*0Mhq(1JFm9Kn~2L&KiIel|6>G)~uLg63anSq3*w@f>Fl95VjE_`Qah@i=OE!y1e9##vk3Jm9RBeu*dYUe4@vi zjF#kYisR5WSvXNT=qNUdJxedi%`$L%iAV5iDrH!(O61Ihz{>H{6VBgbuc-kdOKwSB z5o^@vmgS8VV0>S*@z8u7& zP3#Stq`UW}AH76MT>5&}_9b3qPMBO;JFr=K)OyhN|HczNY@zAiea&p~t5kRx%0qFs zoK3d59(-uZZD?ecrr=Cx9$36w#BOXGv3*e`%K7=BfP8c2ew;@ti4-(l8?33iTaPae z5ua=1qI!G!LZ7tV(aDV2x5U9}oDMd=D^C?o?`C77d!ZYtjVzt5n-02EIcxslp59}O z%(8^uv7%MEZ8ZF17DmUcPGV7$uET~)4(9aj^c<_7+PK?0F)&fL7#)e*SiVfD9Ew!` zbrRGr1GViNj7fBL_)-N}Afwo`@!Hxvu9lRzPt8esxNX8=##S|o@{FE&atoz zRHB1>>Lvh&LwD*=_rge9YE|y;FVGmi&J}a^p#yNYIE{)haBoKkgWcbihF&u>KjdGm z1>@Z9W&WCSS&oWf`<;Cx_@hg{7qrEY_p;E<1BnOn@55vqjG4y|u;7OYEVP6Hf0cAx zVLBl*kAp*{X(2u)##=k*wrH^yZFV?b^R0sE|Ca5Yc|C7O8bLxC5>4B!;XYU6ZelE3 z^TIZ>8#d(6Zw%|Vgxw6iY;awRQT{w-V))N)nlWhH#ew>F?f_5G!yTJB8NmVl(R}p`I_qyQyGF_jQ@~8G8g}!cm!`CBZo4nX~`B+;^q+94O zv-)3zy4RQp#Zj?Ud+?t54SGeZjo)ct_2Ero z2I14^GTBwPye_i3oFPxl4lO|j@sJ;Dig`k5Xl>d}PvKjsLx{7BsH?Cf%OnTE`k8eQ zGwGE+-EdN6Tyk9|d)uWpn>yVU09d|NZ#O5lG$Sfali~AxH}6vxxa2g~Ut}awasU+A zR*GO-JxXx2u1@oE2&|yWwtOB?&=IME5DFl^ON(?k}batU$&B05Rsq8i&w^mdjRTA#b7{z+0;=U3lOfTgvunD#UN(v%F)C{jIGnd zN{9JJpSw!y?+D)BSoA5hhhA@0XK2Rx*bm5xWZxR3H74wuSLYf}!dOxC(U2M|V=-=t zM%eLe3f)cY-{&%>!1Y5DS*i^vmvbK7`FkcLroygRqv|uUO8?^gwDL@}qidnnW zza;su*-f9n@eHkLY^y8IrBclG*!UVWlEmNjtw7|{`=jwuUGCVY?NFaaGoHIRk$=RF z4eh$HqRZg>%*s0|1p|~ba zhs~doIGXUrjgLLpTlWleg@8V?F825+=1FDIzdXEZ?ajS23RP{x-e3AM%VV?SRtF~i z?z+(AWhZ{4*M*vRaPAIqNANAA$=}CU+X>boz&OyTW<2e z0%Z@yqNJYboBueS~45rdfsP*`_`Ma21sW7#Qe-(kCgl0({2LY*DOWdq`HjF)y zL8MX}LT+|E@-MvTSU0?Up5M6|}qk&;G#T-gb8$Gu0?2ytN+J^v&=XBkW z#HycFdWaaO1~Y$`QmGA+ou>b!$LxXD47vu=$kK2|5P&DT9%JJW)jfO>g~HJJrr3dj z@}qM6*D(11THee|Osp&^w>zMi05coY|LJ+R{7}hQ#pICrL(NcRA?3e!h3>|9g-R?` z8$>p!8<}i0xEa}jL9Ny39;vJYJ6P2#Zhka1(e>T4^juY$lxe=c`hH=a!^t?%puTpY zw1g}j%l8kbZ)&oS94uB*S$XdW%;C?ited zAq)xj=;v>HiH!9AVGd(ZZv^Q82M1UGxr-R<2-erDCS>l1i);wx=(#crdjdTZqTw$L z9rF#_2RzIn`ujyVIJUR7{Q=3^!ADN5;$p??MTn{exA5N~PNf~ez3DLV3;Ca4iv%WKi!p-pwR5+&iVFeGcY!#gru4%?NO%gst@yI+g?u@8 z0NKFb07Bo#-`$97?}?^_XlcXH&`&NvU7LTb0Dc6*AP63+h(Wvo2q4bQU$)TBK_Y}7 z{?$UYq%(JYJ24CXARg4RAUApaJ!gU1eZ2}0nc#@7AG)N+*Gx#mbjLRI;C~#!xJh?b zdhQc`3<#+q9bfgmsyh*6lGsh@eG79Km|JITn`-ogIG*tY>gok1nta!LARB&@HvAv~ z0X}qo1$6%U0EvYIIj}Pwe)R$;K%zQ9B7e5O6+sZtQ-DS{xL1H2fwBSjeCc}%0M``; zfw*8F89v{R_!e8)*Z{Gv#Q-yassF)i{EhZ03}63>Cip-E=?aDI#6J^**ZcT>|2+2K zZ@7ePE*=9+d|NP=JyT z_xHfzcg#^w!H0g@R}ao;kE`>C$n--=-?uoDGZ?Suhv}`*=5kmlvqB&reBk{zkbV~U zm8r`f%l^_d|813o+#C8Q*0I?qmyMT`2nuUE$B{{g@B*>k_lKCq>ZfFe;9+|Y)D+4E zyyp-9KtP`vNl!=TyTB`zg*G(Q8se*WQczXsWnhHl%i_Qu-V?k0drD+#71rp}>&^Y; z2Z#_h{E7eP%m>szq?(JyBCVZk>?xjiv$%NTEx#kddUDUqv!AgiCdVc^+(-T3MHf8{GmQ@)AyK@=?*~{ zOK_0Wi=^61;C}-Yjef?4tqaB;lb}2UeWAbjzx}=!AuE=dRzz~XQgcEHKcT+=kOl}{ z5z}7Svm(>Z8oa0PG>_9zOL0E^olUU_9ZiAcyC`@yOAXU&gSlVix{P|@PEvZc=ij(9 zdm=cSV@OGpZlKgVZ)yZw2)&Ol8t>Md8xmm;|T(%A}B$Q`QR$`-q=Z= zaBc2A^$|MHO5vS!7-8hkm0p5$tdzP-r9|shMAvBo#!@HfjSUjD;d@)po%s|&46zcF z1NHYDq?O040~U(7?}Ph{JD!`=27~g_hudWYi37h>_>PL(ht++%)I4fT_?ECH{uN_V zx~eyKUn@`FFs}iN6zFY-qN=F7?fA5sJonWxvI=%YUB*NG+{z<~0x@+8^|~3+?z;gF z4v{^eB#eyJv|Me!uwoi~D~JkuZ#Kpgt{I*SyL8k4Ock-rai>#_ITg9~@v;jZzr|+U zJ7uX#xg(^0G@MWiFQRUPH zdY0~wqKe_UmvGB8_}>Q}EkRZ#hzb$HvDW{iA!nY`_pV6X7`f31RrkMXeMD)>IcE)N zXL8mf1L?m0UVce*9(INFu;e75FW*#Q+7HOE!j1Z=^I9`#j`PGZ?OH**-tqy;@OH%EM?y1l8|$SUWl8f#l@dpzR%2yEG3yb7U`*UW(#>8$^%w> zt$TdV4$-ofWOwf`EK(oKtn_ZjchL=C>Rer@x(mOOco-Z+& zpE}W-5~K*PvG)XJZ#;1Tst);4EL>vcNWUk4xuT5hS6t0LH8G-;sb zLu}4ttnij?YN{@BGLM@dO?W=R*0N8~arJ*XLh4ka4km7AoSV&qLQ9`TpOYLy6JpQ*=kEfQ9}w zfBqT#nmk6lBIFs3lmjmf6~?`|FYm4Nl%7_h2r!w$)aWk55h2$8{y~eS>U*I)rdD9! z>N(%Zz1Si32rQ-5)nmTW&Wxo?QRQ2;x5?>O!*Dm^dJ46@JYF`I`kn|^ejkp~0^!0Z zRatZbz_vO2*=TDN#{4j6kwB;KP&n7IgLK@RzB|VQ zaksc7gWZ?k6%C`S`cU0ni9Qnh_^->e)2Gp;S&}?ss`qq|)zq>?h}QPw?bzox^<+5U ztgAmg=PRE?=etTdU9MfYx0hl`v#^~A(=4s7!D1@h5*-St(!|xJ4VHmgZjVTce_nRW zAPIwZ80C$bBC&ISg91G;)$GfvhI&S&miv4Lna0ChuZQi)#O0jCNZ_1*u1he)9=q(?wPcxgwyO=$s@ zrYY;2l%CB2i|Q4Oi4+M6)4JS}^`RV`!pNfi<4TWq$K*W|=nLEZb-!||Afq_W+6cJ2 ztYlMTd0^ML`BVogDstAcFkH`DCOX7d{xYogfVh8Yu&+3H@19qq{V^HEf5fAn+4+e? zOQzm-pmM`gnk#fx+5t)jU`Vzxndic=O>(tA(fe5&C6+~Fo2O#PYD8qblgtclMm z@h+tm4H`^n9VYBX&!V2vWbP?!~&Q&-46r$SqZUIK@Z#9foOmK0Vc*!rn~ldC zN4zYv_RsaZGh}y#wj=3}C%um|pEb%yEDsJxG~H3`%&EqUn)_i}YbGfx(KoatbsG*a zeI+Mz(sJ1*zQ|KHCXe&AnIS+CW=r}YQ2YIfIrnwmq^}zQr**G{e@dGTO@jNaL=Yy< z$&A!g@3My@Q{bBFqvkP0Yc?&)p>8bE!TvT@=hF{Pk`pXsH?cY-!m;ym&Bz7%8n*0n zNi$th_*IHK&`okYpdvaA9j1wA{_Q6M&WTByU^#m|G_MTq@DuLgAf4(&J=NO@eh+;W zZ%_Y;lePChz2_Pbe;E1p($+g6dSVrx-+1Rbb!L=(+cu4B+UxJ8c`a^Tv+tnJupr&X zYI^#mY3CeU#D?sM?Udx5s`45h&y4A#cfkcnVc0LV1rXfzjy;POt(K{q5lC4rNJ@KT z4;+ zmnqyL06Xq9f6+U&C7!98j4x}sh-v4ibj>Y0p+j41b7o(XL&56lO{)q`g;V6BlZ$Qg385&ni*Y!3MU%pbExWn_XdT4z0)u+i z9;cv`f4$79q-@_EyY>FW;q~6CD$MbcD<%jTY-sZ z^`q<)?vR35kJ$&iue;0+m1)gjEFsIucbAfIf3qi-?h5xD??N&0_sBIaLQ{<*59}+~ zhj(E|^ID75CQuHiNbb$R(;O`QC#9JnFXtebwAVZ)otsQz7YyJ41xk!&&* zE+^fLp|=LadrEm}eN)M(u#YD54W9x(-+#Z+0zoWX<5pW>)=!`k`(slTmFYIqGNYvE zf7K;3&H8BP(9o$92lU*a(E+J!S^}nTrfTa?X9@AK2uRKsV$A}|$EP(Cs~s1|zIcdH zofeyU^2nue>EPc^WIbofwPbA*-`m|f~D(1S2UDeZk%Ex zBp%YLWBGltgMYoUvE$cAo`iPs5Bn;5g(lTY=RUh-5KQD~gwaw&z|AFV;?pR$hGVpUnyOaneuUVLz%@Ta_C1e}r4W zEq!7$qrTmC!3G0QmzTKGCADtq>~QTw2955+y=zBg)0zDpAyTwNa@O_2kQDV~<0d~xFWXmy&T2Xz84C2Tyn{)qgY7!OOo8{4F%Ee;Hn6{QkTc?hMOus zB$N}(K(}o3)gQTem@dzlf21$Kd0d9r@OAuN; z3$jHv3{Y|*g;O4{E7aHD3yEcc!XHyz;mQ@9J316uN;+$@o(zj>y^C_rj0@-S7z?c= z3;x#NL({sgvh!6%PbcX42O)~psLVvDoJhOdU`FORnVc07PJC8(S+|(d*-m(oa=*pT z&j|+1TJDESe{nmpC_V02{No&RcE!&zTVxfV?q+@C8bG$H_w8yXQ!aSC7TRc5f?OoN_@jOe+LV%(V4H@kn0+)DH$YGEMoV$(w(()=XJ*)W<_F5MC8&(=o zG2Ap%e}#EJKTjb7L2Ve6F|>w0+~I6}L~;$YzA!lwsOJCXQ_>TX=YusM@0;XP%gXOG zDL9W2s$oLo)m-lf-*}Hr?zU^tFfY4&*&vWlL|`RpWFhB?xz`l5^rA)1;eIVN-|Q8; zk0-cgeP21DA-oYPPqX|H#gvoS_4y z;~kKaWZd+S{P=_H`(z*|I(i6lXA*?-{4HXf0>>RE@#Ktkn2bfR;ZSkR{8IDfDLJ<* ze_X@AIY{SG?YzS@|9fi#_;r$EOm&d8gFaMn!^J~u;$=V0symL@DSNu>8`NJ4VHLc^w}))1x-toaG{I z1}a9iCXeVmLz(;pEX%94row1eEGaiqf0aD!i;n=R@^|T2d2#~l)QRe96pTP4Mf&N%m&1vQi~L4L+^YK_$#O@bn!ZBt%ZX zr&PVB2o;Kw|Fj;dac=-3r&!en6_4$u+&Amr;87W+JTVx_OcG4YcSe=TVP zZB6gTCOhSu#=@>_s$3@f=zGfz7BVq!L=+{P)kHiOQ7@Nc<6%|Z2>hj9iyKl|Klen! zMGh?s?OXY$LC5dei@WD*uL%7-A^brD1q&Z)t;7g773E+0sWx*+ zaMdlcPp{2sTgW^{3KVn!>7?e9e-*v7EWm+65jBlV6IBQueGQ9Hs)?U`92)NQ?s4v0 zghw%#22D@1%Z6-)R1`?e54dWd1cNNb^MyqL3P_I zfxCq1l(pLh3c%)ek5%ItMf43LdfHOn0oH6w^XpZu#iPQ*kX10!a3ybef2U0jwADp~ za`MPt*rM(fE@SFSEHST7X<0Ii-^@Xx8vT>E#Uli8*LwPWnUk?J;;=uI^c%SGk8sir zt$I786f=RI(sPn8DSv2Jz-d~Er|CcI%B12_JA*v8gO2O$F!UU6JYv_%W)d%88NJ4u zDBd67;eTV-wtd**t;E6qf4a*;^Htu(OdzwxQOSEv&HjcRre7EreDVC`iM3`$K}*4b zBx=i*kT=wr{0b}<5+hpjYQ?xK-Trse!?tTNyU$3djcRy5m z_K1vCu|1kxu%h8iCC^h!e+P*c}xY}nf6=wpg0w;gxXlBI8a^rsWah2 zmM_m@YE4x&L%9xFe=ZwTek9JaHcEMo5@7fJXk}XJ?vkhIwyz>aS+Rfeu63=@(XT>v%b0_6g(Ujz2m|uC@xkk$J*U*u^ zLOg$Q9J3f1WQI4tDqfBV|A&yXKYWc&GaSwRN3 z@)O^r`b5i|Ys4E^pErQ$o^ZM`|ks3~=mV%|0YOe2Y2!n(U4>z!J^etgf zZPtW+N(c3i8g6Mu0aCaay_Ey&K=8ibb>C;FbaKJ97M*Q2iaWv6S#~mSJ1h1+;dg4Y zF$(B)fyna40y42YlXqdAis~Nxc_qF`&->+6%l-SFe`go4@3#S6v_9dVyj5@k8tw2S zA8Zjc2DN95iBXC@LgB@{iG`}9$rY1N(HKc>&rg9n1qG2$nnnZlJAXEhR@D?6Jl`VA zFzQ@#Qnaq?Hxb0ijZWWN2@3DQ!)TBJRw+>qyQ~HsZ`IA@Tv}jE2dRtLN4F~94z~%9 z9QbTVfA?ld^@bvsCW@=%wB1OZfMMinbx^ixlzE zG5!6|4eGTIQc0xC7FN|tqbWx_^5*wM^@J*%e`&BgE>RUlS)6V2*Sr&x(w9N|TtcOJ zm)N4OajUF$KJYm(WodrEKP0*;J(kkEjeq)$JN~VqRmOXKHSB?M__GDvp+2QeEYj2L z*YQeyDmzb^t#!zXR6Y+p$qeH24ksg{D-AT&-@H+k&PJC%l{A#C#I1+m#>u08ci{o! zf2=-!J(_o?<;s9GNH=zI@g6e_vf3$S%8@-CEE8B%?x(oR)X}md)Y_4KT3T~w2 zRg5}dd#lLox)728ye|nexmpT(m$xE*qO-~ctLC9{f6qZ6u3|AnDn$s z%9g2}8-ra9E@Iy;R7PU6Ty!oU{KBmr?Zpdnvs@1JecI540!%*_YV7`+K3{U*&s!+i}f5UJ%dD0c~xNLYcp6C?cN3^v_EbgjYXU@FB;>%E` z*s~;}v&^Dr%TD&l)lZ>f7qojkD<_d@{L_lK0pp=A!@C_v^_#*13bOHTYrgo_aOUhUO)hBds`G4|UE-!DE&YXGl5e+uYrWnu4e zxQbeF?1vSFEckuv-s_Kgo@!N-P!b<=EO1KVoi(XS^{i`n5m`uENIjTtppZMn-Pn=y z4HF*ub~}l7-L9P;`%tP14?6Nh?uYbkd2X>Y8kbhQNDi04WK)eadiQ9%NbE~kI`P=) zS;!2rX2H-sRqmKd+(!nbf4kv0-stm>k2+gt?YQjX_GiBKQ1dRZ^H~$;>N=612t~fg zd|Xt^b|qD5auG}`Wmc&zgcr+JMjTN!@yUO5OS{FK=j^G|mKcv$N>XMQj~A2SRHxAP zifyYD!ciY#s9?L+8EsGcm?iK!?}U+4%ko7cad%H)>;l-9N6~2I&j9Lir1FGT{!d#d~ zP_D86Pa# z-X+GLY~H+QH@10>T=R6t8sM7AU9`Gzz!=#w^dvOF2eP(TBBHX^^V1Z~--o@F%^(1J zRONs_8o=Qre}qX@M7$-p*wRXs6Rp3^+(S2Zg%OAPf9e9OUnrV^*Xgz35g1v>cSPv<*a6l# zUGmGZPsxg&noilcKCSPE+I0H7J1zL6%+fK!W*r$WCQ)B_Ai|GXSQeTL+KLv&TT}%| zPwLy#>4eeMV3Is4l795JJ8Qc2*>chC)LuuG1IK(W#W*2Z*g+YKg|EvV(f|0N9I>pe zfBRilX1MEDcRlhDR@TP$Wo+s>%9P&RQ397O?@j^Vx6Fe7Q2ApdDsp-7xf1(35`*-Jd9nbBVVsN~3gD0lBvzsjAH}0LS z8uA2GnMa5U9MVRbm*qtKFp9y`C7N$iK(eM$tSD{%LR|xdWlips=x8`+!im4ocZ&*N z;cQ2Wl?)CN;%R^^R5Tm|Xgv6LDM5H^0{d}+x5Fwb?%Fr2c17QoBs^Ruxi^iZf3PIu z_+gS0jWbiAJw9&4$X%B3ym9y>x%1G+6@3(-!8+Nyk@gcpeY1Why;qw--yMFKl`uWq zMfD3M;1M5HKRJ!o9?Zwdzv>J=f|p`lcGYg<0|=7zDD{%c;Ez>i^#$Sp>#rA_QwtSj zKCqq`AO7+YuQRZOt2u~pf*Bk7e=r*G7>0_XLL5?(E+;l)X6blybXR|Be=8}G2kt@l zmoCY$j@VRbXIe3qnhN7C1#oZJ1Mic3K{RJ!IuqBQ@~-Peb|gp=~_cif7R}=!bBAiWtz94KJct|@w(Pk zZ#wl&RFqK9!g&^8aKg7r)Hz!|s5n0pkxNiFpov4gZYDp)YUkJHi&O^C3?v5_y(p z{D~B1Y#8iOs^KPkfys^Ir1F?g_H7QU7l}%2?Z+2Ys8rP)Ru0O3lYJuLY00GgMz2;E zS|-21xxGm+5Cg5+vx-W{_)sOJnHK@`f8I-Rs`Y7MeTxvI>N`=hUu87OQ{DMVPbTis zLjlB)IR{QXq%6BQ_0vFnTt*z9y`s1$G&GsjR?#nuP7aHN~s5ZT(FD|Ca0;K!PtVW-ppUDWj|Bpul0i2n`#cmr}))%oP$iaOCgOsFNkeT zn+;Kqv`@ zp0kxFgm(;FayCSQyk!V7`9Eeeqw<$4Bmq3Lg694kmt=eaD-ks{Fd#2XWo~D5Xfhx; zH8?qwA-@%WHZnFKK0XR_baG{3Z3=jtjkE<+)ZG>~jv&%fO2^O*Gr-WDQqn0kz|hP9 zGqiMfhjdD*pdcU(0@B@rgtXEP0w4Om_ulv3|9`FTTeH@0&a?Nk_u2cLXCEdy4Q(!I zE4T$z0S-fQfw+Mp09iFPB_RM1$j1!?@?tYF>DVEE9ie}lv6=Lst_V9gOynN~Syw0o zd2f@0An$o01_4!j`AKOO&#ut6Yzm7OILU;(wUgJJ(C`@I=z{TIH!d{;Y9zzg8L_CNsO@87>yCin8P zg2NoW{zLzBzdQ=+a z!tVFuavuc*{*Ui|z$_i^9}vX7F#mEv5ckuD{Bw=JG4y_({<{u&m?hlm_u%n@1pp9N zSBMw({ng(iFu(_NKcQAo&p*6spzNi8&C@L(`0BwN?p5AG^nEq+OZ_9Y`V3X@L#fg_&l5J z!Th95K~Oog`FU%5by>E5DhZXa-p^GnoptaD8B5-(Q+)9E7~{zF=b7{>Vy&0h zNgh=M%U}9?7YMtkJE8-X-GkN-7{ic+@}j*|a{L%odJBb*f8~|B|Hvfru}~zICDB$Z zpwlA5?v*V}`Ls`F{EGp@z&<!%Ngr+#E#O>8T=QB$HT}rToW_Hy>`^>E7p0q$!v>+WdtOJZ zTda1>%8*@Hfq+JT85O3UZ8X)>@8KsEL^P4p-^oRohOQ|$r=vn4!g$T*n3JF*IxIQh+clQ3CpQ*Z^rI6!qGPRb` z-0bv%((u<=!Pezet;y$^gd6~i965xe`;pazMuKnDS0#@T;i(%NJDZQ0UKR(O#k1Luzj}>8lW;7prYuY2{ZL`E zIhKL$th3Q3g{j8l^PreG^V3(z$1lAjvV^(p$ArYb^QXr>&Lns2xtR107^5_O#BW1x0ciKNIv z8>6s-6Gz4ac&U9lGzOPP(xKr-0((IoQ(L%lQKK-Xx>?Q`~lGk{W=a}>;Dn<I(mV4<~wxgP0c-bLie{S>kDzrMQ)YrV~An1E`wJjrQ<_2SCyw0<3 zE+Q7O&o*WX2Hql0Yv+UK*KG{(FLKC5>iw|AjmzZE)=noXExur&<751ot61@WAYZJF z^ExiLVH$l!=VM*r7s%>Cq3f&G6C&^nlURoK6%cj4aQ8>|w`%4>_<&lq3{W1$1BLXB z=d(C7GA16$`svTnmf(kdo=3`8Xk$Z4qdGUDekr2NgvM8itXOJ~ycZm_StA}?Hbf~G zje$&c?bj@}puqyXLDU>oB9aY%$9Pq}e9U)iTnF+k21h(Ens18SJF>j%rBn`EW2_l= znr{3tP8K*23JIcvzQ8gS&AcjOvbKdnBZ6#7xq)*nD@jCxWMUcPA;m*b9490b(86eWSfpFWJlkx*Zi)3}!F;);^pa)#h>gcJTO6 zm=q^WJCePt!y+9kC8Q@|)O430pU`WeTJAB-lN#9VMBVhI;$RZKoVd{?1Rjz1EPcCE zv&8zm+SL@&0y4d+!kr<1oV2Q>G9-J+5}bS)Tq*YJ#E>wLM4mvsSWKFW@!^LAmcGT9 z4gz&!lCsNI870|=YeD|iFFj&}R%&#!Cff6li?yWQOL5EO`IbE_i4iCa4h-V$FVYE7 zFYCUg3?i>T#537Q(tG|zdW~6Wa*$UGbbLLF6Fa{sRo0F%Ad^RbPCxTgHpwg~o75(M z(M>k^i++-U?X&KvH>%vbt4unUu6|UA-WRf&N?LK1CSkg?7B%)Ch z&l0tk+uihLJQh3Fmmi&aHa^PRk4`~P$fh~L^vVx&xU6fvn{@DeHZI6# z7X4#3a_XZgu)rvPC_#IKX)$fSQas)Mktf(d-%u{Qa0`Pj;-j7;6N6vk8X@ca#4^_@Pgr>u0_WGYYCs~4(h;%+h;QjnkfO*b)SA0O`0i_!tv zDf_V>p&%7&uCZJ1NFA$$lnwC{UM9`cVmDTTRfMBM;;Hw4r-&8~kDRhG3@6IJ48ooO z6nf7kxFp%?=zB{a)eGyTe0fAQ!Tvhd!ya#vc);djU_O;REe4*gy57NL=!a^gHgMAc z5Wy?Stxaec#BJ)?Y)1ivjvSn~6vRBq-D;-Oplcm*j0FLG6grSQECxHpxrt4iDyUuZ zYG^Y;<16cb$kXY82-aUHd76B*4n}1-SQ!!DvUUpiKje+tnF*7O&@g)yMIiber6>E- z`Pd^?QKdW`IHgcudbY1E@Z^WgjZO5Y&9JFYi%Exek`o%7=uPRxJQN8Hb2PE<FVL=nw6GJ#z}q*(vy7?3g=^B`9H8&VDTi zl`o-riDmt(I{$&9`(puOWAu>l(Z?OSLO}C<-B}KezF>P&zXC4La0$;EPzF>T4tObC= zF#~abV)mP36>$!siwr|SKR5wOw4G*yiMNv$RRSI8WZg73`ZK6_xvdtVDxaTbuQ^m+ zodlmSgol14!oGfhyj&UF-&i)UnY}ruxgtiy)slxqwS2FwG<40 zK4{%!dW0gdS0e;gNV&fw}nc7yvTs^sG zTZLb9Eb0VS-j)4)J?|skgThaK?j6g2mS>p?De(_e1=ur*G@@~aTS=Coz`15J(3N0) zv|d8=hAyya`a8^}(Tj_EO1aVL)QcuH%_;lG&Ea=FWcJ)~X;;~2QrW4AzM2QOUpSod z6ljH~v(k(*w^Q$z7BE35lqU$*0 zi|s0IKYv>kEiCKC)amy;;B#+(9joRRy*J&J^~%|5$tOaDzg)XgEBSa1fT5)%^^k|K zVy=I}s1PwFi*5Dvl;P8*=R_XGH?`64t;yWMqV>rfepn8;1YT9%>*`&@_`_e_-vhsc ztS^nGxD-asG?rCLBKuTT08&AWx}A>{KPl5K=BlB!pT}>q9-iq8xH2c$G`> zUK&3sqW{~g3C*;t^-(GJ)-TbF&UBM+NwtH7;8)|ROtrj{kR|&GuIUw2KM~uMSDBZf zA>w*|m4PB=xlOl#uane&s~D-MyOwo58?uO?2%$Q>ReZfD zi^z#J)0gsR=-T>NAZVwa*4ox@P&&7qf@Jo=2(YjlFKlWugz0sExIAnK8q8m&GYBS+ ze*xbedRXM~%WMxoUn#Y`Hb!hRhM%v@pC7(6?y4>Seh8NX=rg&Or~Q=q3!w!1*TA(c_Q5tax1u_h^=*N81ZmSJ-d9Iwoz)#!{VZ@ zXc@KwjlQmP4jtZqXkOoHeaL@1GGF(w2QM-p0{K8+uDViBm|)av&Oz`xeB-QqsqKBI z*tmn#YbJz}vAMall0W8q1+LU*KTy9DQ(2h5S@{7A7`qaG0ur^B95Q{?{1j{IoHf$Z z#;t~uuCh<+6FMB6C9<-pl|>>YX0L12`l+`HwJ@mD~8 zE-jA*MqsMQ4bkjQ=hN|9h7s?BjwnttMb#lyOiT}qU*iRtDyGxVN8|1)EDlrImfPaD zG&A6-{ooIOC*O7ba|DAnzTXiHM6i!YE0*zhf?N}v;&?uFFcYsgRnJ|y=<_`>RWpA=t~v9LZeH$Jm!T1WMq z(Eor*WOt2ZJd13$Xmrv5P56|M%Ou{1+3a!yL}4N5>&+Zi$-r-7P4T3U0?byqDK?RV`_RTWn#7gq`QX09|@y>fk(GSi#hLO1S;!GeR?;D!qlCei~x8fLkfg(_0(WuzvcE-yXIeq1lG)YME76_$9$0K&YWB{ea$J zZYQf@@H%3FN5=HBgB2}4CROS&jFBN~9G`UmS;x1P3Q=J(nr>yBwx&gnHP6q=QP z*rUM(`u8C}_FY;oI5H5wBynKHWkfB0F};^^NrV}yF;z!c-bu1^fVbJv*Q-f!FtHBfoEfMQv8M_Rn$CHD|FDFi;XWG)W0WU?9cyb88HAWh_DwE^uC+@f!2GLt@KAiT|V zj!=)OJ4SOil*)fbem7~6=zl#Gq4?r_pK&bHSQXq~nD%7&YW{i(B?8;J1eK?M6JLN( z{p`#uC2=e=Sm*noaK_8nYZLWp^e^Tq_HVc6YCr@W5#gEoPlH*kUO&(LKKGe5rqpq% z8&vU5rf*)3%+zG1sM#Cyh@(T5zZ#StR!F4zN|(q5JBFs>^oe3-vJ4qb^BvwovYs?c z!JhVM=`WWF!c<&)_w|d8V754ak{TlZz3Riq6OTuuo5^vYFQ=&Ny4xrn&D{utd7?K` z(BVyP5@xeCI;d=>+UR3kG@&pL-y2Sx2&3l>@=r%)ADmR3;~3(^YN10vdUsBq9q=_@ zAnK@{14gg98FBY+cteM@o=K8&0}7l&U*|D&a6BjIBu&3sgi2@}6}ggseLYs{W%45X zaVhl>r5wgpSzYq3YgL>7{ak0=q)+|ubZm*?!3#3d&+2=&AtmzVOLj4N+s1_C>_jr2 zk*KoMqpujs2U-2b8N_=!C`Jq=4RV%9IN3;VXu`SD%vmf-etPA9iRR z9x$#MR1fVfJu)PZk-D&jWu%I*AC_*^MoDQ(W~K&z)Q~5W3(!6`u8O`Y-vKPn=C9?I zREJc_){tEthaRihYHB9ujeDw%q`#7LpEcQzY095DyLvbNx^hK-xq|(Z&T1jU0{!v0 z?N`dsnL|5$Gca-gt5gayh{}*oSp~&0;|xPMO86&k^qoCGU{Cr1jv*QZ-Dxx6vp8zP zi1m^FDnl0uar`#2$DY~SF;r>UK#Clh71+Jhuw0koPZ3znezm{Xg32Oc?%K&?Ktr8L z@KKL-7YzZgKnqoW4C&M=K?yx<$DD$))ON03dq;w__T6EuDjp znNtNLFL|E6%O?MjdG-@qKG~DqFpCJ|e7}rwcD=KE@pb!3>_p+~{N3E+J^zZZeNYPc zu9qy^SmNpHi8I@3h7Hh|!eFd%uDSGE2aGS;lJ*VHR?}vGML4u^5`kh5n8wc zFZrfAuEgvHX>&^L7aDVSoEhYQTkPEt*&Y!kipZ=R!ujUQfaRSoY9%SYwe4ykgP&E{ zqv4i`!`rogOks6J+g+Z&zWT1Ks8Hu4W~VXwie=S@%jIB!!xhHs>ei1X;SgZcmGUsHbAd+gMJst09hvH%@qj5;=(h zN)DNcGEh|~G3@jQ?XmlVVt9mA$L~7&50&vBu%cfTf8$Q}LqjU^en0-T!L7!Q{;}hN z%_ucrugJEBk0Mh^UR#h``4vv)3?TW+>EtXN46xM&=cd0m}md8m~3a!rTCJ0de5*Zn1z%JIX`?gZ@V zThf6oeZ5+y`uypfl?Jk%8eW+BO~xle4eug<%L;kS;Kn^y<)-NZ?Ztt-i|#n?1D`!} zchZQivUnQF;i$l_6>*(YWqkH;3&*cnhzyBJfkvNr8n!ZeSqX>MHGlGX>mNn>)Almw zM4;kiS`xBWe=&%7Kpi5NAB&eKq2+JS;8ro_GpSmROD6~rJjc2i=?}yMI5tyCXG?5< z6QaBo@SZmM{0dCR$xR?6l=?<1i#x&t$<=t#hmmI)AFJ>GdXhifW(;6(6B>8md0@*y z#C`=37b+{;Z`TdkJp2wf2T`mc;M1*>N~R(%vCof7lrvKR6?ak zZ!(!3C$i+3-_ce=Pxp^zxS!;StAFZ5c(WNwuzgNzhJ z_2*PmQwnuXhi^i*&veakz-nb46Tan?GWOqD)hK7O^`sIhCS_|vt9%;8kX-E!=B~IP zA~h6<_MBI^>0~{#%9}o4_Enq~`E$h=f2zted0=x@1$o0FyX>c04Ije{Z5y5goYpQ9 zy*GoR4Y@oZFPv?bel)XxHA%?D5MZ`L?Gla4;iHhtJ_5wcRCO{nrDIpeuVIUkNhU}Y zeM)GxA+c_hNG(xs91#m4x?ml>l!zX1^Mm0|I4O9pzv_P+ z#kAjBL$Li5HR3%n0RN?PHPsCc#l&Vl>7t@Yns{BO!$4VqPE4djkWAc-(7&=LPB~?lo3bEUBc%aBX5QN^QUnf^9SQ=b@QH8& z@y=#b&T4w{+LS5y2xU>kdGOqrUy>L+oLmzS5Y*$hh(|?hCo*}UO?G%@jq=DV&s%qZ z8|C`p;?qdobmZgsb@&v8JgG%UO=7?}Pfruaxgkf1J)3J0H=^%`B8+ zx{ZpHwHMXreBQz`D4o}ddpS;0e2QbOVbW|KuwrP;*6GxhU6jdVr7J<2v-S-`+DcNJ zj5?;b+@kNHL|7`E_Vc5$O04~y2$?dpLL zt);GL_yfP!^?}|Ef9IU?&$7PXA}**%y}na0r?Y?###DUfc9tl(*XapyLl_PvZ>b^` zb(dh9+TWrV{3_?>=B}SUsaqo7nESafot{mm@R6?GCAhvbeCZZS`r+nd4LEWA#S%)i zKpS1$!?v$sUi3DQVAgF+d?C$o<8JAnTQ!H` zHVgF#Ig|tIKyatjGjLScWS;7i$sLMajY%$abYU*heXh$klJ1QqEWtv3SLLpy!ArV2MKe*n8D0R|tv4-G}Dh&?$HQ+fl?n4p%_=9AMkRJJA?74si{bSly4hxI_Lvm>&mKkR(9QE1nV-A4}d=Te_t zIVakZaFykDDFu4i${^ zLE(a)B=I#x4%u5+Db{SxZdC6ZA57L{jui9Kr+%*SjEEbit%0~}3@1c1Gnu`|mEq^? z{}>_We}+Rm>Y92I#O98D&i~R74@G-FictGHIVt1W7Sj{VO~}DFewkWbKX*y#G5dv2 zN^I%|A`-3eE^DC1Og+KpTarfhbj!WBzn;#pCkM~0qb)Wj4Y#9uV2f>D{ruWT#5UK6 zZG-5Q-m@8m(EfN8l|I3CfmY|=yXqDbgPQ+Nf5fsN9m+OkjngT_Ni?AOP%^5iE3a+6miYsmLm@|b1LiF&=M3mveBD@*L zFjnA2PFVRvpayB!b5CX)=fn!_HOVb&tfPzfOF`{k!>tRtCEXADX||K;1y$fN=qy-z zWLL-=yjH0%B52~6bX!a#Xo$Tcg+YoSf62>-XtDc^LT{1SbX%T-W@N`{3ZtjiqHQ69 z8yjTp&paF{=<}qSi87*1aXZq}Uj-aL>*qNzn&I;_(|U!uYA0on-|#xbGGzHc>Lr-5 zOUUFY<0kge?TpHu_ucv8)%zV><8Im;r%wq9Rl*iDEQPK82`L+k@AjxpM<4P!*oVN9aeWzmi>@y-QTaJL#^3hwNQ=2l)KnYw z&Al#=bcnmKH0L~XZd>aOXE}>LPA*7t+>8)c^&g_X+sjdY)+;ujs2R%>3bl;&H0}OB z67rfB3T19&b98cLVQmU!myenOFcLB~F)|=8Ol59obZ9alGBGhZm+=h(6@M}^HZ(FI zK0XR_baG{3Z3=jtjJE|)oY~ec3_*hg*C35saCdiicN%vZcP9`?fMCHbSa5gO;O_2j z!R7YMoNtoz{eRWH)m8NSEMIFsYrhQziIOV4u$hAiP{P3;M9<8?!~+nOS7BxXFfp+* zFfp+pP*A8@foy^Q5hGA&0DqlbtQ_ol{xA@A1{#CFGBINi*iPQT9w6gt3t(miFmv!Q zbMi1T0a%!rxc|q{!I=jjX6$BV29Rd}$T-*oT@WZl9UMKKtt>1-;57g92%t8l0WfoO zbAI^S9UyE6bha`zwg<=?gDin|;Eblmwg6QJQ!60I^S?q+^I3vGj(kFnf81|I#u z4t9>l_MTSu765ZATYn%xQ9_OZ}G6bYit5G_`7mrfP}Cz zz!==%f7){~b+&Q@xiGj`+5Xic<6mLGQx>;36Lqk&1KNXJ5dNx9%*q*P3Ld*B<3A^B zWAET@@BJTOZe?#~{#O%bu8xfA_Et`=Kxwi6n1DqHzhxFc5PyK3iHV7mn-u_b0suWs zEgAm`ujc6p{9DQVml)iEueYOvBfuQo1kl&Y90>kG@OCkF0|G$Ku0UV!KNbIt5SW<( zW>%&kfCYW&GhQZEx-X;Qpst z@RVgfcihnK?C^jSPBkc)&c?4ze%pg#Li?2{=@wLO!dEA{{I;MSCs!7$^Umj z60Wwkf2*ng*8hLh#&%Y=p8qiblhzdkUI2Lq@EX|vZ+}xw;6F<%4>YrKwfo;%X^=5^ z5rpk6Z2ujjm5YRx2hdE(3S?^e4_p3`tN*oSwpR8)B?lL)zpfPkJ@{z;mkzvIrZ(WK z!v##qzg0l+=KOa`aeGq-v%gl1g`ERn?Cfmpi2y!iFk%OIGlO^04CwJUi2;lZ_6{Jh z3jo}nFMq(?!5QJN6XjqBFbe-A`Ui0U7)5>~P5`6mZ^Q*=*uRJw41l&EUv_0E{xf5x5+=-w0fe{BHy0K<7q}d?-+u^Pfabr58;pKia)Zk;`HjFSO`MHQ zZGhl+iaF@Fob_M%KYQ`70$ji8zla?i%+$da%!&Vzu(ACmvHPR6zsSO9_6G!~1pbZy zZUy*X8JJnXxxw@?cCq~3?_WMnuHdEn9R@re^WP9`VEzaEOKJ5x3F}|b?RQq@zXZR7 zu^azo?%?YDM|7}(#UBvd)$eN9z*MyKbhHH8|Cbdh0Uv*62fNyXH|!5RxL1eY#ekh1 z{!0yR#__ir9Ly2?;XaCZhy>=9c=CbevkZ{7TmRq?Vl82W(F7cI|2BD zW&~L}1OI4yTcz2;25rdK=9Dr{(#`Z-TxpA*xTa|2oCT02L#X5>u>m9cbciI zGkAuezu!7w#{Lif`!@s-=m9iESeSJ%Ywxi3#KWuP10v@Nnt_sgz&WJ=N>52ziy_`Gsj+uWn$?Ne2=49^SyP}Sz_*I zyjFjHsIj^cLAql);(vF3exi8#df$h!9bZ{gk7?*ks)$wIY#4$QVXmpxe zClM@iPgcJIrjfNRj{+Jxy&r3wRtAUq=x=|+lA7)Y>xZ^FeKiXNdj$zB+?i>`Ep;Q8 zmv~YMlVFNLBX2r1fzp_$9~RvbxSn8)L;1XeE<_&inK$#8m~^;cx*>-NPT8}3E@FI3 zYtI$h)~C_tY~9iIgI|L=6kbi*lg`ic@GM!yjncxXvs1-8KW49frc&mu0@h9k7c+mJ zua{yoh!uGf%f)T7&tLSD=d(#mcJIuU4Myq(d0O9d=Q5mXl&Uv>Vb4`2**=bQ9j`=8+An>h8idiv*Ra(|y3Tw7e1`R=SGv#x@#hBqG8et7Rm@*}p(Xr!9omrOYhr>C>W6Q~ zcb_;CGABJGvz6`pOWuEr#M`zirmNr4efd>-=Bu$lX<9C5WML= zS`<9Q7T*jN=0Mfw#0wP+C02j&Y?2Uqo=P+-wDp&9;de49KcBWbXnDSx6|z=(5CC6WTTy?JDmaK|BzVP{ zc!Z5;IGhEeo6vT}<)OsK#ymrK#Sa?0lY&@8LFVO1X>9OymUU%5V14|iE(!r-^$oj5 z3RGG(G39&XiAyy5;%7=kp||FA7NFPEw9BT*=0>8MYIrN%lv8n5UH*jCw`&@O&$LEZ zaw#u!FQ2K+^kew5n>T;Q8t&Iwy}NF}8|O@?!EdCjc>K3eU(?klwPhKWWpNJ&X*xgP zNDj$*8%K!hh)8C%A`lUJE>XXWl%)#mW>I9C(nu=fkX9lmw|zW#_|ZTgkF&1ZfqOI! z92tzd>&J)3lO3L;WTCM5YEteMek(JKm-4~Y!B74NOAoHss%w8-N>=zZ2kp0J+V9A{ zUC1R9uiWjUg=>O6xw2oeO=)m{j@@qPom*srN+|`4wqnM5t{?4T)sEa-<9A!gv&p4`Mi&)tX2*o`HCa4}_qm)%j?GK>nDQ$nB7{qelSlwXJcPQ>&1C$v)3rbu5L~-5E7O^{(fW_gdWqt=gpJ)bO zG~mf`8`QD53Lum~E)2nyvu9Vmbf+w$Kbop2&ye)GE95@J zt|vQwEuPW*S9iK?D}|CcOEwRYhA@q)h#ccCUorM6J4Uf+hH&oMZMrRQnfK2QL~638 zc`X=w3D`JN_$Y{Eh!8Gsm3fCaw9Xzi9O`XD&GR=V!Y}@^J`VDTh8VL`Nt$SDF9flz z$e!Es`>%f-0VP?L2CcWopbTPoAw}k+Y{qm5i3{Sdb*!F5WGP#wDDv`io2$9ta}9D z(1$q3mqq+wXMfB1hlY4p?29iUpN!~iz4761fy%eDUkruJaX47;-6p*7)JL!k zD>6qg`*cc}iD-+r`=imzKg-kgn>Yr9@p`Wm55Em8Rc6KB*U;dd&u$rsn0kkdUZ%*P zn6ZCu^`V7}t7Mia__#YP)FP8#kAGc=RAT)>R^m=A+vG7hwoM~2#+KUFqO3E0(PXkT zdWEE6zj!8b=BM7q^Sv>fGBZxaupgj=d(%lHzoB3_9}wqaU~`h=ViuEX|IRD66CSQK zcQ21;mOw7U3r{}=?Y!6-F)}}=IM_`=tSx^^UXqiWTw2cRg)&}v-s1g+y)B0)WVp=R z&k~BYmwd8scaD@s@)To)g>i@6!s7i`Cv9^m_iFF7cjjuS7Dgd77sq#kDLZnQ0%ZX& zcv#;Ut=?KKOuD``$-wUtMd0f1@e-EGpUGr}MDS#|)Xnl}+*|=M3%iyUrz1HEk1>Df zvgNAIvzWMlr85P9ita zaFYrg-7Y(k(+R_3Q*P#a3mKe6xIdC(**9p5mWnbz^ni-Zgvf3Sxgf@E6vC&YWGf)E zrg(EZ4yWU710^1)VG-v)DO^Qv_{(!$=CNiJ7IsT7b66t z7|NyNJ2zjg`}lXB(Th{3OV$_ZWX zC1{J6t<2D^a_)bZ%giYO>m8f9QvOVkB3ds}H|qoTr`*+1Ts-6oKxx zc_z2E+_am+7Jtp0OzwY=;cO@Tdg_vZ+0}P-X|J;eMVr#hUvxX<^6T6o71Kn>JJxd+ z5uQX;lsL*8#}uAH(_g3V_>5?m3CA9B-NZ4}!bK_BjGTT#@1}foI+aq6&#@gEy#d7* z1Iee+FSUki|AAq!C$Wyse6-)ov(PP=c*C$t#H(y5JTvT?MbLk3x&2r4}QeIB~DCt zBVoGVuaA`Y8icg6_HbGxzGkc&5oCU+Uzs*OR)Dss)f zaP_o%w;`oRI#qw73wy_$IGS=|%C2z7UF;~p!YR`%@_be6!U%O5S!Y3gUF3nK{NWu) zK(}m@Yb0LMrMDrFhggN2Tb~1yGUCC`vy8^77BA9m@W8t3Mzb(Vu17`0fKWxm*tY%1 zquMZQPCK2aie0{-9C~f{bP4k;5)LD#xfG@Ly?@~&qji5?=z8x$Hi_@5(bv->F-lE> zfPv!eS!Jz8a#*Rgf<2UBkaS*Y%Ul0}8HNRIf(xN}d#n=YL{!7;WBcX6E_mcN#iuQh zumTLd9I}04RFWW!;VQO)Vd#|S&{J7a}HonUFR}!d29oM zz}J1-c4dFZ*f9K(9RDerjzBs+NpWk*31lh`oGRJH60N6+HlMtL@=X#tb z^8*F9qsG0MMOEoK2y&H}yZwlOgKtz>Mi5y`WDH^hp1tntLRd_7zy!(9MD2v*Lx_8l zX-H}KY3-fDsZ2asiha|3@$!aaqQ_Kzk%eJt{r3T?u*|mrva6{kG|P9xy2@d4mc`oi zJ3)Vbs?IN-#_RxjC2h%~nQ>ksZs=$NedwYI9Bl~fs8AvHfVh>l32J+l@ZEf*|jtRRo&M1)<2E`i1I+4A!2F`J~aMcW=;%EWRqzP-h76_>y-H0BfA z5?-lB_5JmNIa|`E5JIX_l!<(=FfDPX&_I7Tdk8L!z;uZq0=+Gb%3{{uE8|jO5>L;T zEuM=hI?N1Hl3b5-n8YBHG5MF-j~k5UzN~ABsYgG*_ivF(7A2yU?opY`yG+1M6KiRz zKl?u2)Ydm>_tZukAO=j&QCN@klSs9lMJYq7t=CTu?WS0Mswr#+TPYnMyx)zZ`=sWjGCyVZL^;J*DFbOYM!!xO(}H^ z9eaPxffX-LKI0#CG~PEr44k(-QnY`8GD@#MP2F<5dq67Xa`jv$cfL$qxk_+FF!wce z>ZW7w^z~tnv$Z9Sew5E+_<@zI_Yh}CpvUTF@coJRP8TEir?AHy?=jcTc-I0@qh~)jeEp**Lrqv>r9tB4d9o@@;pE!T37G zVBO6(9#QX|`h#;lp{1!4Ut6qE+2sm~r8`V(eSIv6I>=+a#5OV1$GX0_H)}`JwLbsQ z;Tb*K>lw@IO=E7qthM!D0Cv3Zhct4%6MBR11O4Ne7;APpV!!5FpTQ!>`%}gY&xuDP z_iG<%~mc(0#3kD)t729&;mi ze0%*pPtNtgcI?AlVv?EcY2SIjE4LNYDe}6CN*F?q5@^`tIw5wXmz$s*$bE!5 zlQj|m7}XR~bQvY)oUXJFx)cjGx&3VJGthhbNE?SW`>Z^)QK)}lVjfDj)Y7&ZlHox5 zHhQ5z{cVfa#FfRN#fb5C%oo=hiL8kfzHSVy2hWv;;veI09%x(M3|QQ}vI%Oj=y!c# zE0p>+l9M`j`OTnn+({1TP?eUfesbl9bekU+H_j<=Ow*Tll_F*TCF4y~VW}`D>4CRc zm_k@#BI-)B%RW4U&%W zZc%DBS0!Iwm`Kv87TKFAve8(z ztonBnw-0}Md-%_{2Gj9Sg!oX1yeV%xd=6CrVtPG6$WpG;9Iwi~&*RBd>B_7FCcGYG z4Kc*5SH!BrJjK=~XeUb)4Ir6VI7We?Y{l2pG(u;M)xa)15B-Wp*cJhr&9ltTTKxdq z^m{0Fhc;B*z3g!bUepf?l!a6nRz;C|l?uw8(wBcy(<9g8#2tcaJSRf)5@$Gj3a^N8 zs#={ZOqF~;Xqqk8HD_T1TiMJTCB*72KQA%NSF63DF;In>peG8oclUk%fEb~p&>)UA zE(&>Fev7D$7_9;Wto7=ezBy-Ynbbq5n+Kh|yl8K*8-2!+@H0&H=!_1AQqS;-qSA`1 z?GJwskrYBvpGD=6M${ut3E5k|5qRPm)G&N}Gbk|gotsvg$rpR7R*%$s9t-}ARejN` z?_$t(TO!RIYIq?p^q10F;Si1Zmk2JDpeObGv&{D)@1pO<;z$R zmT*q}i1}$PE)K}_jY4qF1=iQLW6vBd*o(nR52p+ zc>>IfXY5)Ex`bKJKF^-3BC_=G;s!k3qxiu7 z1hrW+PxPeWCjVwH7Fl)c~$%eZxYkR|qke0y0FI+mcZ`sGU+Lh@6pa!8Ht@+yCy zdZ!i-0d&yflAtNw4aIup+Y^Q6Wf4_&?y$Sy&T7c$;tbO6*`Bm&i+#0&mX&P-lOoMt zc-STCDq3>DCwJH%cl$J0k)PtXLJcq#NSsT%wY~EB^1~=`oRfHk&7?)&8!<)%`XbO< z10XrP^nTi2q6|MrrpdD5(~bnn(&K;4t!U<}?kGi#lnED0QU&*5_bfl)RF6*%i=VN~ zk4q_WcH)#1ooH`s4$@ai45Ew6$Ij`08xZ-pnMsZgp?|?b!Kd7~yXm(JWofWMv~@6i zT;ZSFPqx_aZT8*KeIkSq!s@~5kk|p9+c|zj-P_*lr!R-9{uRHH;noRu;KzSjH9(89 znxk^Qf{JcI?e7TD9#&GOf--Jt&lV+(Sp@+y=~@jcW>D% zHtz{3S}(<_Y`?jKFdVS`VfcTYr7pH8CGy+4-b@IqOrMvRE8sy5Xf60785?~RSy{ve zQF+8>@vKO+;c1#ob9|uaK4Ib~asnyqvz+tO+L_^r8m+#dd!wv_ZP2mrxhA zMdS(bN;G8FCWpl{h^c%*+B(xu{xg7#Q|By%Svg6dsCEC*KUk7!BSWGOAK}-{Y}GN& zO}?@ANpg)+fc+pUf^bCr+@=B@?gO%pcX0zfOVZ%zGT`2v(#9AB`EJX~4vmJGK@gTb zvuX`t(T|?kHc4fV-Tr^@bHh5v_O8=)Jyfz8a0P?+nH^_T7ABikZ zv@46l&hlG?A)T+kg1g8w-yO3}RWomqG~d_xbxpIgy@tNm@&p5i`iJpuiKn`sVwt$k z*hiR(S-vk0VpO1|c9KNqEBO#QBkP(E~H7a8Zwn9>O2b`&uq z21}H={+=RG;=Lhex!b!A5i+ch0F8()mdWAqj2L!}SZK#DYNL?!#n^b24G9k)VTl8O zQYoAkQ?Gv~YfmtCX!`~Axw8zJc5L)z3m5xtQrIH!V|@q`9D9d)*HVO{yW~&He(39q z?WyT{|H`oU=zIUJ$+E{w5|1bWalV4<8q%p}szP5QN=9qkq&}>L&s@2tU-smMo)|6} zzItDBwoW7gxt-=Q%;%ug9yZmJ2WoDWwi&sY-1L9gKb~iS-Yei`qnv+GYv6`(Vs25* zLS=q~iGH~um$`;}#;7v=C&F2&bnv($FuqS9ZEZE=BUo@2`aU9en(i@rrM4=|pP*p& zj%0sSHn~2^i0Z-w`D`&DdkLuB2EPc%vX2io&hpfst`yRpRB@yC=uuMz-#EhZ#a`Ul z?Yck@U=jU{DkjI9u6tPUqGUwr0M6Jq1_S)T|NV`i(esQLES@kW=w`srw?fzD3T}UN zQoYmUYN%O6H<5Mw6*fa>{#{YU5l&)M1>}ELwpjaOcY?#vJk%G2`<78GpntSvFqUUk zav3uA;~S^|6dE#)bjNh##u$$4=o1`tjGKBborH}Fk#8vJBRbOr0UE;~h*zIM4#7x{nC`0UZuL@+qs|#p zPg=8Y-H1MJP&i+dh>rm^I)|+ZB94EJ18>u4KBY$;;EMV@Os`_hHjp(_*1DN`>3y=Z zjvRS|g#P?t#hg#4a6f&a$T(;hvCkR)1p~$v=>mxY)iOGr=Ro=-ZBfcOgG_YYR zApN*9U1#6|4G~N60_~Xhh!*_paR$rDxhL6TRVZfNR)1osRj<*b%V$IAUba?eTy(FEp zzYSx>B8bf9s?9jA_o;3B^bLf|m1eUjA;$Yn`EYU}Z?LZhRV5Y#c^F_?tS4ga0}+Ey ztlnvhQCOYczfMAa-+Nm0%j#k$foPG_|4K?M4RT*ual)8;#oHr7w*Y_pUD%^I-*bZB z#8Vy=^rLGTB@-)>;-Rvk`Mkz3M+<3k22EQ&M>BEQyTfpE`FZPR_mQp$ z-jzYu=20e=_`U#dOBfXyyK*+ArJtxiDC9U|^@I@5Cl@Gg)e^&RP?y&YI1+}hjN&HK z@p^`)@bSGm2d|Ypf4YB_^q}$2HL=l$f7d-cU}Tp`r&ZaawV@J+qngD!sn}nSEuoK? zyZq{8ece=Du^kxfU~K{~)L=?@))=nCNP_QC7=W-FtD=x3Wc-Px_W}K^a&u8K@(PI; z0f#Ycnr}>Ka+&%hXHgby8hK!bkz)Ny2}K;cF+Os`S1lj_=pv zvu%o3`^b@Nde7axOjd~@Xq%2mue93c$&a+GSnbp>>GxKh3V0i1f%N@n-%=2reQX^8 zULx}NsEkzh+fI5tGGV;zygJ(|omydN|JAR-l2U92Nw<9rZ#j4w zp3G+VgMQM;I#+)@_5;4j`Ej$VxSx@JW$_GK(+oNJ)Ew~{381upSG^e^!}H8_hIU~9 zhaXz>A!?K@E|TUW{$a%;h(yW?0au#OjuOOxy*&4+x#AJY0me`Z(uqakJIpO^eR%Gt zNyRllNZL!b=k5=NA9R9k+SpS+9V1IxNY@fnKf_43321+KlNvZDn{wBFpiM*#4w_zd zJXvxq+IZ5f>8ohCjfOYgWNX@ow|tv8z}w;u)bF30z(}@Z5i|;t$GA;Y5w?-m;`4E! z;=7J9?o5y11GG!+KGz2)XfJ$n=61dAt9>UrF4IftdE(Q&XY{;Pg9)iJ7iao{Y?#4p zE68voU+;grR`+?8Z-4S?$W%F`G;f%*4dIg)kjGxq*^I7B)Uy$~j{ieWT5|~uso0NH z*?M)pFEzK1U(=PgjWM?QF1WG>k~M|8X={*`sQmY(z|NQZ!`1SJ<^~K0?Z;-%JoAu<2LC7yQ)i7C;O-D z$3ofb7kpAdgy7~*PfjSo19H+FaTj)pkm)Ms?EjF`%q zm7VkqexV2ywR&;t{-$dSfp4tBvr`_u5)}vIAS;S*P@`Yuz^v6v{QcnDXvz|%xXPy{ zEL-qTXCja4H5AXWcx3hpW!v;`J4mZQc6k+n{Eo~Gmmv|)19Gu4wVA$GYQ=dXHFowWuYyl$R<3x9{Zr^y=QK07~JYr5T^+b>Lwl$!J{aNxVeq zuA-8Xk196aZwcR9ZJ{lnz_~|n-q2{FsQP_L2YkCPKm(!b5=xZmgi0KTeo;oT=pgJ2 z3NFzf+6l7At}}xCaxgB1)dj(sp;~{Lla59-%OZ`x16qE(7kimUb{8eJfohpxch(QM zmgVEvkKzX6x|nQ$W){nLZt%=+kdY(i8*Yg#B0bI#4)ShTgn zDEKa;B~($#+*0s z+BgG@)}wZw*`=L7iwIK=$#d|9bJi0|=6whHSPY?!tPpqIi|y*yDG-%2I;GZJ;4&UH zB3m&s+qj3{LE`LNi3A?a?Rh#2t}vfZ>Z8EJR2)K|pk7UjX!2;7efob=bMuK=iG{?w z-QuZ z;PSJGwDq-D`-3DX73Q>eNhp|OMr+l1eGI3b%DAf_9KUPBu~%~lH>uAF?<*9WC5LAP zP*0iWT;W$kW!zfIZn1x^;BD{ZqvyWl-r9!ebmDsBN9ou?b$`b2uUq z5C??OtA5rx;vf@|g2WEyQKO1&$JeA-HA#}0a6A``2&yz9pwB679A0KMBgVFWAK}|; z8D>F|_=w4JkMQTsqzOh>#rmxAlqMqWCwL<9xAbYPgcHd0MtpxiH>76`)CIA611^FCW%?MY7{>e>Shg&ukg?;iyDcY-9-aEA=2Wf&KLFk+ui$_cpB zOF!8VQ^r?uc;$Z+s}E>x@0`=Y2Tt(5jh|S_n*0*4*o^gyPq#(HP4a2WFmf1$u1~V{ z1$Kr5)ko9A5I*~n2C6*crCq_up+%U&5VMzl;P!~fnco9&HL)a(!8&J$3iH{G-n=d(I`InRuEai$5VfNX2h(8Yl|1jseH>{WSM~l zESLOlQ{E!Gc0rN+-D|P;g`IN{L@oIr1hHLRlMRl&P_I6I4Kq;RKE)1ds_N)9DbicRHEwV;m%X&{sMSvfN2yW zaW|S}r3QcJ6)Sg%q$_XvP|e8Cy8KZ{FBoU?qSagu1KwmP9DboqB>K`ZS$9(J`oWSl z4Y?m>)`Ik92Rcy@a6jJ&9o*D|50OYJUZnwRv=6FPnOcuxxv;nDcTIJ|$XtMH8-&TiU6RZy7X$_+?BtDOrw zXHFKPW_ZqKx}53(vo!qekPRyPh`&Muso9)33iHuqpx^rG+Wh->HpN5sUt~627d5SN z)RQT`$;u84btanKr;ijVJEwu@4B{SBLq1dJC8oVyT-llnAClk{C)_f>BSL^H<+kvH zhFpIvd1u7Nt0fjm>cB4TiM#5ZOV%s6)1+`SHi=GYza8}TyGsq zGCD;XY0>DF^FD-ub)4PH(E1V5YY@ycL}?9|8Gpk!S#2u0q(UzC3( zw3bC((kzSgo?OU%cWltl>oAFrPZ!GqoiAniuC8JttF6N9$9(U1x4?tA`trr65H0lT zyz}sx-TUS{@hKvu$x>W#xR1E)f${mxmaEn2%QB~D^y#oLBqDt3AW{x=Oi>jV!o!L1Ca;a)XS-nG&&XM2G+3Jt{(9JFM z=atz-0KH7D$huOrV>;5G7tzPn?(2LQ!iA#<)xOM+T^x$l7OIq4;abu}J$iqEsQ5U} zWte6@XftJ+kb~;~$ny0~1?;H+-|UF9%D3#(lSE~#Z_h~UWno2mDrHw>ZVHXt`d;Pr z!YM4IHbT8ZX@?#GT;e3Hi4josQN`i(E9f$LPQh%&bqFIxPIrk+y~B7BO~_F-Q9}6e zMobER2h@gd&dOd83P$l4bLM|kmO3XAdba~3Bhwm=;2`<(UBXms(`bXpS9(^)j^L~U z4V1$#VoB|@8hgir&uJ+NRP{TUt|j?vnJhE19#%vl=$eLV>~#^G-t`|b9%>iP>(86V za{<`7a}z&eTjv=gB%`uK(0_VU(!@ZWGpttAkxscV67)Hy9T81_TUmcv<=E@T#r#+a z|AY)LmLQC|poz#5DQhiaa;;IU40Oiq?VJYE{ifjiw;o-J79G>E+(h07Gb?X8s zts1?~fgf2KdNPT%f6aSc{hZ5JGyC=C+`7$no7byQ)jWVh0lSp$7IjBZl%zvu-~PTB z!Q1meY;pb(!M-WT@=kyE{D7%OE6=^a3U(r<3)%MSl)3W}qe#FPp?3hC=qJs0@e17D z3newwm8e!O?ueJlO^#Rg1dF#ELm}Q1ME+9?Oga}GcovctAq$Ne{k!UB~pF?D}JX>*k)hE%;Z%3B1D zxX@j*oLSeW?CYho6)P{@RJ^{AIgtTl!5=@gO(|=9KNg6vv(YMbcyDl$#M8m##2$c& z0JW5&8xOuciD2Zk=J9O2xc$9(Va8to!}~ z5-3Qd!9Ve{>oR`@61Q66sZ}ckJVDT;@yEm*=tBc$QS$Y2(L8J?S*rIEKQ0U%P6#vh z(CZ1-R}#==Re9{76N((A)xvY1lbT-Z)RT0fzxg1& z<2#YZx2NxUxzUD>WORIs*|m}TJZkhelk1CXmEdm)w**b zw^pAET)cE#N=50ZD8X_45d2AHu#@#TC2=pm1ag{6;FY*26RA?M`BN3-mh7*m(g@J1 zDd@QU$;o+`(LBh_G~Mjwx$$b(Z#YAGuV1W{o|}JV494(P)M-&h?=#>=9b?uhW^+&B z{GzjRmy(-|K+Zs$`8tTx>+K$5V4jL^jaylBaQvt1;V4=`Ha+5yUU&)BA(KHu1RX=9 z3u-gkf})rM0fx1}l&vAyo~~~2$zZyn^u;T zJl%ioW1~)7Wt9LZbz~-ryQs6e+lx}?7i_&AtPKS==rMY@lB~T{oc_Ll(g>$%?hM}M z^|;>~321gCaU?O0%?^JUdLBRiMzJ!@^}D^omG5`Cu#3ni=wA%%n}M>EX= zKl;$r7PQ3@BKDm?3JriXObTI{?<7pbqr8h2oS>!I zOacRs?Tk@>na#T&&=W`rcnwk4oN|9Ch4@{>9R<-vRz~S6)PA!c!VTiA&C#weCA-ch4=eYG{mA3 z^A1c!`h078`xAC5rTb*{`&;w9@$ExbjiMB@kvGO3h>#8BLIY}19qA*po~wV=!Yvv} zfawpA7jpwDd3EDV#GPbp3!_%Ag19k@aNG5Bs;{gj<+cz#a%VN)I8-*8yaOpS07EW3 zHHX(vW>{q-&s)#w=uM1oG~OGoh@(N0l|0=KDH(Dj(uoO4uOw&emCnBSE>@-C?dB%UF+GQG(WGrBQT>mu|R8FM=2TEHjqK7Q$xK3`#1EcjvKE|pw<7Mi(+UBw4B820za+D@jNv=n zrwf}5WlRtOh%8@uaH6iV3)2OyFyj3POT~?xufhu&oAipGkcx|c{6cTXSb4INOs)!R ziH~Ku6p9|m-F*ALVHA2F=`a%p$+NiGo*{G^mKu$pvw!pvmxRjwU=f*-XD4y}8gnLX zVONW<>f;Wh*#cu>H02=OIh5Kw3>WXJT~!8&GJo+_AaI&SVgD-~VPiH>(H5fv;oycW zuo(68niuS($#@Tcq>4?!2Wh}I2}#^`rgz%1E-AabI|_BXZR0}2J^xGg5?(u0xU8ZC z*~) zzxLSf3iCZVX>O%InAKF-K$V*v{4CY(N7BUL-v?*~EDgSYwUR3QvM8s^JvXYCSFmux z(Yw(0qb-|{i;nK z6)W2G9pH9xWq!@~2X*@hi%)B$Zhi_XHQ&Y%n)1H(X}epze~vZ6M5*=4i@S7#D6Vy4pG}*#zYU{*@TSD6V%((Ls|ao(hmb!A<=tqe9cLqg)i zm@!3Mk&nak67A2I$j{MiH0Yxudk&ip@t4S?#$q}H0r_@WuL>1D5v0gTl^G0eZ?F;r zuGg)9TJa8T)1c9j(qPJHsU0JGNNDP9+o&GJyc5(bl&pSeFhNqRw48$YYYUL^>7;?$ znuWWcZgeRvvu+eIr7@;*AN8F-oSJHf;2QnRIqFcYU*=mX;wlayGsFEZJu_@svbdm! zZm5w9b$9fPiLPY!ZSl%G0fLs?>4vKpF7CX4<72nX2Mj@{c1LgVoG8a!s#j9^va4Sy z30Sowh!S^*L=C}Gj8BwCA2R`#5lfK=~Y=<`VOyC-XUf zz}sqnlY`N4e%iU<7fP5f5tKb|G@}X|@j-#4Nl=s`OAibdN`9H3FvKLxe?Bq7MczVa z`(Dh{l(AZnK7CSt@PCf^duD5uB~k*yoWWC9A76X zvL6_kf*pAp(i$%1=a3WB5oA=z2lu?o^aAnn7?L5R-ettR0vRGzt z>JmD}X5TO&>zU&VW27X-fHG~dEgvkjy;|{^on6p`e6bQvUDSC=6VPB<$?%v(qieu! za%g#L&aD1LV6}S}`U^({m8V6h?7{E}Zv$thLP&-0?P+T}QKlH8c|8KcY0^l49U_k- z#wDHqNdtBJH(~z`XtWAFt~i=kc;HcY@L-d?fUv z^aAm-Ih<(wDkh^{Gh2)JOBEmX`ROB5K zc|@n-wM5->vGMZ`%-KgE>NU@-Osuh!xD(~uL8$mFQE&A)L_V)egV#ZV`ccK8Ja28| z^r5exaoI3n&2;zpyLbHIe&`)~HxU_Y9{G;)FKkg6dq~Zay`ej;d&k^=q0#9neT75G zGIzx)&-5xN2ayB+(LP4mMa6V+22vz*@;KJ4nr8?03OzBDMsX4X`;L6dpb`~XsVKrq zniAT!W1qpMj#bIoEcb;~v9dm49q##)2QU%DcHpNi-q#tmR+1o<0L)=;R%>l{Www>g zp7-eKe4Gl?;R9W~%_J6o3Yb>U!`eX~M3eOF!Frc0-!m;Memz1xTajJUe@(QeF?8fS z%ad;`%QW%#O(iDpVb4YYD;^7)GbuN%*4*#(lgyZ<64GSU(D;?zNz)wDbFsZ}U z>0gtg4L%AZUPkBEi(m0E&(|sj`tI5le~d(Cf}~}MhK`Br>QRkLS6IL{=BD(dc9liHpgrZV>fLj%u>R4fYDMqCq~~L1JIavNT_Q19@yRg{(&B z)k>M7x^7*AYxq8~J#}vdB@f$TP6kH1Gsb=u`n0L)^(3azbj-|4?MZ2} zbftj)e%?yhhqmrjb0lCfY|g6gc@EMtS=mSWWdj%(-`-Md9ZSX6Pd0&iq0Snq9_shM z+Mk@+M?K7YH-rY(*T$duF!>|79C~QRVKcVUgLT92@5XV{~=Ta?rs zP&F$irYd`d4aBlJ2g?Sl6b9qrw7=Z*SWn$+KZp3|N?vT;ln-;i@7*gjj)BkmjH~xf zkPf|ubq<|WmgR$uwKrK-z=-^av$P?rEc%l~|HVgbD8`CvRf!&xfL#WHm_SdGr;HuB zUN{#HnOt#yb7&In(|NT(5#y%Zh7-YMhSSHJR1G+&< zh47z4O{L0i@!5CLA*;wqNHa4q7*0#Cs(3pLK$w2bsy z`m6dLcczoMu?Vp|-e4J~cuhr@U&K7R{3YV->qT~F>I zlke{2mtBt?D|0dHrHK%uT^8-OU>JH16$0d&a)@RKkA#9SiHnk0f|Xf!aWZ%@Oolbo z*(JEij&4v7>~|@W?*!E9?}P}E={}QTl+@>co>tj7L6B9+i=7bh3%a!kS-cwlp8&2F zQR(x0P8(Ag;9Zk#d^7=+;uE>_i|>5w@O^*p!e}K?@zF+w2*o2uT_(1%Rksf!jUcD# z-%>-xv?>0#`uG*-w&>9Ll2-`fG!<``gtG>S%n6)&JATzELYy~b(x-6R%h05m{xV5_ z)>1U(J@+0Fatp{{`BBNCjZ;6PBzJ%Av%KC7MJ+RdBLBe`Q;o|;Xae=jsE2vq;ZlJj>lj$ zY(9VDk1HADYGx!z&(-09#5PFD`$d3%6I)@d?Q7XB{~?C~i7;uS+JI@`jj zXQ~laIjvj{+=)L}1|N9iZEvdj1vMO{)~qrmMhkw_zR)#e{=e^hS! znlMY;EGXmV!2RC7{KPCJ8z@;FdpNlElFaLcJDmZmpOZLq6Z7==@gx`vOnD-Iu+Qq$ zN+dWP{@Z$JF;GZ9x|$P*Y_6|zlfAfz-F{BnJ6ykcv~@& zzpRgmCd}YsW!Z5kxaGP=8KT@(;i%BTK-q^3@dObto78QPSgZx6SzzW1Dk&P`;o+-& zKME~vfGYX!6T`LJ5-(4|DJiki|r1Z5z^iIYR#YX@&9aVpa!UpXw zZ!p#pp~E-x3=Pd)T3)6}?Y>M4FMeM-{3=a@`_Zx87$*jBFJ5zfTgv=pj~Id_fAqT@ zQaLlIEMdBoL!hhU@k#onG>BJH5;sIcNlHR3FPe$|ai(fyk}u`jO9yFxLr$CVKZmt| ziY!WEl2%wnI&1DF>*E)n?AhS@zs`00&nC?TNAuY8#e_M+(dWrbpw7G8#oN+fVoJF4 z0aOSW^-SB<8rwZQnqR{fWTL%q<~iUCQK!7zu|xX^HQcG43Gg3gT$C6k@j`Onwv>i- z0mI)J%TBL|Au^mmF{}`Nq6KL8zWvkJWiw9`1 zC(Y}ukGlPA+CZW!<;-@vGx2Cifjt2Vuk_R`U|MXdMu#Yyl|OVilm#|=>rT&(!CRHQ z9fxM5{{0cpw0W{E0TUb8JTXbSyXtBOT8{OyO68)k&@ty0j5YuGPTr%a9j|z^Y@@Z2 zXTY!bnE?us5O$A$0W;EVbO`c#O258-B?*C>=&5lPp*)2uv?;%!MU#bl# zDVXCTb{PVo~L+>Mo&ocQM8?84uWUx93p+8ftRJTMtdhR@f$ zlrRV)hQy$aJsUHkJI2UeULEuK*gi*E$@#5k%No7w!Hi~M}b_ekkB5kmJOsuU*I-?sp= ziYdCX^Q1{bCxaq?(wLZFVpYV9P(#0p!`nQXOZFkgQ51EozBC8UsmG=8f$a;W6JZx5 zgu{9PGS*0cB&EYn&(>{HfR(9q$uraXU+X*1lUn6TPg{!qrj=%l@{V*#aN&x?fg7*k zvGj<4*BZ!Xeq;!ug>Uw3zfHUG_%4ZvUdfDpDsk=?Tt1C^1h7FyoSF!e{HNG>zSg~z z5HO!1>66W#l*r9*F<t)B&`3}mp&ZtPi#lC@>NuZ_JRH;_#szc=iJxZV-trFN zhgoI0#FjhXyYAOzz7ZVV`H*VIl@|rdMT%~=RZDO6mko~VS+l7_0JLpJFRHVs-}4Tz zo1C7!O8eU?VcvnRcbd(sR;jqORhL%3qbM1!uw95OT?PUUqePtU4!It+mnh=`q3DL3 zH9*aOvv%`rzYiA*`RbVP7eHu1AAJVf=SYfV>g2mPc)NP1pJeH{GU2H^%q*a6*$$fF z)utJb{G|F0pR3BPVE>vn&fB)~NTbGgrbgG{K=J<9g5+1Nvu!bMGA!^DvBIulCdKBLM4%iDid~mX0iVFTj3$6MC7jEcduw7l6(Pw zW1mjP0q|d5PVqS@2r3E^wOS=)#4x?vC7{uyiR-NS0H@t4?~_v-O5hk69`O0}R>1(H z_}EolaB*I{nrv=7&jig-ZZUfS36`W`INmpt?jcmuUj-9kOA+H$)TnIBP5)yf;ZV!P zOAK1Hg6328OoaO4;b~_&I>sPPXQf7e6WP~5yvu%(M5Nj?(Q@VjE7lP)$1ScyI&Wqc zV%#lHdH3mDG^io0`b-kyV0NL$Xo9EG$cm1;9TMY|>*-Lg$79@8g@_Jn=%n<x>qfRu=v9=D5tim7i=hhSSSo7 z)C-^*p4w7zjYOP?JMN*LP5!F#BUHAQ#T#+DJLIE3;}Y{EVa|!;M6>>dn3#rX-$M4w zmTKOyeItMiO=1NA{Wtfr+!SJlB5p4Hq`XfLSkslx4?NH~mD4xi2M=MIdUms}>2%K^;#&5Nb6(wE{U*+T-qjr#0_^Zy9tA zV%s+akBr9z{8k0tJ>HD}T)1ymEKVEmXgj`jC7KB~>WxXM#gckXu4Hv)EQXSuZvFAT zna=tLC|)AEqBw<&W@w}|$09(vYWCV-DL#9j#=HUokK+JBXIr4+jbc6tcAvevJWyl% zH6T2hDi62>DMswlS*+zGe?4QhFFJGZkEw;z3-oUM;*cjByRz)AA zL`fBJ>+y(*h!y>}+eq;)kMscJh7fNFQGI`h%=W)3UABI8G61f#OtO&>|I zdTB5ngqh^$`0T~72H4#97|%Atx0l(89A7{$(e%n$OEcXb4y&lNlLC|Rv$oEp%|V6Cft>? zC-Z;bgo(7*EOH|^q)d>X3qA{)a%8kLn0o)=SV(G1JUz#@rs9&fB#BUAnwq)A?l2Oj zTYA$jHoYh@Re7#|H-5g2u|QU9lWMSQt0UmnxH;v=I5KS*eF@Z6)G+Cai$HTwt>Bp6z|aH?B>KVPmgWITf2P-XIFXFoT+Le@Hv`&4PFZ25svk_NQHO1Q=# zm+#Yf^$hcW_lG!wGnY@EaTykA-`NJ%0Quk-!QI=^4NH2f#=oDW%B@-~nf1TqB$S_CuX)qfRsJxLbOq8EVKNd5(}% z#zRlkpSR@S3r%ZU(-D@@t?d;D0``we#LrAhIW=A$MYwMH^Mk@1o4|C;4hQTNy?bW_ zH>MGPF8~GJf^cOp}|2j-LL_< z%%h62w!tof;)Kf}8#ag&BZ-M(ZS6N4HF@!Wg38^*$#L6)E6WOdYLYv|WCJFVW*163 z>=tfCWBv>m?AP)Hf_FbuEE=tjZ4nWVmM4*aNtF-j7)TH9+0XU%{gbr&f_t@n?4%&? z!-T}r*(?u5JCt*q)N6?rzh`RW>;TPLQ8{6D$K;~(5e&>3O_QGuUWj%`^C*v03CG@i z`b1Y2CcutT67s7DWY<9#msFK^hWzlENBmr)9+OdQly!TjSw~#CG#!L#w;q0f zVSj(}X@0D0nt?RL=vX>2_WjqOg_Ca3Pes7n$jP4)&Oi5caU{_g_tCRPwhia~boCmJ z%Ek}a#UGIdgnSEiZuOMEd!+we;rvxWbXVS$Z29yyB_Myv2FjhAbUag-t3)=W3cUvb z-@{A6nH{pKpE3{A_-=1}mVGQF`VNLZisI5CCB?9+vygY|h?7nR}~G zrv16(es3ETJ9Ohzn_KK~a6mNIC!h$s6+x+?!J?|wEY=FcyM$*)FBymLy?tnZYjD}E z`W$Ftq;Q;Gv-vsWGR;}TLlS-QW<>NkdyWBYnFVJfi-p1%QU|yRzar&GHE)6sB&M=S zM}DzbJV#0$gw|OBnEvU_GHLDLv)HEudu78@%vw7=Ky8v zn(~W0O1ANqPQdjtE7F(_@s$sMJ&X>7fd)Yc!tpP*!n=@$J+azM582$RFA6c*^ybWB zd?RCMPjX8|nV>0<*_GiA-7=NX3=d`d!ZfR`~9}7+FScmHEF4$QEETonU4(tpX>lJ(ov9LG_at^h(TsGOQT zSucN4KDrwHkNrmqL;v)I1{>7%qj^rx%)pTZ&M>LpwFe7znGT0YKM3F($UE@0#iXg~ z@?6+J&Ij-%tcV|A_1&PzuH*!^;jhyX&PC3T#N?*RRLr9P;X#1A_dZss4K+WgY(e9k$8uqZn0ML9u zB?|+!(?Fvujb0R@{j)ZzGM}_O25zfcC1z&s`D}8Vl$$A;IlBo4Gr3g#JJn|t*K2kg zE``-z7kDPC8I|-cjCBaDlmJcTWUi;@KfETXi;;Jdnn}Z|7-UI*)>Gk%XZqvHClEgp zNv|b9 z^Q2dB_9ugK>f{+k!-m2We4Nou+QtrvPZn}P_YUIlg|KV>I(71TT=eK(S)2uOlfc;m z^UwXQT``h)Yx1Fg)4~SN%FeYixJ$X~T%L`1L*k^{er3`}vJELqBBkG7LM#}{RNvRe z;9_CIlPk?}2fCF$mWcBbq^+!)xjJPmVdQivY8kMiN<^C-9Si4f{}EnD+@z)W4L}b+ zC>$i-9;~z+@JaJVJ`nz|C485gLiFnXKQWEjbQmq6AqHxH##2Uj!%u8|@Ft?xQBk?i zFd|A9=6M8L5&v@H9y#Id_&bu_MzQ_~r1$+=)|auvde7VLoUDF#*PAk=l$hxWS@zIC zd*sX*L2>VHH&b1dmom=~^W({AuH+d?P8Aj-i4py{scXWyw1xy1B#n`#(*B+tACPC# z=%Bvm-50QbO5_ik!4~I?Tu*9sD1R)5OGskxtRkO3X(sw_Fj`)-dMO4UkGCCB-k}V% z1J@E}FmP9o)hC|@)u@4@NQF|d0He51#&pzOO>%W*dZS)l;ycs>@=mlKy53D@p}kQ4 zv1{u0*zxhvE~s^eIBdz?E0w7x*}ppSD(4$ELjrO>xPDSL^OT)5gGEbnf8VRt=^-99`JpMkW$=BoFS;%_}ehP7%mvCY>W zq@;iR-pTTp9vHQCHPX$Bsxr%{Tz~NIS#r~$fFj+gar3XYXf+EQUPP%zD(rG!NO}#z zrkW*xDM^gy-AE8Xq)xfN(s%X|WSe?lX#NO7Td-uv8&U>!+JoM$KxmZs-~=^q-i%!tB^C>ygf zkZG`*6E4%@Rps`QTUMSx2~7!`J~Z~1%G_grXPG||nC>HW#6GrP=_tzj>AyEMKC-d1 z3pMYwxNTe(2O6mSSUOF3xISMMaUJ?=O)q7OcACzgR6a$ItI8IC zR!nE{k;g_NaGTmF(G*3ga4G<~sC|E);_bx2gjj3bizDf|Lj&ZfNcdRPO;W=26dr=h z7t@Qz^#dZGBArRcogP|-aSYJjL(meO9&J}9O!fYD?2x;Mfc+hk3uH)BQCHFBIj0KF zx9WgZ%R#q(Z%af5u<#|yFKAb0X5*`W=Bf`AxUY3^1;V+rSLOuymp4&VH^@x?#$3u* z&8&-gQoddPEg@~(LpJ>)Q;Me-9xqoAmfO9rc-cMk`DP^w29 z&9w|1W;5w~)?0vxUz|1JwCE-PId?k>ilA3P(1#mn0-`*n=q3~+-+ILrvxwu&9X`b- zZtI$u_kU`rH2q+8$Ajpx*>!HZ3iZtqNL`&CLWt`VYeUG^^c4jex`IJ~0g0>lnI|`Q zuz`NA7>1EeqPR9uu-2QP!e7jPiJo}E|CX>W8Kz;#5ER!_3v6Jc1p$+=I9`W`+&W29 z7S*2E3YGwiDObhieWejb$r5~%2arL>ZO1?bnaAtf67ObePz3#MT1!FH@{P9_bgXk! zy)ZF74v6{ePpN|kEAv`QBgyq;G5vzBOC!Y(qbR(-o(MOki$*jr2E+Q=6`0 zENNX|dUm4fUUdcn?y}?+qJ2~3k#=_IaCfh3RQaHg7#>OUb&iDlY|giHW4g=u4i>;B zm9`z9d9JYx8eUuKV5!k`U+)kWOHN)q` zbN_#>?^{_bdG|BV%%0iv%uZG~Sal8fZM5rV-IwNOZax;p{@0s}xI5+G3tAP^t~ z1d9JnM7c=-6d@jPJAjq|KplmIp@}&ZP_Eu?a0f>WcAvi=0o+g?07zV1^xkiGfSe1= z4Gx7M0a_4@Bg_T6BNT!F7@(kV7{>d5A0fCOIASoa5`u!Bo}K~_7qkG%%|V*y9>5ch zaRlhY&@eX-m>u9($pCGL3+%7b1c*5RhK_LbAA^`W6|a90dk01Zd{ zs!{M)80;}CA?*}UE-o-622K1cKSj7342nH>Z^6Hs>x@KsB7Of}*~5``_P@%ob9WUq zLc$-p!_*Z2;$R`-e`5|X3_uuvC@vx*3{~a9*!|ea8vHf?0 zdjTwfSowhfz+bO_Jy~KEW`{x|y#G!A-C{vw1w&13IljM2{+Cf+9_0mp@Z}d02k?uF z00AHnNCY4%Dh%-dXB=G!{I5Lz!&ePyj{=DQNf&!gf2Zv6mj<~18W0}9KVxa5u*!u2 zxc@Emhd^N<6#EAHKg<2M%l}X1zoPuFLjUiKl-&`C-*)alg#X75ae*Ve|6*X3>yE)r zfffoo3&{Vbn!x^yt`^LH4({&q-&QpY1Un6KNC&K<`9b#ufcO94aI`Yq3udPa$3Pwb zsOArD^lRP_a3o9@g@*sSVX$66;D6b$Lk4xm-XdtMG=H05*ctlgzDh_a%I?>&2?>h; zAZ~6DZ(?k(u`6MKF9f?rv__8UL+6Y|VeKe_tptm=_F6JU@$qN`^YU4sAWJl4JDb z-x?)YU2Bg@Fzbtd6vlAAd+zI~NtmTF^+?{v?&a;_blthq@X1*}M&AANF|UVR*+DC5 zs<{{(rM?aM1OB|hZ^vB@Fcv!$gTuIJdejExmqa~gavO{57F@|Dvp>Q_yTRM9J``NG zqqoh)cL6SdqEiaiG)7FUTu%Eg?h`Xs_BG6q*+YuBTW%JA8SaK^M&p;bPvCK9@~tuS z-@G?0;xdPpm)~Uf_oai6@-=!YMP7ze(Np`Vv*rvZ4bamhW~(=#aX96LPZdg26WHhr zUBWq6@N7g^E~fMQTM`Gr?sX2@3PCq@9*@+!*Pw)FrEB)#336y9;o zNXRl(3L!S|{)N1VE`r5%*xqE}$AeS=6$1yAt{R>;tJ9kM@ZEa?UtjdW%T4bjBTqgy zzG)rmjyOQE?=#a(1tplaW$pIvBsQoCpT4Cu=2a4Z!BlI!Lv>j5#OK6M2k7VKT-R-B zSCKTA6`z}6i#G<7=NVGIGt}J1$WaPP2aHCYJSRnB6 z;>5u*SRYjde%?kB+OcN2bmlsB6SIuM;* z$(6rxj*9j&o8qT&PcAr9HZl-*lz-Ab4A7*+ z)prEFVo}bqJuG@T?#~y2AXPZG1QZo6c5@SjGI`j~phEcU$8TqA?e5*F@jpYzFhO}& zBH8v|S_SA=e6TEY3E!l63oj1UDAO5#oQh*ryBYI(`t`;3?XUWjSJs$m6Uoeuk;9Au zcUkVcWfYDjqUtp_W*Tyg4uFNPNbJQ8Q_^|RNqIT{sf$(+>e%B&^3^3H~edXT-N zlUmdTq5U^h$dhFYw3CFb4#25VhFdja_RZk{25-Hhh>#{7p3qv-3ZUrphba!Sup6N& zBn97-^nG4X9Ut3&@{O3VqEvKTI(e{}@0*#qE}uHQGwc7ovwuDZEo9GsrEu)MvR-99 z@M`*%tR<91EV&xVAo_?ag#N=djmRJOopq$>_O8lhXN>?!B}<5V%ep9~Co6OxoN?b~ z@{)-XJ;JkCU?uo`_Pt?j?&I`BR7X#-xH=RIN7z!QYd816*;)LQ9J#9#F(UeLOZUCo~;f>{-%18H$pgqjC}x(!#Mwl`3}aI zxg|Ohm*KEV^B)Yo`I=;6P`qJ?@2>aVw!Y4hkTy+>gu8E}<nhZK^3dMjW>XRICn@?&x=)y!V_65vlcP)Mj7j11 z+pgl?Y%-oXT#Z&KsX&MZYuGcIQ2VU7SdkAVneo8?>;#3M>n5)WsK zo#^=z%noFpy9%l;?=hBvcig%a<#W6(*5BvXQ7CQq)5+T~D>kU7&e&z(L;4#1qv8<< zg(3QX#N)&-bDhmu*TjABTeb`%6;=WSdohoj6Z0|%Ye>+&N}C#^?qTn{G9+Exi* z{GUOB=VURtqCqjdO2T*3?II2fP;qI#mI`Hm((G4w$~Sx*SSKQRU!af(2%yBcF|R?^cs&8b>`odGqtfxeF;Z0y0Kw z$wB>DfUU?Tp{3ONm0km!DS%@8p#5|76;HTsI@@B>r6Vcs5p zPSL3yNFz7jxx9QN+G#nUJfDaW3G|^WQ+dU_cIQ!4L;NnJ)I{$ShfnDAZS~hpbEX9h z`Q2cQnm4ew{e{5w>AO*V7Rh%Dm_rorD!mO(a&@g#<}EMzTD_9t@x@JN+HMRfio97s zIfZ909>QD6_}NtAYx}nJKx>u+@92tuCbK>6Xe>>ScoHWh$w`ur*_WmT7;%GVVnHs+ zp{GiNcPGeHqZ@b8xSq>r-u!q(j(LIS26F#&{ASIJVQUIyPiDfR=GZEk`tFybPgaWX zl1q!C0}1qlXG@Jj-K>YyD@GCD{hs2a-6i-YY#h34KWP-b^GG+y|Ln(;27^VPew`sn`jS>z zmp;ct5g_nMP`QMWaj=@`RB%GSGLB=>|TBZO*#59__0~plW5S zs@Kzkep(;w$V~-+i`VsNK6S`{vlyQ|W@_rp*G)qK5!o)u4m9G8mw>K(| z@68(Y<%*nawBj>8cPl8iNL=pnuz63?T33A$OLx){;B}_L{xg>`v~XvCT);oCY3$}m zN<#_V(s;Y_Xl4qusyZt%SnBr6E_+tGYj=2u+sXt81h+j2dZYBknz?1?=bvQxkU|^V zWP7wZ)m+kZmS0Glvc7Rig&hvbjv;8tOn$OW87ruMJbxzk)|qZ55&wbrdA7DYDI|q( zr?8~0PoSv(3ob^xwy-yU5+U@OqS0AS%`$?APV1aJpxz+=!%wrcd1M_!a4Z2qX8a6i z39nTg^FSik52!2-`TFf2oDGA14_3$e3ewNoStc3ws&4(^@*&<1qV|^dd*_v@nv(1a~etgnCIO<&D4L(P$N1x*?0RoSsR5!Xw;}t#E zo6ao@0!i8!6KHnrp8F~#(F_&#Jn;;gr(esY6kw+@UfXtLz+|8LII}xDvs>QZt)#hr z0JU$-`(8=WqHx`RBu(~c`1k_+>@?l=4nnW;d9vPz%&6Ld zo)o)oeKjLTnbd*YrP6y#_%q){BhHu8NAkf;M-D-d%h84fTy$idwstrB#UU3j?d2oW zK*MXuBg_NFnHc9IK_Zz_As2d{oZ)f%lcvhO)V1~ebML!<+#8iP91Ff>j1Rik1El)0$m*uD|3tCAiAAzLQ0n&r?0a-SquwVcktFt!Co7no!b5{T`h4l|yF= zt6N}goO(@jbd9H>uDfp{ExNUNyy{#x=LsMGvzMiLMo-eKmA@LD>$0_IjD?5umA6ir zwZlZIWPs(|si#D6J4VJV&00wZXF~C=Tij-9{0T9C2%A@5_a$v+XtqDdO%SO{)V_MY zW~Rz)3renAZ&4laZS)Ko(6=(1%%Uf|NBo>!x#Vq{s^a{SF@ucj5ux{FdK0zo3Wu^( zOK|rHKM)ipHF-W6fjjT8qZ(YD3mLk%0Pw zKK5IGSqU_&&eeLkw#;thuYZGpJeY7H;9*H1<+`?zvwc3~80D@m3Vs$qu~U2Gv9{B3 z5}>hY;+w5Cy#khb7av=yb!7QX!h~Lun$qJ=LKsB`zUjIoeyIGNq#IGird06)x@&5Z zGP$gV1(5)On+<5%&v>UsmYc6alB6b0qpxm%UM30Gc18!f1!`fWy`?I{c{hS=74X_0 zTamV5`WWThs`C(B_2+#>sXvadJv=#^%N=CW48q+F$tb);_Eu1 zi5{metCVfdiRGm4kmgkqXnAa{ay!v~VTwaGRsp1k7kXQIk7sN3Vc zPP*jc>qjryo_0AT%SS(p8S9(Z-H$twl(*80*C|Z~f9v3tzX`4haYwd);ITKXs`ZoY z{LHo1A%I=kyd}Pq!QQ!Q6YS3~PNOH-TeziF0}ITNnd=%D+?lGXyT(HC*>MxkGP=n2 zpyS5nr^>m8v7ljoyp{e0IcK4X}=%c?BKv#TTN)$^`Obz}=Tv=Y^VS3Z$qit6S( z2tvYV9x^lu+HOqt9BCPUE7J@Cg@2CmIje06nTSivQ04OHTd+SfYn27rFpUrtr zW#L6Ver(0HA5QiYW{GnL1}$i&HKQGKapTNx(bVwFp@c=9X;!b2?{WkXswO?exmV#e z=68awM0@QOs^&aU)}Y+jjF`h8-E%Cy*<>yb4V`a?yEeCmh>Bg4GJG3XOVmW@6w)*<74QT- ztDd<~6P7Ox8N6kGf2DW9GO3_>l7F1oNb8m1dE_KMZFlK}Th1XWz20+)cphztn7&q^=up&uV9_C@?~1U0%IzTQX=z_% zoH^WWu@mrkHwL8q?GuX?xg6M|;>N(b&Qp)6N~U_DYaS%TKHs+t8&|#$1Lv2iZSS5w zy=L*$$9p_!hW$DWRI%thBb;uhFZbDoyDv=EH$e*D+eEtKAaYasdt&9bx9o?$pG`(< z--&+zrO=~)Dmei4O*?qtEpIDYieTmRif=x^mo1HW`z4i#-!AX^Vw?Ns&O@B;QQQw~ z83AWp?)yW2G_2B#;0s`FEL~6Q3#*w|DYtoMGWmTQbmE(;bY{N`QRtU+*OGg^`M67T zCsMDE=)_arVIpz8_0r(7CFd#IyE4R6+k;ad$)@Um3^nhWhf448yM}k7T-{2XwMZId z31quroSo0XsTqi#p(u>O*@s>Z=Ab>EkAklH1LrIAon>sdh3ediGn8OS!smRw^Hu0# z^CK<>BI@d<;;$L+w{0W!UNf8=R2d*{I`=kn`h;(cBnpNnPzXydUHG^N~(^T+Da+}t=-{O291UC~=9X16nIPtV^R?A((R zMh>a1Do3XZX3P8-iOyUjwS=GrYPAKg6lPj~aLF)qOP8u)D#Ac7e;Bi^I8nL*J?FRV z3ZhRzz%94-_vPxvEUJNt_(3PQ+Akk=$XMOy+Ry%ITRPY>ey5X5LSxFt(-k^yNR<}P zy0mEhljKx2gR$y7x+!)!Iy~|CirF`e$hUVvFoy;!ngcR92C7*3oH}+CH zZolTUt~y=Ogm5PEX)|Yk`RrABjPJCto1sM&53|A+6{FW?)wtVhw%Rv6Emq(;ahyqjS8CH&zA6Xz9afK7 z9N3pa-8uYX+}6A&M>8tJ7Oh%8xN{o_w`JCMJ~Z!do#@_nswdYo+#x+W?=4|}e8yxR zJ{I1r)rfydo=LwKumt_&Wv0tsPSgRUjmjr@=b|wppF1_x(bN()qB?y;v!MzCcN%)J z+Yu-s<^@gp#BcHfw8>)iC8Rv4&_XXqiOwGx=SL<%wdp&`W)T;{3kLIFSV8Bbr3t-! z?%QBAR(L_7OXdtJD*1wr-tFUm0m*Tg+|+H%KAM(FvIwyC14JnnLeL(Zye&lAKokp* z)JWSmvT4(&NC>U0qM3SO8~dbCBV%#oQAuHa9Y9$ZYe&Rv}|j$bvSZ`HeG zPF_DG(8hUv?nxZRwPg*IPTpZLq?jb#H{l9jzMw#wE?sL+`WE(6@{Ngq+&3HsmB*{x z2L(Lu9<`PA;3_5{A1-p^wLXdL(i7NmTm~gaC*cSQ9ln{|$Z0ibi?PF9^IF({{LOXl zuDhc}7Gn?{uWgmqyy5Ko^j4bYX*J$w08q6%Sm4#s*e-F7{luI3{M(k{EN^iAmbf@B z!Q=5GM_0oS{nXx)#`{Ts*7~LSijKW*if2yr4Wjs&7tVqsKrpmOQ?{O|-uVh$F4XT? zg`YZOH&I7v(7zHeYTNsb&2U!nN@_}OQeW=k|!jhlEbTiPDE|dzb|U)t}}bB zz1raX*<&-*G|^Ngr@hzP@1FM_J12SNkl7=A=F?%1l0Qy3$W)E@wIn#~YNR z0u{*H&T$Us$0a1}bbV8NAmO)UY}@w4wkEcniIbVwPCB-2+qRvF&51d&o$T!WzwF(; z`_TRJeUIJ0Q&s1jsx@{hT93-BMA~`Mf{}bPJC< zwSKb^#7LUk0Uxw%-Eo&}P59dh*OJQx#DvTFeSN#zQSOfC$hgpgtetjq`P6Wt`sIq? zFVK?_YUcm+z5kOPY-?&~YzfE4{;%;(*V@wtT10@s!A!zTqC&!?V&-J$;%H*#M8d(6 zYN-f@pBldeN(*o>bN#nA_ywN6(?;9PpWXnw;u2J(Z4kDF(5CL973uk{VYZcYJ))oK zEvtoMp+)Buy*-^EQt=oRqqh7jnWu@u_U)akSNdU8E3ooEvgfYfj_(?;e!yijO9w6T z^YqG8QL(c8PLQiRcxUyzNJ)?W|9ZsJNusu5c zEWYk9$-Of!Z%ck+6HkAA{*f&~laQ8R3n}{9a3HMZpm-d5VLZ;3(qloK)BluIqMjGl zDeqHn#n;QYUbA_iuN}%{yJMzqt@GvFx4uy3fE{J3i%DGpm-=srD43Oov@l$5cYc#=;ZaWZ|tz`*-!%-0!ii9~%VV>Ca z6AM%)vd}{@(q;{K#YhIjri++R@MutrcK8sbjh2~U@VaCo!=Rj#Y-^=%M{Y274Vs9A zbI|6yE(TXds%0~25~4D}1LaXgFHnVqD{vXuRYs68oeoOX14r$HOp!z&0A{-d4WQXv zjw+$=npN+TPfIpaGH)YW^+1h5<7Ph9*D&R`0Ck^7kdxTMN6#aQY3z$dY}7nD<^XQM znb-@sNA5q%mDCrP9msm`DXv@%uiP9SLV%Jpi7}4h{Y^EXE|D~D9KybGIvM9#{JG7R zyU9kWto8uQS_Jl;`*3>z&`u=~?G{Jh!DUIueW5tk=6%5I4gC!3t?bfyD2K>pBB2g0 zmQB6hcyNy>DbExNLf$?&>-ydLARc?#VBP86NmpQLjv`Z(wRU}v0wTKmuXyxip!WWX z*l5^-G$z#miA1%OrNaFw!R??$dwC;t!|_S2a2td4Q}QQ{{V(fRptS74i~@WM!Jd02 zUr*s&LKccDr5wfNR}?F>PoP~?9}$}PB_AY6wh!R@coWsnDep%JW1X%R&T6w?v z_J+*f9+YbM&k8+}54uB|d+0a9ocefYBk}hO?q)b713yigYMA3a2n!T@%6yDK5au<_ z3?Zf}`xkM?y8UVcpht_GN5@EN$^|nldZlv+izlCwxmmkKRVv!v;^|jS~-#S*wDu?M|75;QY zuV-M!t!ULQl)?K+OzosA>3h;`?5T1|PdubNzt147mQ5rV0_0s{>N~A^6+4Y8SMZLj zL&n&q1I??w1{WD6tB=aCoHcwWP&%oDT%V1OPT**;!aj(|aW*SSl}MEkK^+y96%uis z%e|M&W?F}sd0jR5W&2#d(1b(D51-t4I@kgNQm)YEfPz10yBnN63e2MCU(B79{kQ|AbcAz()t5-i9pVC=-^MyY5P2axJWW4V zna*3jF>!j|UPOJ%7Y#f}(oeOitC2?(Z8$YkCgdxMuNlcARPn1M<~u0z$r?5YMXRW# zrx<8~;TOqXP4+lU@7AYTJgC9(%u8#wP)fe(Px?;D0$^UU_Q@^!v@%x4wUA6Jf?+_M zid1aiX{&PTGhhUsyX&&IwJ{n8HT6+!0iN2#GHij~rKV)`_f2})3DolJMT%wY5}a&z zMsU7Ji0v3~lT(iuW>OdbhJi0#n50_m^XJ-T!!}+jA|umi6^hiU!G9Mz{S}e7BGz4q zX}p4{1Y~>A94ndslDt(YA41BYu7YTfl&-nytvg&pzyy((eK=5?Lhi2h{~8U>@z)zK z2+qmQGr~jW1IZ@gdJ2T)k&cR4Np^DdmWUxNho^BdQiGGlSSkGr=Ep1{Prj4nWywq~ z-5)kJ^ebK9FT#`MN!r-tz8F^R&pJVsRZ~C72cW-}Sa6qLHbhQwn0p~}_I%({DG%i2 z%+1%%K%@`+eq9-R)^uIoC!%=>idPf#$4_k->aVCr>4698y2R6c70{+ESOWY8Uqh5e zQY6Rk!%hm%wD19|qz8+BB{C%qdZ=^|fh47LuO#{yTF-K4D-$WP_NC zGhlt4B)|)v(^DgPY&n)|K!$rmpJ4iq%#Y7-W$TR_x+YYjBHzT>XwPK_ zRlUZAly6NiQ|=?4b!9bC^3zQnySgI}4?ts_KkX@D$YUCSnOzA94KA4tDGSBS7`>$S z;}g|J$%c7Cw>z_W7}CTLs?B%MmJ$CB@pNXp5~NQprzgA!g;zr~I;s@A?+A19Y`?T< zwB&SIx42sgsZsoi=&Umk1gV1K!|{&RO+;BzbAYg(e5ggeDVIIwHlfIm?K3c8Qwe zl0)zF;f_sIO#_|rz91vsA2KaI4-L-FD%xD7NE=+g)#8WN5CNA8tE%A$V*zC!Aat$+ z#CmWA-7t-(rm)*XM^bIEPUi1BOD~<+b~!KIn|AvCX`4PO`?+`cJ0?P+fLKvA&}c=t zNeN-NH@t&05bt5f8y5VM$;jIh0bX3*gLZK>Z5q)|P+RtAsdl5?p6`KqB3(Ze5!>AN z6$a&pnNNrLY2)r5H-hf_mHRwI?TbTrZ*}Lu8v91$?=A{5QmETrLa@icn#jxWrkR4p zFf{OHX#J~6Sx^QWCJ2KDCOb%%Ny~-HTAq7NDGN9`qW1 z_>p@18qRcR(fF^g`woCa+#1=gxn&uCETT;J_eA>-M%f*Y+MEI)QXAsS{{vD?1*HYU z0A)|5Q3PZBpP(Ygf1qM3A{aG5!p6$R`rpB#?nc6X3#w0Utx^t|y0+FHlJzjMYu8!C zge%WlHHCT$aU0vcR5+uFOk?9&?M#0#22&m*+x@Eap_!C}aNeBHt1}mfdE$mN=gTc! zC!Xf-qq=&NjbZLz}%MNPSk}d*T#&wQ%BW-Mq!OSJ0 zluj~spl9$-z20^IN4MujW=m3#@^Ut3tGWGpGT6uc20E-hoODpw!Zzj`$%td)Cexid z%GHNl#jluI2(R zUFr<>g|qacg^ME}<&Mk^GLE>tAxr&k&&G>NV1YG3nnigL#qxqBxWL6ce6K0Iu!Zc` z2&}qw0WBUJx#h%4y{AYr zcE;am@^mEPVmH6y4Q4=^#J#f&t`=I1pgNkG9hUPE3(*k;%=*2>EWsxXOX!+(O8St; z01zNrBX{IRPL?!DstY^x%}s_PPhpt>3)UaQNFoO-44k5gb{08(QUx4tz^|5*zZ3jc z5=lx`MoFw3uSdvKTZPU|wo;;(q9}o4fuB;{t1d@P`E;@A)sffD2Uj<;crOp(D`cUJ zgtz!NhiTed9o>;0I5HAP)R-KF!xys&;Hg7zhmBPBhD9#%{@2gI7ot~|XH!Cum2!Fbs8XNlcliMOv2kWr3vB#a#w%;& z4B>?+@D26NK~bw$4{H`J2vQ8Q0Kut9RrXqm5|77C_S%{Jm&ur+JKE|e_aAxX$u0hn zQGzRDt|#q_fSiC6)avbIvslls0wL&H-A@(g`PAQc0}D3u;Ja$JDurH#=Fs{m!X#P! zc5(A;%M)Ns4*eb9igMH!ac+fk?E4hVk?My*RV_$9U}^P{RlZBvA-eOH18?-C35}Py zM!cjd5{Yb+=eTN=;p3*Ioot);`e*=LLUeizVmmE9<#+I^a4Tp}BZs6vt`A$1(>s}S z(l7lUCV%h-sIss@A5eI*-KTDCvYEI9KRc|huNoMwP4qY28Q{DCY&uiyd34tu29=Mv zjCAp2UFvCMnzh2&?XG8Iz^jwawh-j0W=~-`%*mbZNwl8+2xs_cBvDMA?FrsKS($86 z9P(MXd(0o9oWn?&eA`yvl^h~a#sW?H@tT&lf=^lLNu`(|!jT+iB~B%_$ww?Z5&-*O zJ|w^7YR_K12>h~-1Jv^v=eFAd_$ivf;6~T4H*GW$!nHj{(r)8248)>V7$V8y&AK>-)6hVUIR(P{;K|byjTHa4i_G;&y6M0bL>Q{5kV?1R9V1mI@SUXYvgSW{bSDW zL8o5kfu^dJe38zx>!4vSHztvOwdJBKqOGfl*|AZ_ry>J9ptE!e<|;$7#qFzNbxYQv zw|z^~fp7dO)MHv%QQ=O%%XaSp3APviWzdn(;+W`-Iq2-MCyMLv*0tSXV)ApPb4{<} zv=*lg(TFl8Yj4jSJ*E1UI>8J%DS^% zbRO~&1M83dGco3bjGt|R!b{{!<%f45S^fGrA@ne7fS>)M8qe=s%@^C1lq1*P3G_EI zTiAISwip^5+(7=@Aa_< zgEERT>Q>;cn^i!+FtJ|;Yn;+-lhE_?rZTh1HD#PBM3q{jL+KZFswt+pXY~1Gk#QFx z>CG7Z5rjG0cUGUK7=G}^brh2aF~2!fEhrW*0HV?)OxdKFcI1kn5*)tHVwpzYOP66BzK(fDFEYD&%9T9<9qqp4+XacFM`>(^|tz2QYjgvqvn?m^J-h z0ZlvQNJ#4t80{ru2Dyd0 z6*@$iN$EXuj1zv1L5?2unk+9|>dimHf&6&?Pc_ZB8ksQAD>E76cVhYoTlHpbm$?!t zq1k%1yffhj$gPn_|DSd@V0O00HG+vs)oS^4HkYebVtfi|{0)&uoY>5qnizl2sL|b< zYuv&Ty7VuaLMl5GeiLI@)$}x}aUuuoCb&EbdFIG{gm85oqgDnJzVjfPPF@K%02PO` z#*235N)9C=Q>cLhano=C@t@;y6X&>Idl^#W(~YIvGdZbefS)4nB$MJnAHi_*k;RZQ zD9E?hXKvmQX0Yd?7`4oSpdi{|&ph?_YuxtRiFu#BM%q2qLX>UX$d=ggYv`4hmxBbu zkD=y^A6tSu-8GJ2^-)8kmu+-Mz&Prtma+Ib+E;alV^{)tdu_X4%mWKAXPyz^nwFr4 z)y@}9CyLqcnZ(X+>$fHv)J|iXyR??Vfpf7WsU0#x$}|?i0YL_tHbv;Rh4dk@N#Uet z-Dg%qW{D^=8A9@mf+k}zu7?;Fu<}+u>8&A~=(LW}>U1rLec^BLv;x!gQU8{BEVLM$KJ=Ws|QGzSavx50y_`Xu9_l5oNdB5qe?e{UH z!)+l(ZoxApSVL1QxZUpOGZH57E`@29K zQY#k~Gr1k5ZK_l^qj7t!_z{h}cr)2u>gY;gN8R9vsoANB0;CAi61tE-pb4@U8uqbP zEsA2lAW!!6ohduu_rnJ@(@&Y!;^l7b{a85P*!u>3K*GOnrFS{@l(=F*qgNM(XMcJp zuIU|IC(WfPt3;;}<8<=eSQw^WDktWA43l371?ewD5%rp!6U9hQM}LF2&Kv#B-n9fp z^Nx&K`Bj*DNdu-=&Dqp$YS;3i1Wlb*|QFZN8pI68e{@4o6d2^kfJa;%F&b&B@esya0&{`RsBR&(~ zZra6^KI+|kzrJ|V!%RZ^MmZ>uG|bT$1b4wj0t4Pclh{aHA?~%I_S}%t_%+FJ-LSQi zGopkfRY(EM%P8&>>mD@Kc6zRGZD3kYU$15IR22&JPNoI%3pTrb_Vz;m3c{t~;Pn#I zacS&$Vo&uwx9vsb8!WY4TG}lhg_43$Nl$ieP{Fb7G+(l=6Xl5?c+DO%%Q}Fo z5T3K--p}QzNV-|`J^o642u+Bvi9=s0&q^Y}qtFCiHMd`Aqp&ix^gScV7MZpDX|%?s z){h|=!~I^ytGLz&v>g-15mtL2z9w|25bZVC?`C>>Qf`Fq<)grAXAopA)^JBO+w#X z#B$OdTnis(mWFp7N&B0FK;_GCW#EREzm^A|HU+PZ58&n_RU2if_3klu9@)>+fSdQ@ zprSDOm~Jr&NZr~G7M4azw)>}9C@N_Cw;jOq&EIX(Wa-q%q9Vwh!U580$J@jp_@TZat2eNv z*d);QM8^0mQcAYOq{>p7?}{2B_Px$WN>HDeh9L% z+M@I!g6;FAx(@3tP+P1L1$u|!Au|RwMbCV0MTtr$D2P5~2j-1B_{t4#T1x?4hSiXJ z^F-(eoD@w{j9%P+c@QT@8Oq!@;Kx9=fow2NP&Qp8twd2luqlf7ftF_2dtnU?czJXZ z2QLdb1085=k(I^VH;Q-(GAYy$1L0&W=Mdfl^8s4~itB|(6-OrrCgJc@s>al5i$0L# z>vxnP8edj^$1pS%XmbPc5okbX!89rzrnrWNbg>dnTMKb+k7BV$?)SjYfhxg&CBw$B zbq4M39~-5UkVCx-tEaczzIh?VJz;$&NE)XI`Y!beEy4&rQ=9k;R*={PqOOq5 z7{3~^PE{oBXz2HS8$N7ms@R0|0A%lx%8w*Q3&zsvG6B0`GzEgb*)Tw@jAf>7|7U;U zodO!=JfcM+DU`cfK@;)fvzT?agj60ERDF$%%PzveaEtAFNKo(_KhT{$L zP9sgH3r8RbwucI;TyuapTa)t_Eq}1D2;T=x>3_TEJ2E>w;3W6%25v6&Be^0RTDmcV zG0Z`|BKeBN($-w5Af-h0Eq_*4f0#Ft3rB`(lKrjt-r`9g$Y*~bJSAo)zN%_+7gFTlaE)X>F(c&*o1CyPvajOXK2UkJzNELUl0i3iMzGc0N}n zuNY@|vm5t4W0{>ZWy@1=1{!2~#rBl3eg8t+6he6}s^L|MZ*ops+k()bIkyNjoc~Ns zqnE$$cev0FlBrYzL`1x96A$fcYU5|L)JFc6^{Z}6d$NZ6jO!8|*i~E3oq|W$6CLm_ zguVDEbe@xT{}Kho9~1dl{m0e2$oH?+Ldr-75!c@A4^vn&=RNRaA8*mIw&R`h`z=Mm zgGnZ>SAx9wPHxxlZ94Av-MkEM^VCl4MPR6!-k90+KJx1Tl8ClWA%89#g>|q){M7rs zz#1eBN&n<6p=JFQDC2O@{=}Kqk${I~Vi^h2c-_`ceHy&{7RMC`I)-~6UMF3$M9WUu ztu?o`N$mF(R_Ghq!qGYlJwp{>43(>_U|pnd_;22b5ar=vun!?BLd4K_rkWgMwBBc& zge+S!lEXousnr6`_BIcivllChHp-}7DWcUev_049L02|S=69<82+@W-U| z#69l;ggZg7U+{BD$c&mI^&3h*?kqr%q3a0PEa8~EgiWzloCwwzM^fW=1ZMM{eS5cyx zaE*4I76h*QDAfVfrBdidCl7O;ys4T>H~(!0FrrpB0yu@(sZb8zxFLEcq*#G*O^N5# zps%aUrJl+UHJP0uKc&!I-j})0p1&sF?!p!*dcFq(ozs8vN!` zX%eQBX|PA&zlMP6^+KDw?JC4VLsSxFHx5p|2ZER#Dw0l9s@1QFwa(71e?Rt_{U|J8 zlUtIO_DguMl#-E>g)~qq)G1^5Gf&$ZYO3Rr1(loV#qnNW+Vi-hBCuBd)9z3e;;S=C ziA@^c{x7%9by2|zQ4LN`SL5|ne#A!2dd+|p_y_M5pEtS|GaV`a{zvk51P(%PZ~H4# zt*ANp|0|4h{g*I~%=4ew2}wsg7kd&8uK%x0&huZu5tKU>dj^apwN(*}0rJ1bE>dk~ zz}Q;}mB4(wKzaTRWl#Ym?41AIcfd?#+;)Q*rTgrgdy!wlk$wCa!N!pOESL=)2{ae9 zy16M>1BBHt!~5e2N?Q|52<{DXi=!##MY51B3v0^$Z3IxTewqbJm8zm*v@#y^(n%{F z@jf92DAWG3n3A{%tkk}vebm{DIG;O_Q8+*3DJ8kqJ7ueL(wS#fW9JGihGn3B$R1ba>b z|M7QD;lnH?q&4cU4G#jc1Z{1lATOa6VY0iIp zjP{D;H`mg$J&x$pkUIWgqw>dk)YG+hKy@RV>G}AlB;ABmaV@@xh`iANeR%@a1I8NV z0xhcyxOHRl9tUi2iKx@I{ZKD{%xJNjseBE{Ti5q13$mn<8svtdZHudH^Ode=X|$#O z5bQyBg*quI81MQ!BbfY;q=ec>X*{~9c2gknG4Ht_gY7c_A91hs$P7UWp@jbQA?h6r z=eKEE@3tr7g5+N~XH7Ez#Q$uDAT?|PjJTC-25biul;wYWP@r+K{vRF`EUYZ7T&XuZ z|4b;@SpOXe3c@)#|JVGEdsg%#q*B(#ydV7jC6Tkeo0}UfQa?1#CN6zjXQ!1tylsB~ zR47P)wxLMCo7u#gMefyCHgx2;9D|{^o0Rc1|3G1k$;c6Pl(G1cQK3xJGI*Ax7Z`<8q3|PAmV{3&d>t z9Qf+Xi%0sWGj!NSpkCFK9}^MxEbBaFT_ut*! zey}DtGY98-jC>0)cdfu`kiR6Faglsu1lN+|AeeaqCs*@Yab=(x8p|~REjs~2ACWLN z%8tCDg$$W{Y5`$00uRkkn^fcx#ktPkS(%@O3B{`@QGZR0Igco_-c z1)rKExXAWH`mv0Z0s?Qvhq427N1?&5qEAAA@TPqk!8AF!c;7*HfLCAmmDoW6M1(ML zsG8s)+jQ@pf|_jDR@8OhA}gE!5OXwqq8?pj6cbKT5?)-0AQ@^F2~AU*U4XHAb-FPv z_hwq1?VRlHd=NL(xiYst7a}-uQEMp$a#7baluOA|hjZ*&oRwiIF%Kq6aNg?pB<@>+$YwrYgkP(aT2pl%;NTlWCi z@N7auTN@~-v;g{Q!njZT4|#-!=g95XE8`2;Sqm?GAy<$MVxcc@+#dO~_QJsI6=3Si znx(R%rl_cecYmAms}M+vv%iOMXLGs(N#ki-135qE*8|yVMc)33E`)3Pd?Wa}O?IoZ zhq(T7*=+TCor(YRl>^$*iycIC-CM6luuX*xk@t3$hhOK=nBM(i{Po3u33R-FW!?%E zy!Rr#ehI`!WoG}$_3Y?H_yq2Sy{!0Zdl|NoU4jp zXy#xK(fjYC0V3`owYWP-KIW8(Y(XlYi3@teu>0s<4EDh5WIn!kS%YY#17We~eHAyz zH@z>QU$S<-C0~@jAeC!E_ma_7M_;0@Am2_5p0Sp14aOi1n_sbe2$x?Co>N9I|GmaO zd!JjttB}41TE$|%NLDg0Hag##9(1Wvfn8my6@U~#_QQNf?s*8nJl}o(ckp8S@9GZG zmv~I;#DFW;kU$r#p5db7zn*VTqU6CnpMh z39xwNjrWz?N0d({h~z>_AVFiZinw^==X?7Jy)N4N{gFlqo4fNSzZ}bG+XG?DlM_j! zCMuNSy!>M2hK5W?eVTRDau^39#ix{!ed?dBwjVfKA_=o$wpRhr+mk-{JJ*v^RmxQC zRv`TF{h+#a9Mw(e%b{8)aj^M`aEVU<3_v@vs=C3&vkMPohkO^mx}8r$+#TlM8hegE zjPoz@5WjH4@U4JgB*mN@SOb+2SXJwOAu?ZMbX_-Br31m!X^?=pQu^zt9eJShd(LrR z&)Dkg%|Zq(nnGX7X@tqAsGGV}M*u-k`UV2*yk3a3@Ve0|Ot+@qVsIj4i2< zhaR`+%@KN_(2D-cwX(0b52a{=<8~)`E*Hr2gF8{zok=w9fajWW)>r-THk!uNx^8NJ zwG+)s6xIbAxE5 zK$72kidF@T&$NcFC8%~HqK>oRM`+v~?a%95GfqKrEAup3Zj^6Lj6_VH!pTE^34ghSN!YLuw}#`7%OQ+|)oA z$`&SF=Gb!DL3CaEb`L&3Nb>2ukI{YKMJIzCw_L+lTjpX~@yYnIMY(W?6YH08Zmhb1 zr}*+(fCpW!^47P6`dfjnLV#N`t-mY|-Qeir2MT6>+3#=D!_c`!(Vj4@ljq{A4&+ZH z6JvQYC+C87p_Xw8y$GVo_RQ?LDE&UU%%l;!=(F-CFz+^{>f$ilSY!syloeOXkm79u zwjol5PYXrof8@k{pF9O3D%%O9O4zfpYNPvIzCc`Dd6gEjzB(c78vzPDavEoCAzOkp zsburDzO5Hie9telqXzLq^bg*` z@CR8~LCQ7z^-h`A$%6-ft2lAaCGgH-Pq$&ohnVksV~)+^`}2z}nk9nBxI9Y59g_nR z%+q>Fto<pVf!E?mUX{NLo?bHb&T<^R+(nSk|f91GVo@5`SZaO6EdHX;bLj$I#^vJHiI484{|2{KzcA0p9`L#DhH@IaZ( za(=aT9{HZj`>dmLeSf$TOQy{JPK$@e+E|Ihn`ueQ0 z5pFOvIz+!T6vDeGv+mbIVMx#=6R^_7z z1OXgY?lQTwMmDIn9MS|SOb=0xCstp^ve@j}c)iHhNBkiS9Gvr!!|tswD7tJF7zT!LK8F9nRYHXah`$7l))3I2c|K z&Y{sy+#X@a`49zVSoTPPHj&H-};sSz` zX2vvcll|tD8Q(T>z01@jD-#~zgzXMlO9xk#!na9n?@Ia_JGsKZaMoiMZ-0@SZHeS$ zN9Mx9EBeP`>J3H==~+tL?#1v<{yENe2%lz~J14F`rdCt- zHIJbh_)ut#KY=$+Ys*HS;k$ZR1qKxN*||l3u)?r8aX3QgiA`9b^p#N;u~2K8wS;L^HEzM3k*pLc7>H7Jd1Xt7 zzjk(GIVh}vx+X%<K#|@ATeiwkHhaHIWzs@ zW^#VjB~z13SO4%bc>+~5qS(H3pNS}WepSFlJC8nI(Ig#jGdqy$6k0(5?QT9%en(_2pho^88j z&da>$RyWLF@x68_15PbS3h<1=s$fhkC>N)?L`eHLa<}9#$4FuS80o2^=O1akZ zOC|u0j0-*}({pKjO`q6~6JoRY6%3E+i612b1pM&Cl_6qoM5K{4eoZ(%jD$c}m-m4^ zTzBk1)BAPMx#x&K({F5wI$Ro*KcH!)HQypHggED-EjplxsE@@>sS2Uz3pW!N2PAD~ z?+ln>^Am_HojmNzfxAhtJX+b1j|}v815OJ4Xjj6*u0R-Hl?T5-VKZxl_u|biZH)P%F@UCT?+em zj!yAGpEYiqJj$MQ;^Xle(V#y8hO*U7)({YvN%E`P!zY2wVSM8vH7Ax`hlO>ks^N`* zJ^MYF>S*Wg3nc3F$m`udpIrEx;nLIM73Vn+@4sND%>50ZaNC(H8TrvcQj7J_R!wpr zgBB4KG)}wPGK8(%0U&qt^pS`v5W4&f5T&|1NoADqX`887SxnE|&cQ2DPqvBWOXYmm zlLn=@Buyz$7&T?w7Waq%gs5E!4#jYlTLcR<s@o;x@7Wkrzi`KMV#0Q#RsDgp0n(%+Lhrq(U!Uy07a^JDEJ zE$EyThbrm4bJ->$uXuScX610$qvu#vPy73uW9o6%t)?wK=?+U34cw6J#?>{(Jg&Q_ zWWoFY7NKn_M(4;hP-rbcDr`vx%VGOPk=pZei}DP#Up+l2O%Dv42473Ov#S#-O^z7r z0P#I0-)maYsi`pZ8)EUC?{4R;`Y-uD&e+7k4G-US>QTHbsoUJ-C$=0o?=XzQ3n2y& z=>DV%lDHioj~>YTyNRad+RfBxike=Iqrelq%|HjT(A~NsnJqbflW0xX(fW0Lsq#$yGjurX71S(O9yn-Lvj^{_?rBc8d>Z(PRv{d8`W*>Ad~)AX z2G&$Vki#_MT=N}?Ak&r#FHDu6AwxR)uMFpXp)1wwQN?1XJ#cFX5z+2npRE{?=E z!4!Lf+qnj+xgkwP1Fez%o4Lw?C^o0@n_$uYOcRwg|I61szl3}d0hyZ;ihzNL5ui~U zA+FK66NXnUwnK%|cvjYL51EB7my$L+WAdc^n}&L_1b5-7ngSH(@Y$cfLI2~Wd=1ZS zo)ewm?`EedDXo{eZpi5Ia|S`h|*tdNXZ>{1i^K_nZ`0vZ?-UexM{3 z@r5f+Rmvhu^oT-_5}pSf12emHe+!66NnvF4-x#f=U&*Z0U)3tjPry4;->}XWb4Be=!NO8-42(v?aR0A)pCZX zPFh-H3(4G-5(@Au0SeJse78ckt@V2-e#7lNeR6x9i=SE6reA8qe}0=s)MX}oU z#VO+VYftJzCPJWsQRaJe=+#mvv2uB3V$HvV^Q&*#EDnmCEGbrNPD(~1gY3rFCcEd3 zs$+gGI~0b+(ycJ95=j8{xWnK3vy`fv2~Xkvg@6wa*72$1X>?3J$By>m%_g>o(JPfZ zeUFgI-MH4yid3xoChAK?J!MsOpLw|T&&1bvfyZ2kd@=<+v{}8pF%uDLbm{>49Erx# z{z|%j-2L>>rEtzJ-eSq5wdh7^d#7vK$Zb5yP(F$#v(tC3YB%8K!R>Iuc_?^j9m%yJ z_{_sr?5qx%ft1;#Oo^j+T!X*_6RM%Sjn2V@c_Y?0&w_A;mtyoi_^bb`~6MnOUk z@z?yBMhl{oH52ggkJ4p(WLM$$u5Lz~l`*xzWM6>z#saM~}$rsqXpq?5)P~Rp^ci_si3uL zuYd9${Q#`KZNi+fya>OhM?BaxGX;>)L8ZAx@& zj>R6Bw&F&?ZnxyA*g+6WQ(vxV5aYyg!<&hh87A_?pTF6bQiI@BGNNN0^n(pYwh?6_ z{WP5jIJqeI`_6I$Ej~oAJkjQhlPq>zSLlqx7zRKIBE0&$Pbs2@1)8IDYgrxQ{>8gc zjo7Awh_PvpU~lXK#wiqbl4d%&uY1_`yKaHat{_8u`d1 zm+cTkf*5Ys;ev(Jv^|$yC9RQ9<8yxF!{{v`Z(CTB<*56&g!V06!|0V*f+@o;m!W(G zre@4MG6D><$I`06uG<}#uxhcZMF(r+&Bi>P{lsC2z*=7NS!__j>nh?~T5)Chc5)s! zU)n--VeNst*{5x{LsACwT$Nf}RH$}$5YSanh?sbSlTzms0S_x^eu2Lu!UCaMX@#kwyOAJ^F4AYXA2Fw25p*ErQAv%r z5Z8xOpS$*IOAAlLbk*Y)cyiox^lEV4RsBXX8|b+`HM&`0Cb_dbwZ0=<%e0Ox*+jrUEg_v$zK;*x`}X;f8gHitrXJN^Zxp%i{Yok z4St2*x?{~wonF!oYcCAWf88HzoFwFws2?BknBu^kGMfALo|cfjAZ%DFnp~P{@GpA~ zm8!i_x4uys9^899mB6W!)XmFVV9p^B)r^-ztER%ADBY8eXb3Mfm z_z?Z`pzQfeyTmovXNnxtPbkskw@4Um9V#_Uw|;wB&J$;VG@L+-C-M$xOjBiMF5uU@ zT=zUT!ZiqIo_b44**8w|O)quL^PBMY@PmS)D>B&#&=tH7Nphz()5xY@F$ifk1~SSW zF5X+&mwc0A8p9_5Uv7w}B{^w3XPTXLfYfAs5?eIXC<+vHL4q(ss)feYmcFC6y!8$W znzzl7#;N*#;kGl1RMr64_jp<%(J>q>GvmZTo75GuDz3h%-+_ww^IU~+WD`vx==_o< zV{ogBII^-O8|%@MyGw98K!My*mehbz(5X=9A4d126=5BJkwEP!H5M}JX6(OkSP2+Gp!ia}gdBH8`nm{sFraL0N)hbUyJbhaplZE4j4 zi;ol?ifeQm2$;|4ff>KywbaChPfaz};MLqsn$ggco9HAwmGGl_G88!sC1$FXd`Xek zpUg3?tP*JaDbwz*5H~JGO;v-~j<)Csy~8AMWHPFwMHOg7<$q{|XzPqnp}b}8>;#+6 zN4Gf^o-`tLP-N=3VI@SK`-v-A)8Y2wh%Ppn68q$j75pzuuYP4f!@=qv$-{XQf{XaX zWQ89~aF^NqZP`ilmlp|#m&xNlNO<{=kq~8>3r^e`ao}X~?lrJm=S>{qnWWT<5OJvp z(pRh{XO|2#QhzpL$dw+H?`79iq23HlQ+}U&QQ}C%Da6v^BT#qZuLdI^MK(i3W$%^E zA>vU9ej<0dRi?G8ociLk@YqCl+l9qUqd;}zn~JboExdlUIW(nb1}VxQeIk{TD;(u< zzwB0@tc~n{*jRa7>C%!I_@lKrq#)7hgKlk`@`yTl>wgCUk>fqCrl$)2yxCa%q7c(5z;z)}4hVnV^cgHAckxup;h9z~v7w;NaZ0x)4M92Qz zrtng0xnJO}9~?r`+sGlE^L&&RR^ucU=0CvTrwz+OWUJkPFar&74s@a+++Bt|pb@od zoqes6W`FPXWxSe;<`UPO)+d42vy^8p#@^4nrrP^1g%yG=x~R7pu~+7LVE^;iHReN} zc8Xsi#Jh)v{Gk=7)wkp|Fkpf9}hhuaX-+@e|Myx%xS)*uOt1{ zgntm_Q^8C;OpuQc)!1k;|5P#oT~nm|4K>D&c-Hyh{zA6(04K^amh9JxwQXEdEQpG% z=uHfSCVui)F$hrl21@eWem8E1DlA~h_guQ>IbbP<7@SI1D^L=FL5=f*QVB# zqNeObIQiZo7HWnsDb7Nxu84_^Q>NE4F@IE~o>U(D#*l6{f3_+;x{!EJ&U%w);hEC7 zp-e_JeFwWm#)->}Nt>{K0nx*8P8!N`3zuPs`1K=v-1bXE8lJ5vM9th5S=iv_hwtsTJ zzJ?h8soq82z^R?E*7g>&_#s|g|J?h%oWYBtTdWbR8tv%zy_cJvSecCySuz}o)h_$7 zgmHngAxAdn(fVYSSS&v@)mAo|(?(uNx%-)0PAmRib`z%Ex6dEe54T41awBURfElwX zAm$*#>j{mBf&k_qRkrO5NhGmLgMShf9z#9yz>!m-R*BM!1^tDSXg8RXayeU^=}(}r zcao{+*7Fc_uyk6OoGgYMC%tU&m`n2Yl16r~uOoOqPQvcpiKTS$fGfY^9;F1LQ$+-~ zywq|_rqN3~U;y$MTH_6;`949`FzAU1)g6Vx7vuV<&M4J6b)`KQ>lZ)&Y=3rsHIaNb z8rf%Ryc>MHgq2IL%f~d2U!GjtEFJ5JABojz$(_&S>Qa>4lIcuo2#B6tfQA@yTkvG*qRx zMHUY@*CcOQmk=QR&B%-tJbw^mb{GE4+3nu&J(x9@NDg3n^j>ls6HQL2%I`GAnPMOn zzQ5`6!NYpRbwaT2G96Ro!@2y|%+5G{nm{2F&HA%BEvfgUm+_0!i~(Ea((ZOEAAG8N zHl3iM#j*+^7Tzs#h-O==*NE=Po9!lPI94_oYrHPJMXs;+c>bP z=^b00sM)yjsf}?*Y}2n9p#^^)k|$5BZsdEUJx(mKf)C?GS9iwN_~9b?Y0H#0=sG%j zEHK%1r5MI7Wf*3EaDVpKuPQgUyAAcMV=4C10gL4zez(n_3b5oPG$A1%W74>qTR&yt zeQ2J~0C%hAS^aUgno}E5JG4cfO(X(L0dzhA&Q;lj{cN2TY;2{hc$9}=CGqblCbLhQH